Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
velodyne_pointcloud::Convert Class Reference

#include <convert.h>

Classes

struct  Config
 configuration parameters More...
 

Public Member Functions

 Convert (ros::NodeHandle node, ros::NodeHandle private_nh)
 Constructor. More...
 
 ~Convert ()
 

Private Member Functions

void callback (velodyne_pointcloud::CloudNodeConfig &config, uint32_t level)
 
void processScan (const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
 Callback for raw scan messages. More...
 

Private Attributes

Config config_
 
boost::shared_ptr< velodyne_rawdata::DataContainerBasecontainer_ptr_
 
boost::shared_ptr< velodyne_rawdata::RawDatadata_
 
double diag_max_freq_
 
double diag_min_freq_
 
boost::shared_ptr< diagnostic_updater::TopicDiagnosticdiag_topic_
 
diagnostic_updater::Updater diagnostics_
 
bool first_rcfg_call
 
ros::Publisher output_
 
boost::mutex reconfigure_mtx_
 
boost::shared_ptr< dynamic_reconfigure::Server< velodyne_pointcloud::CloudNodeConfig > > srv_
 
ros::Subscriber velodyne_scan_
 

Detailed Description

Definition at line 56 of file convert.h.

Constructor & Destructor Documentation

velodyne_pointcloud::Convert::Convert ( ros::NodeHandle  node,
ros::NodeHandle  private_nh 
)

Constructor.

Definition at line 24 of file convert.cc.

velodyne_pointcloud::Convert::~Convert ( )
inline

Definition at line 60 of file convert.h.

Member Function Documentation

void velodyne_pointcloud::Convert::callback ( velodyne_pointcloud::CloudNodeConfig &  config,
uint32_t  level 
)
private

Definition at line 86 of file convert.cc.

void velodyne_pointcloud::Convert::processScan ( const velodyne_msgs::VelodyneScan::ConstPtr &  scanMsg)
private

Callback for raw scan messages.

Definition at line 122 of file convert.cc.

Member Data Documentation

Config velodyne_pointcloud::Convert::config_
private

Definition at line 88 of file convert.h.

boost::shared_ptr<velodyne_rawdata::DataContainerBase> velodyne_pointcloud::Convert::container_ptr_
private

Definition at line 72 of file convert.h.

boost::shared_ptr<velodyne_rawdata::RawData> velodyne_pointcloud::Convert::data_
private

Definition at line 68 of file convert.h.

double velodyne_pointcloud::Convert::diag_max_freq_
private

Definition at line 94 of file convert.h.

double velodyne_pointcloud::Convert::diag_min_freq_
private

Definition at line 93 of file convert.h.

boost::shared_ptr<diagnostic_updater::TopicDiagnostic> velodyne_pointcloud::Convert::diag_topic_
private

Definition at line 95 of file convert.h.

diagnostic_updater::Updater velodyne_pointcloud::Convert::diagnostics_
private

Definition at line 92 of file convert.h.

bool velodyne_pointcloud::Convert::first_rcfg_call
private

Definition at line 89 of file convert.h.

ros::Publisher velodyne_pointcloud::Convert::output_
private

Definition at line 70 of file convert.h.

boost::mutex velodyne_pointcloud::Convert::reconfigure_mtx_
private

Definition at line 74 of file convert.h.

boost::shared_ptr<dynamic_reconfigure::Server<velodyne_pointcloud::CloudNodeConfig> > velodyne_pointcloud::Convert::srv_
private

Definition at line 66 of file convert.h.

ros::Subscriber velodyne_pointcloud::Convert::velodyne_scan_
private

Definition at line 69 of file convert.h.


The documentation for this class was generated from the following files:


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Thu Jul 4 2019 19:09:30