scan_tools::LaserOrthoProjector Class Reference

#include <laser_ortho_projector.h>

List of all members.

Public Member Functions

 LaserOrthoProjector (ros::NodeHandle nh, ros::NodeHandle nh_private)
virtual ~LaserOrthoProjector ()

Private Types

typedef pcl::PointCloud< PointTPointCloudT
typedef pcl::PointXYZ PointT

Private Member Functions

void createCache (const sensor_msgs::LaserScan::ConstPtr &scan_msg)
bool getBaseToLaserTf (const sensor_msgs::LaserScan::ConstPtr &scan_msg)
void imuCallback (const sensor_msgs::Imu::ConstPtr &imu_msg)
void scanCallback (const sensor_msgs::LaserScan::ConstPtr &scan_msg)

Private Attributes

std::vector< double > a_cos_
std::vector< double > a_sin_
std::string base_frame_
btTransform base_to_laser_
ros::Publisher cloud_publisher_
ros::Subscriber imu_subscriber_
bool initialized_
sensor_msgs::Imu latest_imu_msg_
PointT nan_point_
ros::NodeHandle nh_
ros::NodeHandle nh_private_
std::string ortho_frame_
bool publish_tf_
ros::Subscriber scan_subscriber_
tf::TransformBroadcaster tf_broadcaster_
tf::TransformListener tf_listener_
bool use_imu_
std::string world_frame_

Detailed Description

Definition at line 54 of file laser_ortho_projector.h.


Member Typedef Documentation

typedef pcl::PointCloud<PointT> scan_tools::LaserOrthoProjector::PointCloudT [private]

Definition at line 57 of file laser_ortho_projector.h.

typedef pcl::PointXYZ scan_tools::LaserOrthoProjector::PointT [private]

Definition at line 56 of file laser_ortho_projector.h.


Constructor & Destructor Documentation

scan_tools::LaserOrthoProjector::LaserOrthoProjector ( ros::NodeHandle  nh,
ros::NodeHandle  nh_private 
)

Definition at line 34 of file laser_ortho_projector.cpp.

scan_tools::LaserOrthoProjector::~LaserOrthoProjector (  )  [virtual]

Definition at line 76 of file laser_ortho_projector.cpp.


Member Function Documentation

void scan_tools::LaserOrthoProjector::createCache ( const sensor_msgs::LaserScan::ConstPtr &  scan_msg  )  [private]

Definition at line 203 of file laser_ortho_projector.cpp.

bool scan_tools::LaserOrthoProjector::getBaseToLaserTf ( const sensor_msgs::LaserScan::ConstPtr &  scan_msg  )  [private]

Definition at line 183 of file laser_ortho_projector.cpp.

void scan_tools::LaserOrthoProjector::imuCallback ( const sensor_msgs::Imu::ConstPtr &  imu_msg  )  [private]

Definition at line 81 of file laser_ortho_projector.cpp.

void scan_tools::LaserOrthoProjector::scanCallback ( const sensor_msgs::LaserScan::ConstPtr &  scan_msg  )  [private]

Definition at line 86 of file laser_ortho_projector.cpp.


Member Data Documentation

std::vector<double> scan_tools::LaserOrthoProjector::a_cos_ [private]

Definition at line 85 of file laser_ortho_projector.h.

std::vector<double> scan_tools::LaserOrthoProjector::a_sin_ [private]

Definition at line 84 of file laser_ortho_projector.h.

Definition at line 75 of file laser_ortho_projector.h.

Definition at line 91 of file laser_ortho_projector.h.

Definition at line 65 of file laser_ortho_projector.h.

Definition at line 67 of file laser_ortho_projector.h.

Definition at line 82 of file laser_ortho_projector.h.

Definition at line 87 of file laser_ortho_projector.h.

Definition at line 89 of file laser_ortho_projector.h.

ros::NodeHandle scan_tools::LaserOrthoProjector::nh_ [private]

Definition at line 62 of file laser_ortho_projector.h.

Definition at line 63 of file laser_ortho_projector.h.

Definition at line 76 of file laser_ortho_projector.h.

Definition at line 77 of file laser_ortho_projector.h.

Definition at line 66 of file laser_ortho_projector.h.

tf::TransformBroadcaster scan_tools::LaserOrthoProjector::tf_broadcaster_ [private]

Definition at line 70 of file laser_ortho_projector.h.

tf::TransformListener scan_tools::LaserOrthoProjector::tf_listener_ [private]

Definition at line 69 of file laser_ortho_projector.h.

Definition at line 78 of file laser_ortho_projector.h.

Definition at line 74 of file laser_ortho_projector.h.


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


laser_ortho_projector
Author(s): Ivan Dryanovski, William Morris
autogenerated on Fri Jan 11 10:03:43 2013