#include <point_cloud_publisher.h>
|
void | add_pointcloud (sensor_msgs::PointCloud2 &c1, sensor_msgs::PointCloud2 c2) |
|
void | copy_pointcloud (sensor_msgs::PointCloud2 &c1, sensor_msgs::PointCloud2 c2) |
|
virtual void | handle_scan (sensor_msgs::LaserScanPtr msg, uint16_t layer_idx, int layer_inclination, bool apply_correction) |
|
void | project_laser (sensor_msgs::PointCloud2 &c, sensor_msgs::LaserScanPtr msg, const int layer_inclination) |
|
void | publish_scan (sensor_msgs::LaserScanPtr msg, uint16_t idx) |
|
void | publish_static_transform (const std::string &parent, const std::string &child, int inclination_angle) |
|
virtual void | resetCurrentScans () |
|
Definition at line 10 of file point_cloud_publisher.h.
◆ PointcloudPublisher()
PointcloudPublisher::PointcloudPublisher |
( |
std::shared_ptr< ScanConfig > |
config, |
|
|
std::shared_ptr< ScanParameters > |
params, |
|
|
const std::string & |
scan_topic, |
|
|
const std::string & |
frame_id, |
|
|
const uint16_t |
num_layers, |
|
|
const std::string & |
part |
|
) |
| |
◆ add_pointcloud()
void PointcloudPublisher::add_pointcloud |
( |
sensor_msgs::PointCloud2 & |
c1, |
|
|
sensor_msgs::PointCloud2 |
c2 |
|
) |
| |
|
private |
◆ copy_pointcloud()
void PointcloudPublisher::copy_pointcloud |
( |
sensor_msgs::PointCloud2 & |
c1, |
|
|
sensor_msgs::PointCloud2 |
c2 |
|
) |
| |
|
private |
◆ handle_scan()
void PointcloudPublisher::handle_scan |
( |
sensor_msgs::LaserScanPtr |
msg, |
|
|
uint16_t |
layer_idx, |
|
|
int |
layer_inclination, |
|
|
bool |
apply_correction |
|
) |
| |
|
privatevirtual |
◆ project_laser()
void PointcloudPublisher::project_laser |
( |
sensor_msgs::PointCloud2 & |
c, |
|
|
sensor_msgs::LaserScanPtr |
msg, |
|
|
const int |
layer_inclination |
|
) |
| |
|
private |
◆ publish_scan()
void PointcloudPublisher::publish_scan |
( |
sensor_msgs::LaserScanPtr |
msg, |
|
|
uint16_t |
idx |
|
) |
| |
|
private |
◆ publish_static_transform()
void PointcloudPublisher::publish_static_transform |
( |
const std::string & |
parent, |
|
|
const std::string & |
child, |
|
|
int |
inclination_angle |
|
) |
| |
|
private |
◆ resetCurrentScans()
void PointcloudPublisher::resetCurrentScans |
( |
| ) |
|
|
privatevirtual |
◆ angles_
std::vector<int> PointcloudPublisher::angles_ |
|
private |
◆ cloud_
sensor_msgs::PointCloud2Ptr PointcloudPublisher::cloud_ |
|
private |
◆ correction_params_
std::map<int, std::vector<double> > PointcloudPublisher::correction_params_ |
|
private |
◆ frame_ids_
std::vector<std::string> PointcloudPublisher::frame_ids_ |
|
private |
◆ layer_prev_
int16_t PointcloudPublisher::layer_prev_ |
|
private |
◆ pcl_publisher_
◆ projector_
◆ scan_publishers_
◆ static_broadcaster_
◆ tfListener_
The documentation for this class was generated from the following files: