|
const boost::numeric::ublas::matrix< double > & | getUnitVectors (double angle_min, double angle_max, double angle_increment, unsigned int length) |
|
| LaserProjection () |
|
void | projectLaser (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default) |
| Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud. More...
|
|
void | projectLaser (const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default) |
| Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2. More...
|
|
void | transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default) |
| Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame. More...
|
|
void | transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, int channel_options=channel_option::Default) |
| Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame. More...
|
|
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) |
| Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame. More...
|
|
void | transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, tf2::BufferCore &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default) |
| Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame. More...
|
|
void | transformLaserScanToPointCloud (const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud2 &cloud_out, const std::string &fixed_frame, tf2::BufferCore &tf, double range_cutoff=-1.0, int channel_options=channel_option::Default) |
| Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame. More...
|
|
| ~LaserProjection () |
| Destructor to deallocate stored unit vectors. More...
|
|
Definition at line 77 of file projection_test.cpp.