laser.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_LASER_H
35 #define MULTISENSE_ROS_LASER_H
36 
37 #include <boost/shared_ptr.hpp>
38 #include <boost/thread.hpp>
39 #include <ros/ros.h>
40 #include <sensor_msgs/LaserScan.h>
41 #include <sensor_msgs/JointState.h>
42 #include <sensor_msgs/PointCloud2.h>
43 #include <tf/transform_datatypes.h>
45 
46 #include <multisense_lib/MultiSenseChannel.hh>
47 
48 namespace multisense_ros {
49 
50 class Laser {
51 public:
53  const std::string& tf_prefix);
54  ~Laser();
55 
58 
59  static const float EXPECTED_RATE;
60 
61 private:
62 
63  //
64  // Device stream control
65 
66  void subscribe();
67  void unsubscribe();
68  void stop();
69 
70  //
71  // Transform boadcasting
72  void publishStaticTransforms(const ros::Time& time);
73  void publishSpindleTransform(const float spindle_angle, const float velocity, const ros::Time& time);
74 
76 
77  void defaultTfPublisher(const ros::TimerEvent& event);
78 
79  //
80  // Query transforms
81 
82  tf::Transform getSpindleTransform(float spindle_angle);
83 
84  //
85  // Calibration from sensor
86 
88 
91 
92  //
93  // Frames to Publish
94  std::string left_camera_optical_;
95  std::string motor_;
96  std::string spindle_;
97  std::string hokuyo_;
98 
99  //
100  // Scan publishing
101 
104  std::string frame_id_;
105 
106  //
107  // Raw data publishing
108 
113 
114  //
115  // Keep around for efficiency
116 
117  sensor_msgs::LaserScan laser_msg_;
118  sensor_msgs::PointCloud2 point_cloud_;
119  sensor_msgs::JointState joint_states_;
120 
121  //
122  // Subscriptions
123 
124  boost::mutex sub_lock_;
125  int32_t subscribers_;
126 
127  //
128  // Timer used to publish the default laser transforms
129 
131 
132  //
133  // Spindle angle used when publishing the default transforms
134 
136 
137 
138  //
139  // Track publishing rates
140 
142 
143 
144 }; // class
145 
146 }// namespace
147 
148 
149 #endif
Laser(crl::multisense::Channel *driver, const std::string &tf_prefix)
Definition: laser.cpp:95
tf::Transform getSpindleTransform(float spindle_angle)
Definition: laser.cpp:454
sensor_msgs::JointState joint_states_
Definition: laser.h:119
void defaultTfPublisher(const ros::TimerEvent &event)
Definition: laser.cpp:466
crl::multisense::lidar::Calibration lidar_cal_
Definition: laser.h:87
sensor_msgs::LaserScan laser_msg_
Definition: laser.h:117
std::string hokuyo_
Definition: laser.h:97
std::string frame_id_
Definition: laser.h:104
ros::Publisher raw_lidar_cal_pub_
Definition: laser.h:111
float spindle_angle_
Definition: laser.h:135
ros::Publisher raw_lidar_data_pub_
Definition: laser.h:109
static const float EXPECTED_RATE
Definition: laser.h:59
tf::Transform laser_to_spindle_
Definition: laser.h:90
void publishSpindleTransform(const float spindle_angle, const float velocity, const ros::Time &time)
Definition: laser.cpp:447
crl::multisense::Channel * driver_
Definition: laser.h:102
std::string motor_
Definition: laser.h:95
ros::Publisher joint_states_pub_
Definition: laser.h:112
sensor_msgs::PointCloud2 point_cloud_
Definition: laser.h:118
boost::mutex sub_lock_
Definition: laser.h:124
std::string spindle_
Definition: laser.h:96
ros::Publisher scan_pub_
Definition: laser.h:103
tf::Transform motor_to_camera_
Definition: laser.h:89
ros::Time previous_scan_time_
Definition: laser.h:141
int32_t subscribers_
Definition: laser.h:125
ros::Timer timer_
Definition: laser.h:130
const std::string header
void scanCallback(const crl::multisense::lidar::Header &header)
Definition: laser.cpp:338
ros::Publisher point_cloud_pub_
Definition: laser.h:110
void pointCloudCallback(const crl::multisense::lidar::Header &header)
Definition: laser.cpp:271
tf::TransformBroadcaster static_tf_broadcaster_
Definition: laser.h:75
std::string left_camera_optical_
Definition: laser.h:94
void publishStaticTransforms(const ros::Time &time)
Definition: laser.cpp:431


multisense_ros
Author(s):
autogenerated on Sat Apr 6 2019 02:16:53