Go to the documentation of this file.
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>
126 const std::string& serial_no);
171 bool getDeviceInfo(realsense2_camera::DeviceInfo::Request& req,
172 realsense2_camera::DeviceInfo::Response&
res);
178 const std::string& from,
179 const std::string& to);
208 cv::Mat&
fix_depth_scale(
const cv::Mat& from_image, cv::Mat& to_image);
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);
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::condition_variable _update_functions_cv
void imu_callback(rs2::frame frame)
sensor_msgs::PointCloud2 _msg_pointcloud
rs2_stream rs2_string_to_stream(std::string str)
GLenum GLenum GLsizei const GLuint GLboolean enabled
void set_sensor_parameter_to_ros(const std::string &module_name, rs2::options sensor, rs2_option option)
imu_sync_method _imu_sync_method
std::map< stream_index_pair, bool > _enable
CimuData(const stream_index_pair type, Eigen::Vector3d data, double time)
bool getEnabledProfile(const stream_index_pair &stream_index, rs2::stream_profile &profile)
std::shared_ptr< rs2::filter > _pointcloud_filter
bool _allow_no_texture_points
std::map< rs2_stream, std::vector< std::function< void()> > > _video_functions_stack
void registerHDRoptions()
std::shared_ptr< SyncedImuPublisher > _synced_imu_publisher
std::shared_ptr< std::thread > _tf_t
virtual void toggleSensors(bool enabled) override
const std::string _namespace
std::map< stream_index_pair, std::vector< rs2::stream_profile > > _enabled_profiles
ros::NodeHandle & _node_handle
stream_index_pair _pointcloud_texture
IMUInfo getImuInfo(const stream_index_pair &stream_index)
virtual void calcAndPublishStaticTransform(const stream_index_pair &stream, const rs2::stream_profile &base_profile)
std::map< rs2_stream, std::string > _stream_name
std::map< stream_index_pair, std::string > _frame_id
void publishPointCloud(rs2::points f, const ros::Time &t, const rs2::frameset &frameset)
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
std::map< stream_index_pair, sensor_msgs::CameraInfo > _camera_info
void publishAlignedDepthToOthers(rs2::frameset frames, const ros::Time &t)
GLdouble GLdouble GLdouble q
std::shared_ptr< std::thread > _monitoring_t
cv::Mat & fix_depth_scale(const cv::Mat &from_image, cv::Mat &to_image)
std::map< stream_index_pair, int > _fps
std::vector< geometry_msgs::TransformStamped > _static_tf_msgs
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
void invoke(frame f) const
std::map< rs2_stream, std::string > _depth_aligned_encoding
std::condition_variable _cv_monitoring
std::map< std::string, rs2::region_of_interest > _auto_exposure_roi
diagnostic_updater::Updater _updater
NamedFilter(std::string name, std::shared_ptr< rs2::filter > filter)
Extrinsics rsExtrinsicsToMsg(const rs2_extrinsics &extrinsics, const std::string &frame_id) const
bool setBaseTime(double frame_time, rs2_timestamp_domain time_domain)
double expected_frequency_
void PublishPendingMessages()
std::map< stream_index_pair, rs2_intrinsics > _stream_intrinsics
void Enable(bool is_enabled)
bool getDeviceInfo(realsense2_camera::DeviceInfo::Request &req, realsense2_camera::DeviceInfo::Response &res)
std::map< stream_index_pair, ros::Publisher > _depth_to_other_extrinsics_publishers
std::string _odom_frame_id
std::map< stream_index_pair, int > _height
virtual void registerDynamicReconfigCb(ros::NodeHandle &nh) override
std::pair< rs2_option, std::shared_ptr< TemperatureDiagnostics > > OptionTemperatureDiag
std::map< stream_index_pair, cv::Mat > _depth_aligned_image
float3 & operator*=(const float &factor)
void FillImuData_Copy(const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
diagnostic_updater::FrequencyStatus frequency_status_
uint32_t getNumSubscribers()
std::map< stream_index_pair, rs2_extrinsics > _depth_to_other_extrinsics
BaseRealSenseNode(ros::NodeHandle &nodeHandle, ros::NodeHandle &privateNodeHandle, rs2::device dev, const std::string &serial_no)
std::map< stream_index_pair, int > _width
void runFirstFrameInitialization(rs2_stream stream_type)
std::pair< rs2_stream, int > stream_index_pair
void setupErrorCallback()
std::map< rs2_stream, int > _image_format
FrequencyDiagnostics(double expected_frequency, std::string name, std::string hardware_id)
void clip_depth(rs2::depth_frame depth_frame, float clipping_dist)
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _depth_aligned_image_publishers
std::map< stream_index_pair, cv::Mat > _depth_scaled_image
std::map< stream_index_pair, cv::Mat > _image
sensor_msgs::Imu CreateUnitedMessage(const CimuData accel_data, const CimuData gyro_data)
void registerAutoExposureROIOptions(ros::NodeHandle &nh)
std::string _json_file_path
std::shared_ptr< rs2::filter > _filter
void ImuMessage_AddDefaultValues(sensor_msgs::Imu &imu_msg)
std::map< rs2_stream, std::string > _encoding
std::vector< NamedFilter > _filters
bool _hold_back_imu_for_frames
void frame_callback(rs2::frame frame)
void operator()(rs2::frame f) const
tf2_ros::TransformBroadcaster _dynamic_tf_broadcaster
void pose_callback(rs2::frame frame)
GLint GLint GLint GLint GLint GLint GLint GLbitfield GLenum filter
std::map< stream_index_pair, std::string > _depth_aligned_frame_id
double frameSystemTimeSec(rs2::frame frame)
std::condition_variable _cv_tf
std::map< stream_index_pair, std::shared_ptr< ros::Publisher > > _metadata_publishers
std::vector< rs2_option > _monitor_options
float3 & operator+=(const float3 &other)
std::map< rs2_stream, int > _format
void monitor_update_functions()
void setHardwareID(const std::string &hwid)
ros::Publisher _pointcloud_publisher
std::string _base_frame_id
std::size_t _waiting_list_size
ros::Publisher _publisher
static std::string getNamespaceStr()
tf2_ros::StaticTransformBroadcaster _static_tf_broadcaster
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &status)
void publish_frequency_update()
std::vector< rs2::sensor > _dev_sensors
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > _ddynrec
void publish_temperature()
diagnostic_updater::Updater diagnostic_updater_
std::map< stream_index_pair, ros::Publisher > _info_publisher
TemperatureDiagnostics(std::string name, std::string serial_no)
void set_sensor_auto_exposure_roi(rs2::sensor sensor)
std::map< rs2_stream, int > _unit_step_size
std::map< stream_index_pair, sensor_msgs::CameraInfo > _depth_aligned_camera_info
std::map< stream_index_pair, rs2::sensor > _sensors
std::map< stream_index_pair, ros::Publisher > _imu_publishers
std::map< stream_index_pair, std::string > _optical_frame_id
void multiple_message_callback(rs2::frame frame, imu_sync_method sync_method)
void update(double crnt_temperaure)
void publish_static_tf(const ros::Time &t, const float3 &trans, const tf::Quaternion &q, const std::string &from, const std::string &to)
std::vector< std::function< void()> > _update_functions_v
std::map< std::string, std::function< void(rs2::frame)> > _sensors_callback
void set_auto_exposure_roi(const std::string option_name, rs2::sensor sensor, int new_value)
void updateStreamCalibData(const rs2::video_stream_profile &video_profile)
void FillImuData_LinearInterpolation(const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
double _angular_velocity_cov
void Publish(sensor_msgs::Imu msg)
void publishDynamicTransforms()
std::vector< unsigned int > _valid_pc_indices
virtual void publishTopics() override
std::shared_ptr< rs2::filter > _colorizer
rs2::stream_profile getAProfile(const stream_index_pair &stream)
uint32_t getNumSubscribers() const
std::queue< sensor_msgs::Imu > _pending_messages
std::shared_ptr< std::thread > _update_functions_t
float _depth_scale_meters
std::map< rs2_stream, bool > _is_first_frame
std::map< stream_index_pair, ros::Publisher > _depth_aligned_info_publisher
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics > _image_publishers
std::atomic_bool _is_initialized_time_base
std::map< stream_index_pair, int > _depth_aligned_seq
void add(const std::string &name, TaskFunction f)
void imu_callback_sync(rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY)
void publishStaticTransforms()
void registerDynamicOption(ros::NodeHandle &nh, rs2::options sensor, std::string &module_name)
std::vector< OptionTemperatureDiag > _temperature_nodes
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)
virtual ~BaseRealSenseNode()
std::pair< image_transport::Publisher, std::shared_ptr< FrequencyDiagnostics > > ImagePublisherWithFrequencyDiagnostics
std::shared_ptr< ros::ServiceServer > _device_info_srv
std::map< stream_index_pair, int > _seq
tf::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const
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)
stream_index_pair _base_stream
void publishMetadata(rs2::frame f, const ros::Time &header_time, const std::string &frame_id)
realsense2_camera
Author(s): Sergey Dorodnicov
, Doron Hirshberg
autogenerated on Fri Mar 25 2022 02:15:35