laser.h
Go to the documentation of this file.
00001 
00034 #ifndef MULTISENSE_ROS_LASER_H
00035 #define MULTISENSE_ROS_LASER_H
00036 
00037 #include <boost/shared_ptr.hpp>
00038 #include <boost/thread.hpp>
00039 #include <ros/ros.h>
00040 #include <sensor_msgs/LaserScan.h>
00041 #include <sensor_msgs/JointState.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <tf/transform_datatypes.h>
00044 #include <tf/transform_broadcaster.h>
00045 
00046 #include <multisense_lib/MultiSenseChannel.hh>
00047 
00048 namespace multisense_ros {
00049 
00050 class Laser {
00051 public:
00052     Laser(crl::multisense::Channel* driver,
00053           const std::string& tf_prefix);
00054     ~Laser();
00055 
00056     void scanCallback(const crl::multisense::lidar::Header& header);
00057     void pointCloudCallback(const crl::multisense::lidar::Header& header);
00058 
00059     static const float EXPECTED_RATE;
00060 
00061 private:
00062 
00063     //
00064     // Device stream control
00065 
00066     void subscribe();
00067     void unsubscribe();
00068     void stop();
00069 
00070     //
00071     // Transform boadcasting
00072     void publishStaticTransforms(const ros::Time& time);
00073     void publishSpindleTransform(const float spindle_angle, const float velocity, const ros::Time& time);
00074 
00075     tf::TransformBroadcaster static_tf_broadcaster_;
00076 
00077     void defaultTfPublisher(const ros::TimerEvent& event);
00078 
00079     //
00080     // Query transforms
00081 
00082     tf::Transform getSpindleTransform(float spindle_angle);
00083 
00084     //
00085     // Calibration from sensor
00086 
00087     crl::multisense::lidar::Calibration lidar_cal_;
00088 
00089     tf::Transform motor_to_camera_;
00090     tf::Transform laser_to_spindle_;
00091 
00092     //
00093     // Frames to Publish
00094     std::string left_camera_optical_;
00095     std::string motor_;
00096     std::string spindle_;
00097     std::string hokuyo_;
00098 
00099     //
00100     // Scan publishing
00101 
00102     crl::multisense::Channel *driver_;
00103     ros::Publisher            scan_pub_;
00104     std::string               frame_id_;
00105 
00106     //
00107     // Raw data publishing
00108 
00109     ros::Publisher raw_lidar_data_pub_;
00110     ros::Publisher point_cloud_pub_;
00111     ros::Publisher raw_lidar_cal_pub_;
00112     ros::Publisher joint_states_pub_;
00113 
00114     //
00115     // Keep around for efficiency
00116 
00117     sensor_msgs::LaserScan   laser_msg_;
00118     sensor_msgs::PointCloud2 point_cloud_;
00119     sensor_msgs::JointState  joint_states_;
00120 
00121     //
00122     // Subscriptions
00123 
00124     boost::mutex sub_lock_;
00125     int32_t      subscribers_;
00126 
00127     //
00128     // Timer used to publish the default laser transforms
00129 
00130     ros::Timer timer_;
00131 
00132     //
00133     // Spindle angle used when publishing the default transforms
00134 
00135     float spindle_angle_;
00136 
00137 
00138     //
00139     // Track publishing rates
00140 
00141     ros::Time previous_scan_time_;
00142 
00143 
00144 }; // class
00145 
00146 }// namespace
00147 
00148 
00149 #endif


multisense_ros
Author(s):
autogenerated on Mon Oct 9 2017 03:06:27