Make it compile, remove PointCloud support, and remove boost
- Compiles on Windows with VS2015/VS2017 - Compiles on Mac with clang - Compiles on Linux with gcc - Removed PointCloud support as this is deprecated and might not be needed in ROS 2 - Remove boost as per ROS 2 development guidelines
This commit is contained in:
committed by
Martin Idel
parent
7ad6e21d3d
commit
8fb9c51bf8
@@ -34,13 +34,9 @@
|
||||
#include <iostream>
|
||||
#include <sstream>
|
||||
|
||||
#include "boost/numeric/ublas/matrix.hpp"
|
||||
#include "boost/thread/mutex.hpp"
|
||||
|
||||
#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 "tf2/buffer_core.h"
|
||||
#include "sensor_msgs/msg/laser_scan.hpp"
|
||||
#include "sensor_msgs/msg/point_cloud2.hpp"
|
||||
|
||||
#ifndef ROS_DEBUG
|
||||
#define ROS_DEBUG(...)
|
||||
@@ -107,33 +103,6 @@ namespace laser_geometry
|
||||
|
||||
LaserProjection() : angle_min_(0), angle_max_(0) {}
|
||||
|
||||
//! Destructor to deallocate stored unit vectors
|
||||
~LaserProjection();
|
||||
|
||||
//! 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
|
||||
* as the original laser scan.
|
||||
*
|
||||
* \param scan_in The input laser scan
|
||||
* \param cloud_out The output point cloud
|
||||
* \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 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::msg::LaserScan into a sensor_msgs::msg::PointCloud2
|
||||
/*!
|
||||
* Project a single laser scan from a linear array into a 3D
|
||||
@@ -158,65 +127,6 @@ namespace laser_geometry
|
||||
projectLaser_(scan_in, cloud_out, range_cutoff, channel_options);
|
||||
}
|
||||
|
||||
//! 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
|
||||
* 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.
|
||||
* \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::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::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
|
||||
* 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 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::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::msg::LaserScan into a sensor_msgs::msg::PointCloud2 in target frame
|
||||
/*!
|
||||
* Transform a single laser scan from a linear array into a 3D
|
||||
@@ -249,42 +159,14 @@ namespace laser_geometry
|
||||
transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
//! Internal protected representation of getUnitVectors
|
||||
/*!
|
||||
* This function should not be used by external users, however,
|
||||
* it is left protected so that test code can evaluate it
|
||||
* appropriately.
|
||||
*/
|
||||
const boost::numeric::ublas::matrix<double>& getUnitVectors_(double angle_min,
|
||||
double angle_max,
|
||||
double angle_increment,
|
||||
unsigned int length);
|
||||
|
||||
private:
|
||||
|
||||
//! Internal hidden representation of projectLaser
|
||||
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::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::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::msg::LaserScan &scan_in,
|
||||
@@ -305,11 +187,9 @@ namespace laser_geometry
|
||||
int channel_options);
|
||||
|
||||
//! Internal map of pointers to stored values
|
||||
std::map<std::string,boost::numeric::ublas::matrix<double>* > unit_vector_map_;
|
||||
float angle_min_;
|
||||
float angle_max_;
|
||||
Eigen::ArrayXXd co_sine_map_;
|
||||
boost::mutex guv_mutex_;
|
||||
};
|
||||
|
||||
}
|
||||
Reference in New Issue
Block a user