#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.
typedef sensor_msgs::Imu scan_tools::LaserOrthoProjector::ImuMsg [private] |
Definition at line 57 of file laser_ortho_projector.h.
typedef pcl::PointCloud<PointT> scan_tools::LaserOrthoProjector::PointCloudT [private] |
Definition at line 54 of file laser_ortho_projector.h.
typedef pcl::PointXYZ scan_tools::LaserOrthoProjector::PointT [private] |
Definition at line 53 of file laser_ortho_projector.h.
typedef geometry_msgs::PoseStamped scan_tools::LaserOrthoProjector::PoseMsg [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 34 of file laser_ortho_projector.cpp.
scan_tools::LaserOrthoProjector::~LaserOrthoProjector | ( | ) | [virtual] |
Definition at line 93 of file laser_ortho_projector.cpp.
void scan_tools::LaserOrthoProjector::createCache | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_msg | ) | [private] |
Definition at line 241 of file laser_ortho_projector.cpp.
bool scan_tools::LaserOrthoProjector::getBaseToLaserTf | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_msg | ) | [private] |
Definition at line 221 of file laser_ortho_projector.cpp.
void scan_tools::LaserOrthoProjector::getOrthoTf | ( | const tf::Transform & | world_to_base, |
tf::Transform & | world_to_ortho | ||
) | [private] |
Definition at line 144 of file laser_ortho_projector.cpp.
void scan_tools::LaserOrthoProjector::imuCallback | ( | const ImuMsg::ConstPtr & | imu_msg | ) | [private] |
Definition at line 98 of file laser_ortho_projector.cpp.
void scan_tools::LaserOrthoProjector::poseCallback | ( | const PoseMsg::ConstPtr & | pose_msg | ) | [private] |
Definition at line 123 of file laser_ortho_projector.cpp.
void scan_tools::LaserOrthoProjector::scanCallback | ( | const sensor_msgs::LaserScan::ConstPtr & | scan_msg | ) | [private] |
Definition at line 156 of file laser_ortho_projector.cpp.
std::vector<double> scan_tools::LaserOrthoProjector::a_cos_ [private] |
Definition at line 95 of file laser_ortho_projector.h.
std::vector<double> scan_tools::LaserOrthoProjector::a_sin_ [private] |
Definition at line 94 of file laser_ortho_projector.h.
std::string scan_tools::LaserOrthoProjector::base_frame_ [private] |
Definition at line 83 of file laser_ortho_projector.h.
Definition at line 99 of file laser_ortho_projector.h.
Definition at line 71 of file laser_ortho_projector.h.
Definition at line 74 of file laser_ortho_projector.h.
bool scan_tools::LaserOrthoProjector::initialized_ [private] |
Definition at line 92 of file laser_ortho_projector.h.
Definition at line 97 of file laser_ortho_projector.h.
Definition at line 68 of file laser_ortho_projector.h.
Definition at line 69 of file laser_ortho_projector.h.
std::string scan_tools::LaserOrthoProjector::ortho_frame_ [private] |
Definition at line 84 of file laser_ortho_projector.h.
Definition at line 100 of file laser_ortho_projector.h.
Definition at line 75 of file laser_ortho_projector.h.
bool scan_tools::LaserOrthoProjector::publish_tf_ [private] |
Definition at line 86 of file laser_ortho_projector.h.
Definition at line 73 of file laser_ortho_projector.h.
Definition at line 78 of file laser_ortho_projector.h.
Definition at line 77 of file laser_ortho_projector.h.
bool scan_tools::LaserOrthoProjector::use_imu_ [private] |
Definition at line 88 of file laser_ortho_projector.h.
bool scan_tools::LaserOrthoProjector::use_pose_ [private] |
Definition at line 87 of file laser_ortho_projector.h.
std::string scan_tools::LaserOrthoProjector::world_frame_ [private] |
Definition at line 82 of file laser_ortho_projector.h.