Skip to content

Commit

Permalink
Make laser_geometry build for ros2 (on windows 10)
Browse files Browse the repository at this point in the history
  • Loading branch information
bfjelds committed Jan 9, 2018
1 parent c9cbfc6 commit d39ce22
Show file tree
Hide file tree
Showing 5 changed files with 141 additions and 280 deletions.
68 changes: 36 additions & 32 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,47 +1,51 @@
cmake_minimum_required(VERSION 2.8.3)
project(laser_geometry)
cmake_minimum_required(VERSION 3.5)

find_package(catkin REQUIRED
COMPONENTS
angles
cmake_modules
roscpp
sensor_msgs
tf
tf2
)
project(laser_geometry)

find_package(Boost REQUIRED COMPONENTS system thread)
find_package(ament_cmake REQUIRED)

find_package(Eigen REQUIRED)
find_package(angles REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(ecl_eigen REQUIRED)

catkin_python_setup()
# TODO(dhood): enable python support once ported to ROS 2
# catkin_python_setup()

catkin_package(
INCLUDE_DIRS include
LIBRARIES laser_geometry
DEPENDS Boost Eigen
)
#
#catkin_package(
# INCLUDE_DIRS include
# LIBRARIES laser_geometry
# DEPENDS Boost Eigen
#)
#

include_directories(include
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${Eigen_INCLUDE_DIRS}
${angles_INCLUDE_DIRS}
${rclcpp_INCLUDE_DIRS}
${sensor_msgs_INCLUDE_DIRS}
${tf2_INCLUDE_DIRS}
${tf2_eigen_INCLUDE_DIRS}
$ENV{BOOST_ROOT}
)

add_library(laser_geometry src/laser_geometry.cpp)
target_link_libraries(laser_geometry ${Boost_LIBRARIES} ${tf_LIBRARIES})

if(CATKIN_ENABLE_TESTING)
catkin_add_gtest(projection_test test/projection_test.cpp)
target_link_libraries(projection_test laser_geometry)
target_link_libraries(laser_geometry
${angles_LIBRARIES}
${rclcpp_LIBRARIES}
${sensor_msgs_LIBRARIES}
${tf2_LIBRARIES}
${tf2_eigen_LIBRARIES}
)

catkin_add_nosetests(test/projection_test.py)
endif()
ament_export_include_directories(include)
ament_export_libraries(laser_geometry)
ament_package()

install(TARGETS laser_geometry
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib)
install(DIRECTORY include/laser_geometry/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
DESTINATION include/${PROJECT_NAME}/
FILES_MATCHING PATTERN "*.h")
111 changes: 37 additions & 74 deletions include/laser_geometry/laser_geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,15 +37,19 @@
#include "boost/numeric/ublas/matrix.hpp"
#include "boost/thread/mutex.hpp"

#include <tf/tf.h>
#include <tf2/buffer_core.h>
#include "sensor_msgs/msg/Laser_Scan.hpp"
#include "sensor_msgs/msg/Point_Cloud.hpp"
#include <sensor_msgs/msg/Point_Cloud2.hpp>

#include "sensor_msgs/LaserScan.h"
#include "sensor_msgs/PointCloud.h"
#include "sensor_msgs/PointCloud.h"
#ifndef ROS_DEBUG
#define ROS_DEBUG(...)
#endif // !ROS_DEBUG
#ifndef ROS_ASSERT
#define ROS_ASSERT(...)
#endif // !ROS_ASSERT

#include <Eigen/Core>
#include <sensor_msgs/PointCloud2.h>

namespace laser_geometry
{
Expand Down Expand Up @@ -106,7 +110,7 @@ namespace laser_geometry
//! Destructor to deallocate stored unit vectors
~LaserProjection();

//! Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud
//! Project a sensor_msgs::msg::LaserScan into a sensor_msgs::msg::PointCloud
/*!
* Project a single laser scan from a linear array into a 3D
* point cloud. The generated cloud will be in the same frame
Expand All @@ -122,15 +126,15 @@ namespace laser_geometry
* channel_option::Intensity, channel_option::Index,
* channel_option::Distance, channel_option::Timestamp.
*/
void projectLaser (const sensor_msgs::LaserScan& scan_in,
sensor_msgs::PointCloud& cloud_out,
void projectLaser (const sensor_msgs::msg::LaserScan& scan_in,
sensor_msgs::msg::PointCloud& cloud_out,
double range_cutoff = -1.0,
int channel_options = channel_option::Default)
{
return projectLaser_ (scan_in, cloud_out, range_cutoff, false, channel_options);
}

//! Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2
//! Project a sensor_msgs::msg::LaserScan into a sensor_msgs::msg::PointCloud2
/*!
* Project a single laser scan from a linear array into a 3D
* point cloud. The generated cloud will be in the same frame
Expand All @@ -146,16 +150,15 @@ namespace laser_geometry
* channel_option::Intensity, channel_option::Index,
* channel_option::Distance, channel_option::Timestamp.
*/
void projectLaser (const sensor_msgs::LaserScan& scan_in,
sensor_msgs::PointCloud2 &cloud_out,
void projectLaser (const sensor_msgs::msg::LaserScan& scan_in,
sensor_msgs::msg::PointCloud2 &cloud_out,
double range_cutoff = -1.0,
int channel_options = channel_option::Default)
{
projectLaser_(scan_in, cloud_out, range_cutoff, channel_options);
}


//! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame
//! Transform a sensor_msgs::msg::LaserScan into a sensor_msgs::msg::PointCloud in target frame
/*!
* Transform a single laser scan from a linear array into a 3D
* point cloud, accounting for movement of the laser over the
Expand All @@ -177,16 +180,16 @@ namespace laser_geometry
* channel_option::Distance, channel_option::Timestamp.
*/
void transformLaserScanToPointCloud (const std::string& target_frame,
const sensor_msgs::LaserScan& scan_in,
sensor_msgs::PointCloud& cloud_out,
tf::Transformer& tf,
const sensor_msgs::msg::LaserScan& scan_in,
sensor_msgs::msg::PointCloud& cloud_out,
tf2::BufferCore &tf,
double range_cutoff,
int channel_options = channel_option::Default)
{
return transformLaserScanToPointCloud_ (target_frame, cloud_out, scan_in, tf, range_cutoff, channel_options);
}

//! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame
//! Transform a sensor_msgs::msg::LaserScan into a sensor_msgs::msg::PointCloud in target frame
/*!
* Transform a single laser scan from a linear array into a 3D
* point cloud, accounting for movement of the laser over the
Expand All @@ -206,47 +209,15 @@ namespace laser_geometry
* channel_option::Distance, channel_option::Timestamp.
*/
void transformLaserScanToPointCloud (const std::string& target_frame,
const sensor_msgs::LaserScan& scan_in,
sensor_msgs::PointCloud& cloud_out,
tf::Transformer& tf,
const sensor_msgs::msg::LaserScan& scan_in,
sensor_msgs::msg::PointCloud& cloud_out,
tf2::BufferCore &tf,
int channel_options = channel_option::Default)
{
return transformLaserScanToPointCloud_ (target_frame, cloud_out, scan_in, tf, -1.0, channel_options);
}

//! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame
/*!
* Transform a single laser scan from a linear array into a 3D
* point cloud, accounting for movement of the laser over the
* course of the scan. In order for this transform to be
* meaningful at a single point in time, the target_frame must
* be a fixed reference frame. See the tf documentation for
* more information on fixed frames.
*
* \param target_frame The frame of the resulting point cloud
* \param scan_in The input laser scan
* \param cloud_out The output point cloud
* \param tf a tf::Transformer object to use to perform the
* transform
* \param range_cutoff An additional range cutoff which can be
* applied to discard everything above it.
* Defaults to -1.0, which means the laser scan max range.
* \param channel_option An OR'd set of channels to include.
* Options include: channel_option::Default,
* channel_option::Intensity, channel_option::Index,
* channel_option::Distance, channel_option::Timestamp.
*/
void transformLaserScanToPointCloud(const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
tf::Transformer &tf,
double range_cutoff = -1.0,
int channel_options = channel_option::Default)
{
transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
}

//! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame
//! Transform a sensor_msgs::msg::LaserScan into a sensor_msgs::msg::PointCloud2 in target frame
/*!
* Transform a single laser scan from a linear array into a 3D
* point cloud, accounting for movement of the laser over the
Expand All @@ -269,8 +240,8 @@ namespace laser_geometry
* channel_option::Distance, channel_option::Timestamp.
*/
void transformLaserScanToPointCloud(const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
const sensor_msgs::msg::LaserScan &scan_in,
sensor_msgs::msg::PointCloud2 &cloud_out,
tf2::BufferCore &tf,
double range_cutoff = -1.0,
int channel_options = channel_option::Default)
Expand All @@ -294,46 +265,38 @@ namespace laser_geometry
private:

//! Internal hidden representation of projectLaser
void projectLaser_ (const sensor_msgs::LaserScan& scan_in,
sensor_msgs::PointCloud& cloud_out,
void projectLaser_ (const sensor_msgs::msg::LaserScan& scan_in,
sensor_msgs::msg::PointCloud& cloud_out,
double range_cutoff,
bool preservative,
int channel_options);

//! Internal hidden representation of projectLaser
void projectLaser_ (const sensor_msgs::LaserScan& scan_in,
sensor_msgs::PointCloud2 &cloud_out,
void projectLaser_ (const sensor_msgs::msg::LaserScan& scan_in,
sensor_msgs::msg::PointCloud2 &cloud_out,
double range_cutoff,
int channel_options);

//! Internal hidden representation of transformLaserScanToPointCloud
void transformLaserScanToPointCloud_ (const std::string& target_frame,
sensor_msgs::PointCloud& cloud_out,
const sensor_msgs::LaserScan& scan_in,
tf::Transformer & tf,
double range_cutoff,
int channel_options);

//! Internal hidden representation of transformLaserScanToPointCloud2
void transformLaserScanToPointCloud_ (const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
tf::Transformer &tf,
sensor_msgs::msg::PointCloud& cloud_out,
const sensor_msgs::msg::LaserScan& scan_in,
tf2::BufferCore &tf,
double range_cutoff,
int channel_options);

//! Internal hidden representation of transformLaserScanToPointCloud2
void transformLaserScanToPointCloud_ (const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
const sensor_msgs::msg::LaserScan &scan_in,
sensor_msgs::msg::PointCloud2 &cloud_out,
tf2::BufferCore &tf,
double range_cutoff,
int channel_options);

//! Function used by the several forms of transformLaserScanToPointCloud_
void transformLaserScanToPointCloud_ (const std::string &target_frame,
const sensor_msgs::LaserScan &scan_in,
sensor_msgs::PointCloud2 &cloud_out,
const sensor_msgs::msg::LaserScan &scan_in,
sensor_msgs::msg::PointCloud2 &cloud_out,
tf2::Quaternion quat_start,
tf2::Vector3 origin_start,
tf2::Quaternion quat_end,
Expand Down
32 changes: 17 additions & 15 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
<package>
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>laser_geometry</name>
<version>1.6.4</version>
<description>
Expand All @@ -16,23 +18,23 @@

<url>http://ros.org/wiki/laser_geometry</url>

<buildtool_depend version_gte="0.5.68">catkin</buildtool_depend>
<buildtool_depend>ament_cmake</buildtool_depend>

<build_depend>angles</build_depend>
<build_depend>boost</build_depend>
<build_depend>cmake_modules</build_depend>
<build_depend>eigen</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>ecl_eigen</build_depend>
<build_depend>rclcpp</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>tf</build_depend>
<build_depend>tf2</build_depend>

<run_depend>angles</run_depend>
<run_depend>boost</run_depend>
<run_depend>eigen</run_depend>
<run_depend>python-numpy</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>tf</run_depend>
<exec_depend>angles</exec_depend>
<exec_depend>ecl_eigen</exec_depend>
<exec_depend>rclcpp</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>tf2</exec_depend>

<test_depend>rosunit</test_depend>
<exec_depend>ament_cmake</exec_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit d39ce22

Please sign in to comment.