base_realsense_node.h
Go to the documentation of this file.
1 // License: Apache 2.0. See LICENSE file in root directory.
2 // Copyright(c) 2018 Intel Corporation. All Rights Reserved
3 
4 #pragma once
5 
7 #include <realsense2_camera/DeviceInfo.h>
8 #include "realsense2_camera/Metadata.h"
10 
13 #include <sensor_msgs/CameraInfo.h>
15 #include <sensor_msgs/point_cloud2_iterator.h>
16 #include <sensor_msgs/Imu.h>
17 #include <nav_msgs/Odometry.h>
20 #include <condition_variable>
21 
22 #include <queue>
23 #include <mutex>
24 #include <atomic>
25 #include <thread>
26 
28 {
30  {
31  FrequencyDiagnostics(double expected_frequency, std::string name, std::string hardware_id) :
32  expected_frequency_(expected_frequency),
34  diagnostic_updater_(ros::NodeHandle(), ros::NodeHandle("~"), ros::this_node::getName() + "_" + name)
35  {
36  ROS_INFO("Expected frequency for %s = %.5f", name.c_str(), expected_frequency_);
39  }
40 
41  void tick()
42  {
44  }
45 
46  void update()
47  {
49  }
50 
54  };
55  typedef std::pair<image_transport::Publisher, std::shared_ptr<FrequencyDiagnostics>> ImagePublisherWithFrequencyDiagnostics;
56 
58  {
59  public:
60  TemperatureDiagnostics(std::string name, std::string serial_no);
62 
63  void update(double crnt_temperaure)
64  {
65  _crnt_temp = crnt_temperaure;
66  _updater.update();
67  }
68 
69  private:
70  double _crnt_temp;
72 
73  };
74 
76  {
77  public:
78  std::string _name;
79  std::shared_ptr<rs2::filter> _filter;
80 
81  public:
82  NamedFilter(std::string name, std::shared_ptr<rs2::filter> filter):
83  _name(name), _filter(filter)
84  {}
85  };
86 
88  {
89  public:
90  void operator()(rs2::frame f) const
91  {
92  invoke(std::move(f));
93  }
94  };
95 
97  {
98  public:
99  SyncedImuPublisher() {_is_enabled=false;};
100  SyncedImuPublisher(ros::Publisher imu_publisher, std::size_t waiting_list_size=1000);
102  void Pause(); // Pause sending messages. All messages from now on are saved in queue.
103  void Resume(); // Send all pending messages and allow sending future messages.
104  void Publish(sensor_msgs::Imu msg); //either send or hold message.
105  uint32_t getNumSubscribers() { return _publisher.getNumSubscribers();};
106  void Enable(bool is_enabled) {_is_enabled=is_enabled;};
107 
108  private:
109  void PublishPendingMessages();
110 
111  private:
112  std::mutex _mutex;
115  std::queue<sensor_msgs::Imu> _pending_messages;
116  std::size_t _waiting_list_size;
118  };
119 
121  {
122  public:
124  ros::NodeHandle& privateNodeHandle,
126  const std::string& serial_no);
127 
128  virtual void toggleSensors(bool enabled) override;
129  virtual void publishTopics() override;
130  virtual void registerDynamicReconfigCb(ros::NodeHandle& nh) override;
131  virtual ~BaseRealSenseNode();
132 
133  public:
134  enum imu_sync_method{NONE, COPY, LINEAR_INTERPOLATION};
135 
136  protected:
137  class float3
138  {
139  public:
140  float x, y, z;
141 
142  public:
143  float3& operator*=(const float& factor)
144  {
145  x*=factor;
146  y*=factor;
147  z*=factor;
148  return (*this);
149  }
150  float3& operator+=(const float3& other)
151  {
152  x+=other.x;
153  y+=other.y;
154  z+=other.z;
155  return (*this);
156  }
157  };
158 
160  std::string _base_frame_id;
161  std::string _odom_frame_id;
162  std::map<stream_index_pair, std::string> _frame_id;
163  std::map<stream_index_pair, std::string> _optical_frame_id;
164  std::map<stream_index_pair, std::string> _depth_aligned_frame_id;
165  ros::NodeHandle& _node_handle, _pnh;
167  std::vector<rs2_option> _monitor_options;
168  std::shared_ptr<ros::ServiceServer> _device_info_srv;
169 
170  virtual void calcAndPublishStaticTransform(const stream_index_pair& stream, const rs2::stream_profile& base_profile);
171  bool getDeviceInfo(realsense2_camera::DeviceInfo::Request& req,
172  realsense2_camera::DeviceInfo::Response& res);
173  rs2::stream_profile getAProfile(const stream_index_pair& stream);
174  tf::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const;
175  void publish_static_tf(const ros::Time& t,
176  const float3& trans,
177  const tf::Quaternion& q,
178  const std::string& from,
179  const std::string& to);
180 
181 
182  private:
183  class CimuData
184  {
185  public:
186  CimuData() : m_time(-1) {};
187  CimuData(const stream_index_pair type, Eigen::Vector3d data, double time):
188  m_type(type),
189  m_data(data),
190  m_time(time){};
191  bool is_set() {return m_time > 0;};
192  public:
194  Eigen::Vector3d m_data;
195  double m_time;
196  };
197 
198  static std::string getNamespaceStr();
199  void getParameters();
200  void setupDevice();
201  void setupErrorCallback();
202  void setupPublishers();
203  void enable_devices();
204  void setupFilters();
205  void setupStreams();
206  bool setBaseTime(double frame_time, rs2_timestamp_domain time_domain);
207  double frameSystemTimeSec(rs2::frame frame);
208  cv::Mat& fix_depth_scale(const cv::Mat& from_image, cv::Mat& to_image);
209  void clip_depth(rs2::depth_frame depth_frame, float clipping_dist);
210  void updateStreamCalibData(const rs2::video_stream_profile& video_profile);
211  void SetBaseStream();
212  void publishStaticTransforms();
213  void publishDynamicTransforms();
214  void publishIntrinsics();
215  void runFirstFrameInitialization(rs2_stream stream_type);
216  void publishPointCloud(rs2::points f, const ros::Time& t, const rs2::frameset& frameset);
217  Extrinsics rsExtrinsicsToMsg(const rs2_extrinsics& extrinsics, const std::string& frame_id) const;
218 
219  IMUInfo getImuInfo(const stream_index_pair& stream_index);
220  void publishFrame(rs2::frame f, const ros::Time& t,
221  const stream_index_pair& stream,
222  std::map<stream_index_pair, cv::Mat>& images,
223  const std::map<stream_index_pair, ros::Publisher>& info_publishers,
224  const std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics>& image_publishers,
225  const bool is_publishMetadata,
226  std::map<stream_index_pair, int>& seq,
227  std::map<stream_index_pair, sensor_msgs::CameraInfo>& camera_info,
228  const std::map<rs2_stream, std::string>& encoding,
229  bool copy_data_from_frame = true);
230  void publishMetadata(rs2::frame f, const ros::Time& header_time, const std::string& frame_id);
231  bool getEnabledProfile(const stream_index_pair& stream_index, rs2::stream_profile& profile);
232 
233  void publishAlignedDepthToOthers(rs2::frameset frames, const ros::Time& t);
234  sensor_msgs::Imu CreateUnitedMessage(const CimuData accel_data, const CimuData gyro_data);
235 
236  void FillImuData_Copy(const CimuData imu_data, std::deque<sensor_msgs::Imu>& imu_msgs);
237  void ImuMessage_AddDefaultValues(sensor_msgs::Imu& imu_msg);
238  void FillImuData_LinearInterpolation(const CimuData imu_data, std::deque<sensor_msgs::Imu>& imu_msgs);
239  void imu_callback(rs2::frame frame);
240  void imu_callback_sync(rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY);
241  void pose_callback(rs2::frame frame);
242  void multiple_message_callback(rs2::frame frame, imu_sync_method sync_method);
243  void frame_callback(rs2::frame frame);
244  void registerDynamicOption(ros::NodeHandle& nh, rs2::options sensor, std::string& module_name);
245  void registerHDRoptions();
246  void set_sensor_parameter_to_ros(const std::string& module_name, rs2::options sensor, rs2_option option);
247  void monitor_update_functions();
248  void readAndSetDynamicParam(ros::NodeHandle& nh1, std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec, const std::string option_name, const int min_val, const int max_val, rs2::sensor sensor, int* option_value);
249  void registerAutoExposureROIOptions(ros::NodeHandle& nh);
250  void set_auto_exposure_roi(const std::string option_name, rs2::sensor sensor, int new_value);
251  void set_sensor_auto_exposure_roi(rs2::sensor sensor);
252  rs2_stream rs2_string_to_stream(std::string str);
253  void startMonitoring();
254  void publish_temperature();
255  void publish_frequency_update();
256  void publishServices();
257 
259  std::map<stream_index_pair, rs2::sensor> _sensors;
260  std::map<std::string, std::function<void(rs2::frame)>> _sensors_callback;
261  std::vector<std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure>> _ddynrec;
262 
263  std::string _json_file_path;
264  std::string _serial_no;
269 
270 
274 
275  std::map<stream_index_pair, rs2_intrinsics> _stream_intrinsics;
276  std::map<stream_index_pair, int> _width;
277  std::map<stream_index_pair, int> _height;
278  std::map<stream_index_pair, int> _fps;
279  std::map<rs2_stream, int> _format;
280  std::map<stream_index_pair, bool> _enable;
281  std::map<rs2_stream, std::string> _stream_name;
286  std::vector<geometry_msgs::TransformStamped> _static_tf_msgs;
287  std::shared_ptr<std::thread> _tf_t, _update_functions_t;
288 
289  std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics> _image_publishers;
290  std::map<stream_index_pair, ros::Publisher> _imu_publishers;
291  std::shared_ptr<SyncedImuPublisher> _synced_imu_publisher;
292  std::map<rs2_stream, int> _image_format;
293  std::map<stream_index_pair, ros::Publisher> _info_publisher;
294  std::map<stream_index_pair, std::shared_ptr<ros::Publisher>> _metadata_publishers;
295  std::map<stream_index_pair, cv::Mat> _image;
296  std::map<rs2_stream, std::string> _encoding;
297 
298  std::map<stream_index_pair, int> _seq;
299  std::map<rs2_stream, int> _unit_step_size;
300  std::map<stream_index_pair, sensor_msgs::CameraInfo> _camera_info;
301  std::atomic_bool _is_initialized_time_base;
303  std::map<stream_index_pair, std::vector<rs2::stream_profile>> _enabled_profiles;
304 
311  std::string _filters_str;
314  std::vector<NamedFilter> _filters;
315  std::shared_ptr<rs2::filter> _colorizer, _pointcloud_filter;
316  std::vector<rs2::sensor> _dev_sensors;
317 
318  std::map<stream_index_pair, cv::Mat> _depth_aligned_image;
319  std::map<stream_index_pair, cv::Mat> _depth_scaled_image;
320  std::map<rs2_stream, std::string> _depth_aligned_encoding;
321  std::map<stream_index_pair, sensor_msgs::CameraInfo> _depth_aligned_camera_info;
322  std::map<stream_index_pair, int> _depth_aligned_seq;
323  std::map<stream_index_pair, ros::Publisher> _depth_aligned_info_publisher;
324  std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics> _depth_aligned_image_publishers;
325  std::map<stream_index_pair, ros::Publisher> _depth_to_other_extrinsics_publishers;
326  std::map<stream_index_pair, rs2_extrinsics> _depth_to_other_extrinsics;
327  std::map<std::string, rs2::region_of_interest> _auto_exposure_roi;
328  std::map<rs2_stream, bool> _is_first_frame;
329  std::map<rs2_stream, std::vector<std::function<void()> > > _video_functions_stack;
330 
331  typedef std::pair<rs2_option, std::shared_ptr<TemperatureDiagnostics>> OptionTemperatureDiag;
332  std::vector< OptionTemperatureDiag > _temperature_nodes;
333  std::shared_ptr<std::thread> _monitoring_t;
334  std::vector<std::function<void()> > _update_functions_v;
335  mutable std::condition_variable _cv_monitoring, _cv_tf, _update_functions_cv;
336 
338  const std::string _namespace;
339 
341  std::vector< unsigned int > _valid_pc_indices;
342  };//end class
343 
344 }
345 
std::map< stream_index_pair, cv::Mat > _depth_aligned_image
std::map< stream_index_pair, int > _seq
msg
std::map< rs2_stream, int > _image_format
tf2_ros::StaticTransformBroadcaster _static_tf_broadcaster
U1 type
dev
rs2_option
std::map< stream_index_pair, ros::Publisher > _info_publisher
tf2_ros::TransformBroadcaster _dynamic_tf_broadcaster
std::map< stream_index_pair, rs2_intrinsics > _stream_intrinsics
void setHardwareID(const std::string &hwid)
std::vector< unsigned int > _valid_pc_indices
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
std::pair< image_transport::Publisher, std::shared_ptr< FrequencyDiagnostics > > ImagePublisherWithFrequencyDiagnostics
void add(const std::string &name, TaskFunction f)
std::shared_ptr< rs2::filter > _pointcloud_filter
std::shared_ptr< std::thread > _update_functions_t
void operator()(rs2::frame f) const
GLuint GLuint stream
std::map< rs2_stream, bool > _is_first_frame
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _image_publishers
GLint GLint GLint GLint GLint GLint GLint GLbitfield GLenum filter
std::queue< sensor_msgs::Imu > _pending_messages
std::pair< rs2_option, std::shared_ptr< TemperatureDiagnostics > > OptionTemperatureDiag
status
std::map< stream_index_pair, sensor_msgs::CameraInfo > _depth_aligned_camera_info
GLdouble t
std::vector< OptionTemperatureDiag > _temperature_nodes
std::map< stream_index_pair, rs2::sensor > _sensors
std::map< stream_index_pair, int > _width
GLdouble f
std::pair< rs2_stream, int > stream_index_pair
Definition: constants.h:99
sensor_msgs::PointCloud2 _msg_pointcloud
std::map< stream_index_pair, std::shared_ptr< ros::Publisher > > _metadata_publishers
std::map< stream_index_pair, rs2_extrinsics > _depth_to_other_extrinsics
std::map< rs2_stream, std::string > _encoding
unsigned int uint32_t
std::map< stream_index_pair, bool > _enable
std::map< stream_index_pair, cv::Mat > _image
std::map< rs2_stream, std::vector< std::function< void()> > > _video_functions_stack
#define ROS_INFO(...)
diagnostic_updater::FrequencyStatus frequency_status_
std::shared_ptr< SyncedImuPublisher > _synced_imu_publisher
GLenum GLenum GLsizei const GLuint GLboolean enabled
std::map< rs2_stream, std::string > _stream_name
std::shared_ptr< ros::ServiceServer > _device_info_srv
NamedFilter(std::string name, std::shared_ptr< rs2::filter > filter)
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _depth_aligned_image_publishers
std::map< stream_index_pair, cv::Mat > _depth_scaled_image
rs2_stream
std::function< void(stream_profile, frame_object, std::function< void()>)> frame_callback
FrequencyDiagnostics(double expected_frequency, std::string name, std::string hardware_id)
std::map< stream_index_pair, std::vector< rs2::stream_profile > > _enabled_profiles
GLdouble GLdouble GLdouble q
std::map< stream_index_pair, ros::Publisher > _imu_publishers
std::map< stream_index_pair, ros::Publisher > _depth_to_other_extrinsics_publishers
std::vector< rs2_option > _monitor_options
std::vector< std::function< void()> > _update_functions_v
std::map< stream_index_pair, std::string > _frame_id
std::map< stream_index_pair, int > _height
std::map< stream_index_pair, sensor_msgs::CameraInfo > _camera_info
CimuData(const stream_index_pair type, Eigen::Vector3d data, double time)
std::map< rs2_stream, int > _unit_step_size
std::shared_ptr< rs2::filter > _filter
std::shared_ptr< std::thread > _monitoring_t
std::vector< geometry_msgs::TransformStamped > _static_tf_msgs
std::map< rs2_stream, std::string > _depth_aligned_encoding
std::map< stream_index_pair, int > _fps
std::map< std::string, std::function< void(rs2::frame)> > _sensors_callback
std::vector< rs2::sensor > _dev_sensors
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > _ddynrec
GLuint res
std::map< stream_index_pair, int > _depth_aligned_seq
std::condition_variable _update_functions_cv
std::map< std::string, rs2::region_of_interest > _auto_exposure_roi
std::map< stream_index_pair, ros::Publisher > _depth_aligned_info_publisher
std::map< stream_index_pair, std::string > _optical_frame_id
std::map< stream_index_pair, std::string > _depth_aligned_frame_id
diagnostic_updater::Updater diagnostic_updater_
std::map< rs2_stream, int > _format
rs2_timestamp_domain


realsense2_camera
Author(s): Sergey Dorodnicov , Doron Hirshberg
autogenerated on Thu Mar 24 2022 02:12:40