Public Member Functions | Private Member Functions | Private Attributes | List of all members
pointcloud_to_laserscan::PointCloudToLaserScanNodelet Class Reference

#include <pointcloud_to_laserscan_nodelet.h>

Inheritance diagram for pointcloud_to_laserscan::PointCloudToLaserScanNodelet:
Inheritance graph
[legend]

Public Member Functions

 PointCloudToLaserScanNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

void cloudCb (const sensor_msgs::PointCloud2ConstPtr &cloud_msg)
 
void connectCb ()
 
void disconnectCb ()
 
void failureCb (const sensor_msgs::PointCloud2ConstPtr &cloud_msg, tf2_ros::filter_failure_reasons::FilterFailureReason reason)
 
virtual void onInit ()
 

Private Attributes

double angle_increment_
 
double angle_max_
 
double angle_min_
 
boost::mutex connect_mutex_
 
double inf_epsilon_
 
unsigned int input_queue_size_
 
double max_height_
 
boost::shared_ptr< MessageFiltermessage_filter_
 
double min_height_
 
ros::NodeHandle nh_
 
ros::NodeHandle private_nh_
 
ros::Publisher pub_
 
double range_max_
 
double range_min_
 
double scan_time_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_
 
std::string target_frame_
 
boost::shared_ptr< tf2_ros::Buffertf2_
 
boost::shared_ptr< tf2_ros::TransformListenertf2_listener_
 
double tolerance_
 
bool use_inf_
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Class to process incoming pointclouds into laserscans. Some initial code was pulled from the defunct turtlebot pointcloud_to_laserscan implementation.

Definition at line 61 of file pointcloud_to_laserscan_nodelet.h.

Constructor & Destructor Documentation

◆ PointCloudToLaserScanNodelet()

pointcloud_to_laserscan::PointCloudToLaserScanNodelet::PointCloudToLaserScanNodelet ( )

Definition at line 51 of file pointcloud_to_laserscan_nodelet.cpp.

Member Function Documentation

◆ cloudCb()

void pointcloud_to_laserscan::PointCloudToLaserScanNodelet::cloudCb ( const sensor_msgs::PointCloud2ConstPtr &  cloud_msg)
private

Definition at line 144 of file pointcloud_to_laserscan_nodelet.cpp.

◆ connectCb()

void pointcloud_to_laserscan::PointCloudToLaserScanNodelet::connectCb ( )
private

Definition at line 115 of file pointcloud_to_laserscan_nodelet.cpp.

◆ disconnectCb()

void pointcloud_to_laserscan::PointCloudToLaserScanNodelet::disconnectCb ( )
private

Definition at line 125 of file pointcloud_to_laserscan_nodelet.cpp.

◆ failureCb()

void pointcloud_to_laserscan::PointCloudToLaserScanNodelet::failureCb ( const sensor_msgs::PointCloud2ConstPtr &  cloud_msg,
tf2_ros::filter_failure_reasons::FilterFailureReason  reason 
)
private

Definition at line 135 of file pointcloud_to_laserscan_nodelet.cpp.

◆ onInit()

void pointcloud_to_laserscan::PointCloudToLaserScanNodelet::onInit ( )
privatevirtual

Implements nodelet::Nodelet.

Definition at line 55 of file pointcloud_to_laserscan_nodelet.cpp.

Member Data Documentation

◆ angle_increment_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::angle_increment_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ angle_max_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::angle_max_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ angle_min_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::angle_min_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ connect_mutex_

boost::mutex pointcloud_to_laserscan::PointCloudToLaserScanNodelet::connect_mutex_
private

Definition at line 79 of file pointcloud_to_laserscan_nodelet.h.

◆ inf_epsilon_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::inf_epsilon_
private

Definition at line 92 of file pointcloud_to_laserscan_nodelet.h.

◆ input_queue_size_

unsigned int pointcloud_to_laserscan::PointCloudToLaserScanNodelet::input_queue_size_
private

Definition at line 87 of file pointcloud_to_laserscan_nodelet.h.

◆ max_height_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::max_height_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ message_filter_

boost::shared_ptr<MessageFilter> pointcloud_to_laserscan::PointCloudToLaserScanNodelet::message_filter_
private

Definition at line 84 of file pointcloud_to_laserscan_nodelet.h.

◆ min_height_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::min_height_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ nh_

ros::NodeHandle pointcloud_to_laserscan::PointCloudToLaserScanNodelet::nh_
private

Definition at line 77 of file pointcloud_to_laserscan_nodelet.h.

◆ private_nh_

ros::NodeHandle pointcloud_to_laserscan::PointCloudToLaserScanNodelet::private_nh_
private

Definition at line 77 of file pointcloud_to_laserscan_nodelet.h.

◆ pub_

ros::Publisher pointcloud_to_laserscan::PointCloudToLaserScanNodelet::pub_
private

Definition at line 78 of file pointcloud_to_laserscan_nodelet.h.

◆ range_max_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::range_max_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ range_min_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::range_min_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ scan_time_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::scan_time_
private

Definition at line 90 of file pointcloud_to_laserscan_nodelet.h.

◆ sub_

message_filters::Subscriber<sensor_msgs::PointCloud2> pointcloud_to_laserscan::PointCloudToLaserScanNodelet::sub_
private

Definition at line 83 of file pointcloud_to_laserscan_nodelet.h.

◆ target_frame_

std::string pointcloud_to_laserscan::PointCloudToLaserScanNodelet::target_frame_
private

Definition at line 88 of file pointcloud_to_laserscan_nodelet.h.

◆ tf2_

boost::shared_ptr<tf2_ros::Buffer> pointcloud_to_laserscan::PointCloudToLaserScanNodelet::tf2_
private

Definition at line 81 of file pointcloud_to_laserscan_nodelet.h.

◆ tf2_listener_

boost::shared_ptr<tf2_ros::TransformListener> pointcloud_to_laserscan::PointCloudToLaserScanNodelet::tf2_listener_
private

Definition at line 82 of file pointcloud_to_laserscan_nodelet.h.

◆ tolerance_

double pointcloud_to_laserscan::PointCloudToLaserScanNodelet::tolerance_
private

Definition at line 89 of file pointcloud_to_laserscan_nodelet.h.

◆ use_inf_

bool pointcloud_to_laserscan::PointCloudToLaserScanNodelet::use_inf_
private

Definition at line 91 of file pointcloud_to_laserscan_nodelet.h.


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


pointcloud_to_laserscan
Author(s): Paul Bovbel , Tully Foote
autogenerated on Wed Mar 2 2022 00:44:25