7 #include <realsense2_camera/DeviceInfo.h> 8 #include "realsense2_camera/Metadata.h" 15 #include <sensor_msgs/point_cloud2_iterator.h> 17 #include <nav_msgs/Odometry.h> 20 #include <condition_variable> 65 _crnt_temp = crnt_temperaure;
83 _name(name), _filter(filter)
106 void Enable(
bool is_enabled) {_is_enabled=is_enabled;};
109 void PublishPendingMessages();
126 const std::string& serial_no);
128 virtual void toggleSensors(
bool enabled)
override;
129 virtual void publishTopics()
override;
171 bool getDeviceInfo(realsense2_camera::DeviceInfo::Request& req,
172 realsense2_camera::DeviceInfo::Response&
res);
174 tf::Quaternion rotationMatrixToQuaternion(
const float rotation[9])
const;
178 const std::string& from,
179 const std::string& to);
191 bool is_set() {
return m_time > 0;};
198 static std::string getNamespaceStr();
199 void getParameters();
201 void setupErrorCallback();
202 void setupPublishers();
203 void enable_devices();
208 cv::Mat& fix_depth_scale(
const cv::Mat& from_image, cv::Mat& to_image);
211 void SetBaseStream();
212 void publishStaticTransforms();
213 void publishDynamicTransforms();
214 void publishIntrinsics();
215 void runFirstFrameInitialization(
rs2_stream stream_type);
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);
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);
245 void registerHDRoptions();
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);
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);
253 void startMonitoring();
254 void publish_temperature();
255 void publish_frequency_update();
256 void publishServices();
261 std::vector<std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure>>
_ddynrec;
278 std::map<stream_index_pair, int>
_fps;
295 std::map<stream_index_pair, cv::Mat>
_image;
298 std::map<stream_index_pair, int>
_seq;
std::map< stream_index_pair, cv::Mat > _depth_aligned_image
std::map< stream_index_pair, int > _seq
std::map< rs2_stream, int > _image_format
void update(double crnt_temperaure)
tf2_ros::StaticTransformBroadcaster _static_tf_broadcaster
std::vector< NamedFilter > _filters
float3 & operator+=(const float3 &other)
ros::Publisher _publisher
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)
double _angular_velocity_cov
std::size_t _waiting_list_size
std::string _base_frame_id
ros::Publisher _pointcloud_publisher
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
stream_index_pair _pointcloud_texture
std::map< rs2_stream, bool > _is_first_frame
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _image_publishers
std::atomic_bool _is_initialized_time_base
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
std::map< stream_index_pair, sensor_msgs::CameraInfo > _depth_aligned_camera_info
std::vector< OptionTemperatureDiag > _temperature_nodes
std::map< stream_index_pair, rs2::sensor > _sensors
std::map< stream_index_pair, int > _width
std::pair< rs2_stream, int > stream_index_pair
sensor_msgs::PointCloud2 _msg_pointcloud
double expected_frequency_
std::map< stream_index_pair, std::shared_ptr< ros::Publisher > > _metadata_publishers
std::map< stream_index_pair, rs2_extrinsics > _depth_to_other_extrinsics
float _depth_scale_meters
std::map< rs2_stream, std::string > _encoding
std::map< stream_index_pair, bool > _enable
std::map< stream_index_pair, cv::Mat > _image
bool _allow_no_texture_points
std::map< rs2_stream, std::vector< std::function< void()> > > _video_functions_stack
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
imu_sync_method _imu_sync_method
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
const std::string _namespace
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
void Enable(bool is_enabled)
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
stream_index_pair _base_stream
diagnostic_updater::Updater _updater
std::vector< rs2::sensor > _dev_sensors
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > _ddynrec
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
uint32_t getNumSubscribers()
std::string _json_file_path
std::map< stream_index_pair, ros::Publisher > _depth_aligned_info_publisher
std::map< stream_index_pair, std::string > _optical_frame_id
float3 & operator*=(const float &factor)
bool _hold_back_imu_for_frames
std::string _odom_frame_id
std::map< stream_index_pair, std::string > _depth_aligned_frame_id
diagnostic_updater::Updater diagnostic_updater_
std::map< rs2_stream, int > _format