#include <laser_ortho_projector.h>
Public Member Functions | |
LaserOrthoProjector (ros::NodeHandle nh, ros::NodeHandle nh_private) | |
virtual | ~LaserOrthoProjector () |
Private Types | |
typedef sensor_msgs::Imu | ImuMsg |
typedef pcl::PointCloud< PointT > | PointCloudT |
typedef pcl::PointXYZ | PointT |
typedef geometry_msgs::PoseStamped | PoseMsg |
Private Member Functions | |
void | createCache (const sensor_msgs::LaserScan::ConstPtr &scan_msg) |
bool | getBaseToLaserTf (const sensor_msgs::LaserScan::ConstPtr &scan_msg) |
void | getOrthoTf (const tf::Transform &world_to_base, tf::Transform &world_to_ortho) |
void | imuCallback (const ImuMsg::ConstPtr &imu_msg) |
void | poseCallback (const PoseMsg::ConstPtr &pose_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_ |
tf::Transform | base_to_laser_ |
ros::Publisher | cloud_publisher_ |
ros::Subscriber | imu_subscriber_ |
bool | initialized_ |
PointT | nan_point_ |
ros::NodeHandle | nh_ |
ros::NodeHandle | nh_private_ |
std::string | ortho_frame_ |
tf::Transform | ortho_to_laser_ |
ros::Subscriber | pose_subscriber_ |
bool | publish_tf_ |
ros::Subscriber | scan_subscriber_ |
tf::TransformBroadcaster | tf_broadcaster_ |
tf::TransformListener | tf_listener_ |
bool | use_imu_ |
bool | use_pose_ |
std::string | world_frame_ |
Definition at line 51 of file laser_ortho_projector.h.
|
private |
Definition at line 57 of file laser_ortho_projector.h.
|
private |
Definition at line 54 of file laser_ortho_projector.h.
|
private |
Definition at line 53 of file laser_ortho_projector.h.
|
private |
Definition at line 56 of file laser_ortho_projector.h.
scan_tools::LaserOrthoProjector::LaserOrthoProjector | ( | ros::NodeHandle | nh, |
ros::NodeHandle | nh_private | ||
) |
Definition at line 36 of file laser_ortho_projector.cpp.
|
virtual |
Definition at line 95 of file laser_ortho_projector.cpp.
|
private |
Definition at line 243 of file laser_ortho_projector.cpp.
|
private |
Definition at line 223 of file laser_ortho_projector.cpp.
|
private |
Definition at line 146 of file laser_ortho_projector.cpp.
|
private |
Definition at line 100 of file laser_ortho_projector.cpp.
|
private |
Definition at line 125 of file laser_ortho_projector.cpp.
|
private |
Definition at line 158 of file laser_ortho_projector.cpp.
|
private |
Definition at line 95 of file laser_ortho_projector.h.
|
private |
Definition at line 94 of file laser_ortho_projector.h.
|
private |
Definition at line 83 of file laser_ortho_projector.h.
|
private |
Definition at line 99 of file laser_ortho_projector.h.
|
private |
Definition at line 71 of file laser_ortho_projector.h.
|
private |
Definition at line 74 of file laser_ortho_projector.h.
|
private |
Definition at line 92 of file laser_ortho_projector.h.
|
private |
Definition at line 97 of file laser_ortho_projector.h.
|
private |
Definition at line 68 of file laser_ortho_projector.h.
|
private |
Definition at line 69 of file laser_ortho_projector.h.
|
private |
Definition at line 84 of file laser_ortho_projector.h.
|
private |
Definition at line 100 of file laser_ortho_projector.h.
|
private |
Definition at line 75 of file laser_ortho_projector.h.
|
private |
Definition at line 86 of file laser_ortho_projector.h.
|
private |
Definition at line 73 of file laser_ortho_projector.h.
|
private |
Definition at line 78 of file laser_ortho_projector.h.
|
private |
Definition at line 77 of file laser_ortho_projector.h.
|
private |
Definition at line 88 of file laser_ortho_projector.h.
|
private |
Definition at line 87 of file laser_ortho_projector.h.
|
private |
Definition at line 82 of file laser_ortho_projector.h.