laser_joint_processor::LaserJointProcessorNode Class Reference

#include <laser_joint_processor_node.h>

List of all members.

Public Member Functions

void configure (const std::vector< std::string > &joint_names, unsigned max_cache_size)
void jointStateCallback (const sensor_msgs::JointStateConstPtr &joint_state)
 LaserJointProcessorNode ()
 ~LaserJointProcessorNode ()

Private Member Functions

void processPair (const calibration_msgs::DenseLaserSnapshotConstPtr &snapshot, const calibration_msgs::CalibrationPatternConstPtr &features)
void syncCallback (const calibration_msgs::DenseLaserSnapshotConstPtr &snapshot, const calibration_msgs::CalibrationPatternConstPtr &features)

Private Attributes

message_filters::Subscriber
< calibration_msgs::CalibrationPattern > 
features_sub_
boost::mutex mutex_
ros::NodeHandle nh_
LaserJointProcessor processor_
ros::Publisher pub_
calibration_msgs::CalibrationPatternConstPtr queued_features_
calibration_msgs::DenseLaserSnapshotConstPtr queued_snapshot_
message_filters::Subscriber
< calibration_msgs::DenseLaserSnapshot > 
snapshot_sub_
message_filters::TimeSynchronizer
< calibration_msgs::DenseLaserSnapshot,
calibration_msgs::CalibrationPattern > 
sync_
message_filters::Connection sync_connection_

Detailed Description

Definition at line 42 of file laser_joint_processor_node.h.


Constructor & Destructor Documentation

LaserJointProcessorNode::LaserJointProcessorNode (  ) 

Definition at line 46 of file laser_joint_processor_node.cpp.

LaserJointProcessorNode::~LaserJointProcessorNode (  ) 

Definition at line 57 of file laser_joint_processor_node.cpp.


Member Function Documentation

void laser_joint_processor::LaserJointProcessorNode::configure ( const std::vector< std::string > &  joint_names,
unsigned  max_cache_size 
)
void LaserJointProcessorNode::jointStateCallback ( const sensor_msgs::JointStateConstPtr &  joint_state  ) 

Definition at line 102 of file laser_joint_processor_node.cpp.

void LaserJointProcessorNode::processPair ( const calibration_msgs::DenseLaserSnapshotConstPtr &  snapshot,
const calibration_msgs::CalibrationPatternConstPtr &  features 
) [private]

Definition at line 136 of file laser_joint_processor_node.cpp.

void LaserJointProcessorNode::syncCallback ( const calibration_msgs::DenseLaserSnapshotConstPtr &  snapshot,
const calibration_msgs::CalibrationPatternConstPtr &  features 
) [private]

Definition at line 68 of file laser_joint_processor_node.cpp.


Member Data Documentation

message_filters::Subscriber<calibration_msgs::CalibrationPattern> laser_joint_processor::LaserJointProcessorNode::features_sub_ [private]

Definition at line 63 of file laser_joint_processor_node.h.

Definition at line 57 of file laser_joint_processor_node.h.

Definition at line 60 of file laser_joint_processor_node.h.

Definition at line 73 of file laser_joint_processor_node.h.

Definition at line 61 of file laser_joint_processor_node.h.

calibration_msgs::CalibrationPatternConstPtr laser_joint_processor::LaserJointProcessorNode::queued_features_ [private]

Definition at line 70 of file laser_joint_processor_node.h.

calibration_msgs::DenseLaserSnapshotConstPtr laser_joint_processor::LaserJointProcessorNode::queued_snapshot_ [private]

Definition at line 69 of file laser_joint_processor_node.h.

message_filters::Subscriber<calibration_msgs::DenseLaserSnapshot> laser_joint_processor::LaserJointProcessorNode::snapshot_sub_ [private]

Definition at line 62 of file laser_joint_processor_node.h.

message_filters::TimeSynchronizer<calibration_msgs::DenseLaserSnapshot, calibration_msgs::CalibrationPattern> laser_joint_processor::LaserJointProcessorNode::sync_ [private]

Definition at line 65 of file laser_joint_processor_node.h.

Definition at line 66 of file laser_joint_processor_node.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


laser_joint_processor
Author(s): Vijay Pradeep
autogenerated on Fri Jan 11 09:14:18 2013