39 #ifndef VELODYNE_POINTCLOUD_CONVERT_H 40 #define VELODYNE_POINTCLOUD_CONVERT_H 48 #include <sensor_msgs/PointCloud2.h> 51 #include <dynamic_reconfigure/server.h> 52 #include <velodyne_pointcloud/CloudNodeConfig.h> 63 void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level);
64 void processScan(
const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg);
99 #endif // VELODYNE_POINTCLOUD_CONVERT_H Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
boost::shared_ptr< diagnostic_updater::TopicDiagnostic > diag_topic_
boost::shared_ptr< velodyne_rawdata::DataContainerBase > container_ptr_
boost::mutex reconfigure_mtx_
double max_range
maximum range to publish
std::string target_frame
target frame
void callback(velodyne_pointcloud::CloudNodeConfig &config, uint32_t level)
void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
Callback for raw scan messages.
bool organize_cloud
enable/disable organized cloud structure
uint16_t num_lasers
number of lasers
double min_range
minimum range to publish
Convert(ros::NodeHandle node, ros::NodeHandle private_nh)
Constructor.
diagnostic_updater::Updater diagnostics_
int npackets
number of packets to combine
boost::shared_ptr< velodyne_rawdata::RawData > data_
std::string fixed_frame
fixed frame
ros::Subscriber velodyne_scan_
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::CloudNodeConfig > > srv_