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):
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:
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.
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:
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;
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);
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();
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);
232 
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);
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);
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);
250  void set_auto_exposure_roi(const std::string option_name, rs2::sensor sensor, int new_value);
252  rs2_stream rs2_string_to_stream(std::string str);
253  void startMonitoring();
254  void publish_temperature();
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 
realsense2_camera::SyncedImuPublisher::~SyncedImuPublisher
~SyncedImuPublisher()
Definition: base_realsense_node.cpp:26
rs2::device
ddynamic_reconfigure.h
realsense2_camera::BaseRealSenseNode::_update_functions_cv
std::condition_variable _update_functions_cv
Definition: base_realsense_node.h:335
realsense2_camera::BaseRealSenseNode::imu_callback
void imu_callback(rs2::frame frame)
Definition: base_realsense_node.cpp:1493
realsense2_camera::BaseRealSenseNode::_msg_pointcloud
sensor_msgs::PointCloud2 _msg_pointcloud
Definition: base_realsense_node.h:340
diagnostic_updater::FrequencyStatus
realsense2_camera::BaseRealSenseNode::rs2_string_to_stream
rs2_stream rs2_string_to_stream(std::string str)
Definition: base_realsense_node.cpp:702
enabled
GLenum GLenum GLsizei const GLuint GLboolean enabled
status
status
realsense2_camera::PipelineSyncer
Definition: base_realsense_node.h:87
realsense2_camera::BaseRealSenseNode::set_sensor_parameter_to_ros
void set_sensor_parameter_to_ros(const std::string &module_name, rs2::options sensor, rs2_option option)
Definition: base_realsense_node.cpp:663
name
sensor_msgs::Imu_
rs2::frame
realsense2_camera::BaseRealSenseNode::_imu_sync_method
imu_sync_method _imu_sync_method
Definition: base_realsense_node.h:310
realsense2_camera::BaseRealSenseNode::_enable
std::map< stream_index_pair, bool > _enable
Definition: base_realsense_node.h:280
ros::Publisher
rs2::frameset
realsense2_camera::BaseRealSenseNode::CimuData::CimuData
CimuData(const stream_index_pair type, Eigen::Vector3d data, double time)
Definition: base_realsense_node.h:187
realsense2_camera::BaseRealSenseNode::getEnabledProfile
bool getEnabledProfile(const stream_index_pair &stream_index, rs2::stream_profile &profile)
Definition: base_realsense_node.cpp:2477
rs2_extrinsics
rs2::stream_profile
realsense2_camera::BaseRealSenseNode::_pointcloud_filter
std::shared_ptr< rs2::filter > _pointcloud_filter
Definition: base_realsense_node.h:315
realsense2_camera::BaseRealSenseNode::_allow_no_texture_points
bool _allow_no_texture_points
Definition: base_realsense_node.h:267
realsense2_camera::BaseRealSenseNode::_video_functions_stack
std::map< rs2_stream, std::vector< std::function< void()> > > _video_functions_stack
Definition: base_realsense_node.h:329
realsense2_camera::BaseRealSenseNode::registerHDRoptions
void registerHDRoptions()
Definition: base_realsense_node.cpp:620
realsense2_camera::BaseRealSenseNode::_synced_imu_publisher
std::shared_ptr< SyncedImuPublisher > _synced_imu_publisher
Definition: base_realsense_node.h:291
realsense2_camera::BaseRealSenseNode::_tf_t
std::shared_ptr< std::thread > _tf_t
Definition: base_realsense_node.h:287
realsense2_camera::BaseRealSenseNode::toggleSensors
virtual void toggleSensors(bool enabled) override
Definition: base_realsense_node.cpp:173
realsense2_camera::BaseRealSenseNode::_namespace
const std::string _namespace
Definition: base_realsense_node.h:338
realsense2_camera::BaseRealSenseNode::_enabled_profiles
std::map< stream_index_pair, std::vector< rs2::stream_profile > > _enabled_profiles
Definition: base_realsense_node.h:303
realsense2_camera::BaseRealSenseNode::_node_handle
ros::NodeHandle & _node_handle
Definition: base_realsense_node.h:165
realsense2_camera::BaseRealSenseNode::_pointcloud_texture
stream_index_pair _pointcloud_texture
Definition: base_realsense_node.h:312
realsense2_camera::BaseRealSenseNode::getImuInfo
IMUInfo getImuInfo(const stream_index_pair &stream_index)
Definition: base_realsense_node.cpp:2333
realsense2_camera::BaseRealSenseNode::enable_devices
void enable_devices()
Definition: base_realsense_node.cpp:1058
realsense2_camera::BaseRealSenseNode::_pointcloud
bool _pointcloud
Definition: base_realsense_node.h:308
realsense_node_factory.h
realsense2_camera::BaseRealSenseNode::_ros_time_base
ros::Time _ros_time_base
Definition: base_realsense_node.h:306
realsense2_camera::BaseRealSenseNode::calcAndPublishStaticTransform
virtual void calcAndPublishStaticTransform(const stream_index_pair &stream, const rs2::stream_profile &base_profile)
Definition: base_realsense_node.cpp:2001
ros
realsense2_camera::BaseRealSenseNode::_syncer
PipelineSyncer _syncer
Definition: base_realsense_node.h:313
realsense2_camera::BaseRealSenseNode::_stream_name
std::map< rs2_stream, std::string > _stream_name
Definition: base_realsense_node.h:281
realsense2_camera::BaseRealSenseNode::_frame_id
std::map< stream_index_pair, std::string > _frame_id
Definition: base_realsense_node.h:162
data
realsense2_camera::BaseRealSenseNode::float3::x
float x
Definition: base_realsense_node.h:140
realsense2_camera::BaseRealSenseNode::publishPointCloud
void publishPointCloud(rs2::points f, const ros::Time &t, const rs2::frameset &frameset)
Definition: base_realsense_node.cpp:2167
rs2::asynchronous_syncer
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
rs2::options
realsense2_camera::BaseRealSenseNode::_align_depth
bool _align_depth
Definition: base_realsense_node.h:166
realsense2_camera::BaseRealSenseNode::_camera_info
std::map< stream_index_pair, sensor_msgs::CameraInfo > _camera_info
Definition: base_realsense_node.h:300
realsense2_camera::BaseRealSenseNode::publishAlignedDepthToOthers
void publishAlignedDepthToOthers(rs2::frameset frames, const ros::Time &t)
realsense2_camera::BaseRealSenseNode::LINEAR_INTERPOLATION
@ LINEAR_INTERPOLATION
Definition: base_realsense_node.h:134
CameraInfo.h
q
GLdouble GLdouble GLdouble q
realsense2_camera::BaseRealSenseNode::_monitoring_t
std::shared_ptr< std::thread > _monitoring_t
Definition: base_realsense_node.h:333
realsense2_camera::BaseRealSenseNode::fix_depth_scale
cv::Mat & fix_depth_scale(const cv::Mat &from_image, cv::Mat &to_image)
Definition: base_realsense_node.cpp:1285
realsense2_camera::BaseRealSenseNode::_fps
std::map< stream_index_pair, int > _fps
Definition: base_realsense_node.h:278
realsense2_camera::BaseRealSenseNode::imu_sync_method
imu_sync_method
Definition: base_realsense_node.h:134
diagnostic_updater::Updater
realsense2_camera::BaseRealSenseNode::_static_tf_msgs
std::vector< geometry_msgs::TransformStamped > _static_tf_msgs
Definition: base_realsense_node.h:286
void
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
rs2::processing_block::invoke
void invoke(frame f) const
realsense2_camera::BaseRealSenseNode::_depth_aligned_encoding
std::map< rs2_stream, std::string > _depth_aligned_encoding
Definition: base_realsense_node.h:320
realsense2_camera::BaseRealSenseNode::_cv_monitoring
std::condition_variable _cv_monitoring
Definition: base_realsense_node.h:335
realsense2_camera::BaseRealSenseNode::_auto_exposure_roi
std::map< std::string, rs2::region_of_interest > _auto_exposure_roi
Definition: base_realsense_node.h:327
realsense2_camera::BaseRealSenseNode
Definition: base_realsense_node.h:120
realsense2_camera::BaseRealSenseNode::_publish_tf
bool _publish_tf
Definition: base_realsense_node.h:282
realsense2_camera::TemperatureDiagnostics::_updater
diagnostic_updater::Updater _updater
Definition: base_realsense_node.h:71
realsense2_camera::NamedFilter::NamedFilter
NamedFilter(std::string name, std::shared_ptr< rs2::filter > filter)
Definition: base_realsense_node.h:82
realsense2_camera::BaseRealSenseNode::rsExtrinsicsToMsg
Extrinsics rsExtrinsicsToMsg(const rs2_extrinsics &extrinsics, const std::string &frame_id) const
Definition: base_realsense_node.cpp:2310
realsense2_camera::BaseRealSenseNode::setBaseTime
bool setBaseTime(double frame_time, rs2_timestamp_domain time_domain)
Definition: base_realsense_node.cpp:1802
realsense2_camera::FrequencyDiagnostics::expected_frequency_
double expected_frequency_
Definition: base_realsense_node.h:51
realsense2_camera::SyncedImuPublisher::PublishPendingMessages
void PublishPendingMessages()
Definition: base_realsense_node.cpp:64
realsense2_camera::BaseRealSenseNode::_stream_intrinsics
std::map< stream_index_pair, rs2_intrinsics > _stream_intrinsics
Definition: base_realsense_node.h:275
realsense2_camera::BaseRealSenseNode::CimuData::m_time
double m_time
Definition: base_realsense_node.h:195
f
GLdouble f
realsense2_camera::BaseRealSenseNode::_camera_time_base
double _camera_time_base
Definition: base_realsense_node.h:302
realsense2_camera::SyncedImuPublisher::Enable
void Enable(bool is_enabled)
Definition: base_realsense_node.h:106
realsense2_camera::BaseRealSenseNode::setupPublishers
void setupPublishers()
Definition: base_realsense_node.cpp:962
transform_broadcaster.h
diagnostic_updater.h
realsense2_camera::BaseRealSenseNode::getDeviceInfo
bool getDeviceInfo(realsense2_camera::DeviceInfo::Request &req, realsense2_camera::DeviceInfo::Response &res)
Definition: base_realsense_node.cpp:2562
realsense2_camera::BaseRealSenseNode::publishIntrinsics
void publishIntrinsics()
Definition: base_realsense_node.cpp:2141
realsense2_camera::BaseRealSenseNode::_depth_to_other_extrinsics_publishers
std::map< stream_index_pair, ros::Publisher > _depth_to_other_extrinsics_publishers
Definition: base_realsense_node.h:325
realsense2_camera::BaseRealSenseNode::_odom_frame_id
std::string _odom_frame_id
Definition: base_realsense_node.h:161
realsense2_camera::BaseRealSenseNode::_publish_odom_tf
bool _publish_odom_tf
Definition: base_realsense_node.h:309
realsense2_camera::BaseRealSenseNode::_height
std::map< stream_index_pair, int > _height
Definition: base_realsense_node.h:277
realsense2_camera::BaseRealSenseNode::registerDynamicReconfigCb
virtual void registerDynamicReconfigCb(ros::NodeHandle &nh) override
Definition: base_realsense_node.cpp:599
realsense2_camera::BaseRealSenseNode::OptionTemperatureDiag
std::pair< rs2_option, std::shared_ptr< TemperatureDiagnostics > > OptionTemperatureDiag
Definition: base_realsense_node.h:331
realsense2_camera::BaseRealSenseNode::SetBaseStream
void SetBaseStream()
Definition: base_realsense_node.cpp:2044
diagnostic_updater::FrequencyStatus::tick
void tick()
tf2_ros::StaticTransformBroadcaster
realsense2_camera::BaseRealSenseNode::_depth_aligned_image
std::map< stream_index_pair, cv::Mat > _depth_aligned_image
Definition: base_realsense_node.h:318
realsense2_camera::BaseRealSenseNode::float3::operator*=
float3 & operator*=(const float &factor)
Definition: base_realsense_node.h:143
realsense2_camera::BaseRealSenseNode::FillImuData_Copy
void FillImuData_Copy(const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
Definition: base_realsense_node.cpp:1416
realsense2_camera::FrequencyDiagnostics::frequency_status_
diagnostic_updater::FrequencyStatus frequency_status_
Definition: base_realsense_node.h:52
realsense2_camera::SyncedImuPublisher::getNumSubscribers
uint32_t getNumSubscribers()
Definition: base_realsense_node.h:105
dev
dev
realsense2_camera::BaseRealSenseNode::_depth_to_other_extrinsics
std::map< stream_index_pair, rs2_extrinsics > _depth_to_other_extrinsics
Definition: base_realsense_node.h:326
realsense_legacy_msgs::extrinsics_
realsense2_camera::FrequencyDiagnostics::update
void update()
Definition: base_realsense_node.h:46
uint32_t
unsigned int uint32_t
realsense2_camera::BaseRealSenseNode::BaseRealSenseNode
BaseRealSenseNode(ros::NodeHandle &nodeHandle, ros::NodeHandle &privateNodeHandle, rs2::device dev, const std::string &serial_no)
Definition: base_realsense_node.cpp:83
realsense2_camera::TemperatureDiagnostics::_crnt_temp
double _crnt_temp
Definition: base_realsense_node.h:70
realsense2_camera::BaseRealSenseNode::_width
std::map< stream_index_pair, int > _width
Definition: base_realsense_node.h:276
rs2::video_stream_profile
realsense2_camera::BaseRealSenseNode::runFirstFrameInitialization
void runFirstFrameInitialization(rs2_stream stream_type)
Definition: base_realsense_node.cpp:260
realsense2_camera::stream_index_pair
std::pair< rs2_stream, int > stream_index_pair
Definition: constants.h:99
realsense2_camera::BaseRealSenseNode::setupErrorCallback
void setupErrorCallback()
Definition: base_realsense_node.cpp:218
realsense2_camera::BaseRealSenseNode::_image_format
std::map< rs2_stream, int > _image_format
Definition: base_realsense_node.h:292
realsense2_camera::BaseRealSenseNode::CimuData::m_type
stream_index_pair m_type
Definition: base_realsense_node.h:191
realsense2_camera::FrequencyDiagnostics::FrequencyDiagnostics
FrequencyDiagnostics(double expected_frequency, std::string name, std::string hardware_id)
Definition: base_realsense_node.h:31
realsense2_camera::BaseRealSenseNode::clip_depth
void clip_depth(rs2::depth_frame depth_frame, float clipping_dist)
Definition: base_realsense_node.cpp:1325
realsense2_camera::BaseRealSenseNode::_depth_aligned_image_publishers
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _depth_aligned_image_publishers
Definition: base_realsense_node.h:324
realsense2_camera::BaseRealSenseNode::_depth_scaled_image
std::map< stream_index_pair, cv::Mat > _depth_scaled_image
Definition: base_realsense_node.h:319
rs2::points
realsense2_camera::BaseRealSenseNode::_image
std::map< stream_index_pair, cv::Mat > _image
Definition: base_realsense_node.h:295
realsense2_camera::BaseRealSenseNode::CreateUnitedMessage
sensor_msgs::Imu CreateUnitedMessage(const CimuData accel_data, const CimuData gyro_data)
Definition: base_realsense_node.cpp:1350
realsense2_camera::BaseRealSenseNode::getParameters
void getParameters()
Definition: base_realsense_node.cpp:715
realsense2_camera::BaseRealSenseNode::registerAutoExposureROIOptions
void registerAutoExposureROIOptions(ros::NodeHandle &nh)
Definition: base_realsense_node.cpp:414
realsense2_camera::TemperatureDiagnostics
Definition: base_realsense_node.h:57
realsense2_camera::BaseRealSenseNode::CimuData
Definition: base_realsense_node.h:183
stream
GLuint GLuint stream
diagnostic_updater
z
GLdouble GLdouble z
realsense2_camera::BaseRealSenseNode::_json_file_path
std::string _json_file_path
Definition: base_realsense_node.h:263
realsense2_camera::BaseRealSenseNode::_filters_str
std::string _filters_str
Definition: base_realsense_node.h:311
realsense2_camera::NamedFilter::_filter
std::shared_ptr< rs2::filter > _filter
Definition: base_realsense_node.h:79
realsense2_camera::BaseRealSenseNode::COPY
@ COPY
Definition: base_realsense_node.h:134
type
U1 type
realsense2_camera::BaseRealSenseNode::ImuMessage_AddDefaultValues
void ImuMessage_AddDefaultValues(sensor_msgs::Imu &imu_msg)
Definition: base_realsense_node.cpp:1432
realsense2_camera::BaseRealSenseNode::_encoding
std::map< rs2_stream, std::string > _encoding
Definition: base_realsense_node.h:296
realsense2_camera::BaseRealSenseNode::_filters
std::vector< NamedFilter > _filters
Definition: base_realsense_node.h:314
realsense2_camera::BaseRealSenseNode::_hold_back_imu_for_frames
bool _hold_back_imu_for_frames
Definition: base_realsense_node.h:273
rs2::sensor
realsense2_camera::BaseRealSenseNode::frame_callback
void frame_callback(rs2::frame frame)
Definition: base_realsense_node.cpp:1631
realsense2_camera::BaseRealSenseNode::_tf_publish_rate
double _tf_publish_rate
Definition: base_realsense_node.h:283
realsense2_camera::PipelineSyncer::operator()
void operator()(rs2::frame f) const
Definition: base_realsense_node.h:90
res
GLuint res
realsense2_camera::BaseRealSenseNode::_dynamic_tf_broadcaster
tf2_ros::TransformBroadcaster _dynamic_tf_broadcaster
Definition: base_realsense_node.h:285
seq
realsense2_camera::BaseRealSenseNode::pose_callback
void pose_callback(rs2::frame frame)
Definition: base_realsense_node.cpp:1538
filter
GLint GLint GLint GLint GLint GLint GLint GLbitfield GLenum filter
realsense2_camera::BaseRealSenseNode::_depth_aligned_frame_id
std::map< stream_index_pair, std::string > _depth_aligned_frame_id
Definition: base_realsense_node.h:164
rs2_option
rs2_option
realsense2_camera::BaseRealSenseNode::frameSystemTimeSec
double frameSystemTimeSec(rs2::frame frame)
Definition: base_realsense_node.cpp:1815
realsense2_camera::BaseRealSenseNode::_cv_tf
std::condition_variable _cv_tf
Definition: base_realsense_node.h:335
realsense2_camera::BaseRealSenseNode::_metadata_publishers
std::map< stream_index_pair, std::shared_ptr< ros::Publisher > > _metadata_publishers
Definition: base_realsense_node.h:294
realsense2_camera::BaseRealSenseNode::_monitor_options
std::vector< rs2_option > _monitor_options
Definition: base_realsense_node.h:167
realsense2_camera::SyncedImuPublisher::Pause
void Pause()
Definition: base_realsense_node.cpp:50
realsense2_camera::BaseRealSenseNode::_is_running
bool _is_running
Definition: base_realsense_node.h:159
realsense2_camera::BaseRealSenseNode::float3::operator+=
float3 & operator+=(const float3 &other)
Definition: base_realsense_node.h:150
realsense2_camera::BaseRealSenseNode::_format
std::map< rs2_stream, int > _format
Definition: base_realsense_node.h:279
realsense2_camera::FrequencyDiagnostics
Definition: base_realsense_node.h:29
realsense2_camera::BaseRealSenseNode::monitor_update_functions
void monitor_update_functions()
Definition: base_realsense_node.cpp:684
diagnostic_updater::Updater::setHardwareID
void setHardwareID(const std::string &hwid)
realsense2_camera::BaseRealSenseNode::_pointcloud_publisher
ros::Publisher _pointcloud_publisher
Definition: base_realsense_node.h:305
realsense2_camera::BaseRealSenseNode::_base_frame_id
std::string _base_frame_id
Definition: base_realsense_node.h:160
str
realsense2_camera::BaseRealSenseNode::_sync_frames
bool _sync_frames
Definition: base_realsense_node.h:307
realsense2_camera::SyncedImuPublisher
Definition: base_realsense_node.h:96
realsense2_camera::SyncedImuPublisher::_waiting_list_size
std::size_t _waiting_list_size
Definition: base_realsense_node.h:116
realsense2_camera::BaseRealSenseNode::float3
Definition: base_realsense_node.h:137
realsense2_camera::BaseRealSenseNode::_linear_accel_cov
double _linear_accel_cov
Definition: base_realsense_node.h:271
realsense2_camera::SyncedImuPublisher::_publisher
ros::Publisher _publisher
Definition: base_realsense_node.h:113
realsense2_camera::BaseRealSenseNode::getNamespaceStr
static std::string getNamespaceStr()
Definition: base_realsense_node.cpp:76
realsense2_camera::BaseRealSenseNode::_static_tf_broadcaster
tf2_ros::StaticTransformBroadcaster _static_tf_broadcaster
Definition: base_realsense_node.h:284
realsense2_camera::BaseRealSenseNode::_clipping_distance
float _clipping_distance
Definition: base_realsense_node.h:266
realsense2_camera::TemperatureDiagnostics::diagnostics
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &status)
Definition: base_realsense_node.cpp:2551
realsense2_camera::BaseRealSenseNode::publish_frequency_update
void publish_frequency_update()
Definition: base_realsense_node.cpp:2535
realsense2_camera::BaseRealSenseNode::_dev_sensors
std::vector< rs2::sensor > _dev_sensors
Definition: base_realsense_node.h:316
sensor_msgs::PointCloud2_< std::allocator< void > >
realsense2_camera::BaseRealSenseNode::_ddynrec
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > _ddynrec
Definition: base_realsense_node.h:261
diagnostic_updater::Updater::update
void update()
update_functions.h
option
realsense2_camera::BaseRealSenseNode::publish_temperature
void publish_temperature()
Definition: base_realsense_node.cpp:2514
realsense2_camera::FrequencyDiagnostics::diagnostic_updater_
diagnostic_updater::Updater diagnostic_updater_
Definition: base_realsense_node.h:53
ros::Time
realsense2_camera::BaseRealSenseNode::_info_publisher
std::map< stream_index_pair, ros::Publisher > _info_publisher
Definition: base_realsense_node.h:293
realsense2_camera::TemperatureDiagnostics::TemperatureDiagnostics
TemperatureDiagnostics(std::string name, std::string serial_no)
Definition: base_realsense_node.cpp:2545
realsense2_camera::BaseRealSenseNode::CimuData::m_data
Eigen::Vector3d m_data
Definition: base_realsense_node.h:194
realsense2_camera
Definition: base_realsense_node.h:27
realsense2_camera::BaseRealSenseNode::CimuData::is_set
bool is_set()
Definition: base_realsense_node.h:191
realsense2_camera::BaseRealSenseNode::set_sensor_auto_exposure_roi
void set_sensor_auto_exposure_roi(rs2::sensor sensor)
Definition: base_realsense_node.cpp:388
t
GLdouble t
rs2::depth_frame
realsense2_camera::NamedFilter::_name
std::string _name
Definition: base_realsense_node.h:78
realsense2_camera::SyncedImuPublisher::_pause_mode
bool _pause_mode
Definition: base_realsense_node.h:114
realsense2_camera::BaseRealSenseNode::_unit_step_size
std::map< rs2_stream, int > _unit_step_size
Definition: base_realsense_node.h:299
realsense2_camera::BaseRealSenseNode::_depth_aligned_camera_info
std::map< stream_index_pair, sensor_msgs::CameraInfo > _depth_aligned_camera_info
Definition: base_realsense_node.h:321
realsense2_camera::BaseRealSenseNode::_sensors
std::map< stream_index_pair, rs2::sensor > _sensors
Definition: base_realsense_node.h:259
realsense2_camera::BaseRealSenseNode::_imu_publishers
std::map< stream_index_pair, ros::Publisher > _imu_publishers
Definition: base_realsense_node.h:290
realsense2_camera::BaseRealSenseNode::_optical_frame_id
std::map< stream_index_pair, std::string > _optical_frame_id
Definition: base_realsense_node.h:163
realsense2_camera::BaseRealSenseNode::multiple_message_callback
void multiple_message_callback(rs2::frame frame, imu_sync_method sync_method)
Definition: base_realsense_node.cpp:1784
realsense2_camera::TemperatureDiagnostics::update
void update(double crnt_temperaure)
Definition: base_realsense_node.h:63
realsense2_camera::BaseRealSenseNode::publish_static_tf
void publish_static_tf(const ros::Time &t, const float3 &trans, const tf::Quaternion &q, const std::string &from, const std::string &to)
Definition: base_realsense_node.cpp:1981
realsense2_camera::NamedFilter
Definition: base_realsense_node.h:75
realsense2_camera::BaseRealSenseNode::_serial_no
std::string _serial_no
Definition: base_realsense_node.h:264
tf2_ros::TransformBroadcaster
realsense2_camera::BaseRealSenseNode::_update_functions_v
std::vector< std::function< void()> > _update_functions_v
Definition: base_realsense_node.h:334
realsense2_camera::BaseRealSenseNode::_sensors_callback
std::map< std::string, std::function< void(rs2::frame)> > _sensors_callback
Definition: base_realsense_node.h:260
static_transform_broadcaster.h
realsense2_camera::BaseRealSenseNode::publishServices
void publishServices()
Definition: base_realsense_node.cpp:2557
realsense2_camera::BaseRealSenseNode::set_auto_exposure_roi
void set_auto_exposure_roi(const std::string option_name, rs2::sensor sensor, int new_value)
Definition: base_realsense_node.cpp:369
realsense2_camera::BaseRealSenseNode::setupDevice
void setupDevice()
Definition: base_realsense_node.cpp:820
realsense2_camera::BaseRealSenseNode::updateStreamCalibData
void updateStreamCalibData(const rs2::video_stream_profile &video_profile)
Definition: base_realsense_node.cpp:1883
realsense2_camera::BaseRealSenseNode::float3::z
float z
Definition: base_realsense_node.h:140
realsense2_camera::BaseRealSenseNode::FillImuData_LinearInterpolation
void FillImuData_LinearInterpolation(const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
Definition: base_realsense_node.cpp:1371
realsense2_camera::BaseRealSenseNode::_angular_velocity_cov
double _angular_velocity_cov
Definition: base_realsense_node.h:272
diagnostic_updater::DiagnosticStatusWrapper
realsense2_camera::SyncedImuPublisher::Publish
void Publish(sensor_msgs::Imu msg)
Definition: base_realsense_node.cpp:31
realsense2_camera::BaseRealSenseNode::_pnh
ros::NodeHandle _pnh
Definition: base_realsense_node.h:165
realsense2_camera::BaseRealSenseNode::publishDynamicTransforms
void publishDynamicTransforms()
Definition: base_realsense_node.cpp:2122
realsense2_camera::BaseRealSenseNode::_valid_pc_indices
std::vector< unsigned int > _valid_pc_indices
Definition: base_realsense_node.h:341
realsense2_camera::BaseRealSenseNode::publishTopics
virtual void publishTopics() override
Definition: base_realsense_node.cpp:240
realsense2_camera::BaseRealSenseNode::NONE
@ NONE
Definition: base_realsense_node.h:134
PointCloud2.h
realsense2_camera::BaseRealSenseNode::_colorizer
std::shared_ptr< rs2::filter > _colorizer
Definition: base_realsense_node.h:315
realsense2_camera::BaseRealSenseNode::setupFilters
void setupFilters()
Definition: base_realsense_node.cpp:1185
realsense2_camera::BaseRealSenseNode::CimuData::CimuData
CimuData()
Definition: base_realsense_node.h:186
realsense2_camera::BaseRealSenseNode::getAProfile
rs2::stream_profile getAProfile(const stream_index_pair &stream)
Definition: base_realsense_node.cpp:2324
x
GLdouble x
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
realsense2_camera::SyncedImuPublisher::_pending_messages
std::queue< sensor_msgs::Imu > _pending_messages
Definition: base_realsense_node.h:115
realsense2_camera::BaseRealSenseNode::_update_functions_t
std::shared_ptr< std::thread > _update_functions_t
Definition: base_realsense_node.h:287
realsense2_camera::BaseRealSenseNode::_ordered_pc
bool _ordered_pc
Definition: base_realsense_node.h:268
rs2_timestamp_domain
rs2_timestamp_domain
realsense2_camera::BaseRealSenseNode::_depth_scale_meters
float _depth_scale_meters
Definition: base_realsense_node.h:265
realsense2_camera::BaseRealSenseNode::_is_first_frame
std::map< rs2_stream, bool > _is_first_frame
Definition: base_realsense_node.h:328
realsense2_camera::SyncedImuPublisher::SyncedImuPublisher
SyncedImuPublisher()
Definition: base_realsense_node.h:99
realsense2_camera::BaseRealSenseNode::_depth_aligned_info_publisher
std::map< stream_index_pair, ros::Publisher > _depth_aligned_info_publisher
Definition: base_realsense_node.h:323
realsense2_camera::BaseRealSenseNode::_dev
rs2::device _dev
Definition: base_realsense_node.h:258
realsense2_camera::BaseRealSenseNode::_image_publishers
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _image_publishers
Definition: base_realsense_node.h:289
realsense2_camera::BaseRealSenseNode::_is_initialized_time_base
std::atomic_bool _is_initialized_time_base
Definition: base_realsense_node.h:301
Imu.h
realsense2_camera::BaseRealSenseNode::_depth_aligned_seq
std::map< stream_index_pair, int > _depth_aligned_seq
Definition: base_realsense_node.h:322
ROS_INFO
#define ROS_INFO(...)
realsense2_camera::SyncedImuPublisher::_is_enabled
bool _is_enabled
Definition: base_realsense_node.h:117
diagnostic_updater::DiagnosticTaskVector::add
void add(const std::string &name, TaskFunction f)
realsense2_camera::BaseRealSenseNode::imu_callback_sync
void imu_callback_sync(rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY)
Definition: base_realsense_node.cpp:1445
realsense2_camera::BaseRealSenseNode::publishStaticTransforms
void publishStaticTransforms()
Definition: base_realsense_node.cpp:2062
realsense2_camera::BaseRealSenseNode::registerDynamicOption
void registerDynamicOption(ros::NodeHandle &nh, rs2::options sensor, std::string &module_name)
Definition: base_realsense_node.cpp:447
realsense2_camera::BaseRealSenseNode::_temperature_nodes
std::vector< OptionTemperatureDiag > _temperature_nodes
Definition: base_realsense_node.h:332
tf::Quaternion
realsense2_camera::SyncedImuPublisher::_mutex
std::mutex _mutex
Definition: base_realsense_node.h:112
realsense2_camera::FrequencyDiagnostics::tick
void tick()
Definition: base_realsense_node.h:41
realsense2_camera::BaseRealSenseNode::readAndSetDynamicParam
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)
Definition: base_realsense_node.cpp:401
realsense2_camera::InterfaceRealSenseNode
Definition: realsense_node_factory.h:48
rs2_stream
rs2_stream
realsense2_camera::BaseRealSenseNode::float3::y
float y
Definition: base_realsense_node.h:140
realsense2_camera::BaseRealSenseNode::~BaseRealSenseNode
virtual ~BaseRealSenseNode()
Definition: base_realsense_node.cpp:137
realsense2_camera::BaseRealSenseNode::startMonitoring
void startMonitoring()
Definition: base_realsense_node.cpp:2491
realsense2_camera::SyncedImuPublisher::Resume
void Resume()
Definition: base_realsense_node.cpp:57
profile
ros::NodeHandle
realsense2_camera::ImagePublisherWithFrequencyDiagnostics
std::pair< image_transport::Publisher, std::shared_ptr< FrequencyDiagnostics > > ImagePublisherWithFrequencyDiagnostics
Definition: base_realsense_node.h:55
realsense2_camera::BaseRealSenseNode::_device_info_srv
std::shared_ptr< ros::ServiceServer > _device_info_srv
Definition: base_realsense_node.h:168
realsense2_camera::BaseRealSenseNode::_seq
std::map< stream_index_pair, int > _seq
Definition: base_realsense_node.h:298
realsense2_camera::BaseRealSenseNode::rotationMatrixToQuaternion
tf::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const
Definition: base_realsense_node.cpp:1969
realsense2_camera::BaseRealSenseNode::setupStreams
void setupStreams()
Definition: base_realsense_node.cpp:1828
realsense2_camera::BaseRealSenseNode::publishFrame
void publishFrame(rs2::frame f, const ros::Time &t, const stream_index_pair &stream, std::map< stream_index_pair, cv::Mat > &images, const std::map< stream_index_pair, ros::Publisher > &info_publishers, const std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > &image_publishers, const bool is_publishMetadata, std::map< stream_index_pair, int > &seq, std::map< stream_index_pair, sensor_msgs::CameraInfo > &camera_info, const std::map< rs2_stream, std::string > &encoding, bool copy_data_from_frame=true)
Definition: base_realsense_node.cpp:2363
realsense2_camera::BaseRealSenseNode::_base_stream
stream_index_pair _base_stream
Definition: base_realsense_node.h:337
y
GLint y
realsense2_camera::BaseRealSenseNode::publishMetadata
void publishMetadata(rs2::frame f, const ros::Time &header_time, const std::string &frame_id)
Definition: base_realsense_node.cpp:2437


realsense2_camera
Author(s): Sergey Dorodnicov , Doron Hirshberg
autogenerated on Fri Mar 25 2022 02:15:35