34 #ifndef MULTISENSE_ROS_LASER_H 35 #define MULTISENSE_ROS_LASER_H 37 #include <boost/shared_ptr.hpp> 38 #include <boost/thread.hpp> 40 #include <sensor_msgs/LaserScan.h> 41 #include <sensor_msgs/JointState.h> 42 #include <sensor_msgs/PointCloud2.h> 46 #include <multisense_lib/MultiSenseChannel.hh> 53 const std::string& tf_prefix);
Laser(crl::multisense::Channel *driver, const std::string &tf_prefix)
tf::Transform getSpindleTransform(float spindle_angle)
sensor_msgs::JointState joint_states_
void defaultTfPublisher(const ros::TimerEvent &event)
crl::multisense::lidar::Calibration lidar_cal_
sensor_msgs::LaserScan laser_msg_
ros::Publisher raw_lidar_cal_pub_
ros::Publisher raw_lidar_data_pub_
static const float EXPECTED_RATE
tf::Transform laser_to_spindle_
void publishSpindleTransform(const float spindle_angle, const float velocity, const ros::Time &time)
crl::multisense::Channel * driver_
ros::Publisher joint_states_pub_
sensor_msgs::PointCloud2 point_cloud_
tf::Transform motor_to_camera_
ros::Time previous_scan_time_
void scanCallback(const crl::multisense::lidar::Header &header)
ros::Publisher point_cloud_pub_
void pointCloudCallback(const crl::multisense::lidar::Header &header)
tf::TransformBroadcaster static_tf_broadcaster_
std::string left_camera_optical_
void publishStaticTransforms(const ros::Time &time)