Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
realsense2_camera::BaseRealSenseNode Class Reference

#include <base_realsense_node.h>

Inheritance diagram for realsense2_camera::BaseRealSenseNode:
Inheritance graph
[legend]

Classes

class  CimuData
 
class  float3
 

Public Types

enum  imu_sync_method { NONE, COPY, LINEAR_INTERPOLATION }
 

Public Member Functions

 BaseRealSenseNode (ros::NodeHandle &nodeHandle, ros::NodeHandle &privateNodeHandle, rs2::device dev, const std::string &serial_no)
 
virtual void publishTopics () override
 
virtual void registerDynamicReconfigCb (ros::NodeHandle &nh) override
 
virtual void toggleSensors (bool enabled) override
 
virtual ~BaseRealSenseNode ()
 
- Public Member Functions inherited from realsense2_camera::InterfaceRealSenseNode
virtual ~InterfaceRealSenseNode ()=default
 

Protected Member Functions

virtual void calcAndPublishStaticTransform (const stream_index_pair &stream, const rs2::stream_profile &base_profile)
 
rs2::stream_profile getAProfile (const stream_index_pair &stream)
 
bool getDeviceInfo (realsense2_camera::DeviceInfo::Request &req, realsense2_camera::DeviceInfo::Response &res)
 
void publish_static_tf (const ros::Time &t, const float3 &trans, const tf::Quaternion &q, const std::string &from, const std::string &to)
 
tf::Quaternion rotationMatrixToQuaternion (const float rotation[9]) const
 

Protected Attributes

bool _align_depth
 
std::string _base_frame_id
 
std::map< stream_index_pair, std::string_depth_aligned_frame_id
 
std::shared_ptr< ros::ServiceServer_device_info_srv
 
std::map< stream_index_pair, std::string_frame_id
 
bool _is_running
 
std::vector< rs2_option_monitor_options
 
ros::NodeHandle_node_handle
 
std::string _odom_frame_id
 
std::map< stream_index_pair, std::string_optical_frame_id
 
ros::NodeHandle _pnh
 

Private Types

typedef std::pair< rs2_option, std::shared_ptr< TemperatureDiagnostics > > OptionTemperatureDiag
 

Private Member Functions

void clip_depth (rs2::depth_frame depth_frame, float clipping_dist)
 
sensor_msgs::Imu CreateUnitedMessage (const CimuData accel_data, const CimuData gyro_data)
 
void enable_devices ()
 
void FillImuData_Copy (const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
 
void FillImuData_LinearInterpolation (const CimuData imu_data, std::deque< sensor_msgs::Imu > &imu_msgs)
 
cv::Mat & fix_depth_scale (const cv::Mat &from_image, cv::Mat &to_image)
 
void frame_callback (rs2::frame frame)
 
double frameSystemTimeSec (rs2::frame frame)
 
bool getEnabledProfile (const stream_index_pair &stream_index, rs2::stream_profile &profile)
 
IMUInfo getImuInfo (const stream_index_pair &stream_index)
 
void getParameters ()
 
void imu_callback (rs2::frame frame)
 
void imu_callback_sync (rs2::frame frame, imu_sync_method sync_method=imu_sync_method::COPY)
 
void ImuMessage_AddDefaultValues (sensor_msgs::Imu &imu_msg)
 
void monitor_update_functions ()
 
void multiple_message_callback (rs2::frame frame, imu_sync_method sync_method)
 
void pose_callback (rs2::frame frame)
 
void publish_frequency_update ()
 
void publish_temperature ()
 
void publishAlignedDepthToOthers (rs2::frameset frames, const ros::Time &t)
 
void publishDynamicTransforms ()
 
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)
 
void publishIntrinsics ()
 
void publishMetadata (rs2::frame f, const ros::Time &header_time, const std::string &frame_id)
 
void publishPointCloud (rs2::points f, const ros::Time &t, const rs2::frameset &frameset)
 
void publishServices ()
 
void publishStaticTransforms ()
 
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)
 
void registerAutoExposureROIOptions (ros::NodeHandle &nh)
 
void registerDynamicOption (ros::NodeHandle &nh, rs2::options sensor, std::string &module_name)
 
void registerHDRoptions ()
 
rs2_stream rs2_string_to_stream (std::string str)
 
Extrinsics rsExtrinsicsToMsg (const rs2_extrinsics &extrinsics, const std::string &frame_id) const
 
void runFirstFrameInitialization (rs2_stream stream_type)
 
void set_auto_exposure_roi (const std::string option_name, rs2::sensor sensor, int new_value)
 
void set_sensor_auto_exposure_roi (rs2::sensor sensor)
 
void set_sensor_parameter_to_ros (const std::string &module_name, rs2::options sensor, rs2_option option)
 
void SetBaseStream ()
 
bool setBaseTime (double frame_time, rs2_timestamp_domain time_domain)
 
void setupDevice ()
 
void setupErrorCallback ()
 
void setupFilters ()
 
void setupPublishers ()
 
void setupStreams ()
 
void startMonitoring ()
 
void updateStreamCalibData (const rs2::video_stream_profile &video_profile)
 

Static Private Member Functions

static std::string getNamespaceStr ()
 

Private Attributes

bool _allow_no_texture_points
 
double _angular_velocity_cov
 
std::map< std::string, rs2::region_of_interest_auto_exposure_roi
 
stream_index_pair _base_stream
 
std::map< stream_index_pair, sensor_msgs::CameraInfo_camera_info
 
double _camera_time_base
 
float _clipping_distance
 
std::shared_ptr< rs2::filter_colorizer
 
std::condition_variable _cv_monitoring
 
std::condition_variable _cv_tf
 
std::vector< std::shared_ptr< ddynamic_reconfigure::DDynamicReconfigure > > _ddynrec
 
std::map< stream_index_pair, sensor_msgs::CameraInfo_depth_aligned_camera_info
 
std::map< rs2_stream, std::string_depth_aligned_encoding
 
std::map< stream_index_pair, cv::Mat > _depth_aligned_image
 
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics_depth_aligned_image_publishers
 
std::map< stream_index_pair, ros::Publisher_depth_aligned_info_publisher
 
std::map< stream_index_pair, int > _depth_aligned_seq
 
float _depth_scale_meters
 
std::map< stream_index_pair, cv::Mat > _depth_scaled_image
 
std::map< stream_index_pair, rs2_extrinsics_depth_to_other_extrinsics
 
std::map< stream_index_pair, ros::Publisher_depth_to_other_extrinsics_publishers
 
rs2::device _dev
 
std::vector< rs2::sensor_dev_sensors
 
tf2_ros::TransformBroadcaster _dynamic_tf_broadcaster
 
std::map< stream_index_pair, bool > _enable
 
std::map< stream_index_pair, std::vector< rs2::stream_profile > > _enabled_profiles
 
std::map< rs2_stream, std::string_encoding
 
std::vector< NamedFilter_filters
 
std::string _filters_str
 
std::map< rs2_stream, int > _format
 
std::map< stream_index_pair, int > _fps
 
std::map< stream_index_pair, int > _height
 
bool _hold_back_imu_for_frames
 
std::map< stream_index_pair, cv::Mat > _image
 
std::map< rs2_stream, int > _image_format
 
std::map< stream_index_pair, ImagePublisherWithFrequencyDiagnostics_image_publishers
 
std::map< stream_index_pair, ros::Publisher_imu_publishers
 
imu_sync_method _imu_sync_method
 
std::map< stream_index_pair, ros::Publisher_info_publisher
 
std::map< rs2_stream, bool > _is_first_frame
 
std::atomic_bool _is_initialized_time_base
 
std::string _json_file_path
 
double _linear_accel_cov
 
std::map< stream_index_pair, std::shared_ptr< ros::Publisher > > _metadata_publishers
 
std::shared_ptr< std::thread > _monitoring_t
 
sensor_msgs::PointCloud2 _msg_pointcloud
 
const std::string _namespace
 
bool _ordered_pc
 
bool _pointcloud
 
std::shared_ptr< rs2::filter_pointcloud_filter
 
ros::Publisher _pointcloud_publisher
 
stream_index_pair _pointcloud_texture
 
bool _publish_odom_tf
 
bool _publish_tf
 
ros::Time _ros_time_base
 
std::map< stream_index_pair, rs2::sensor_sensors
 
std::map< std::string, std::function< void(rs2::frame)> > _sensors_callback
 
std::map< stream_index_pair, int > _seq
 
std::string _serial_no
 
tf2_ros::StaticTransformBroadcaster _static_tf_broadcaster
 
std::vector< geometry_msgs::TransformStamped_static_tf_msgs
 
std::map< stream_index_pair, rs2_intrinsics_stream_intrinsics
 
std::map< rs2_stream, std::string_stream_name
 
bool _sync_frames
 
std::shared_ptr< SyncedImuPublisher_synced_imu_publisher
 
PipelineSyncer _syncer
 
std::vector< OptionTemperatureDiag_temperature_nodes
 
double _tf_publish_rate
 
std::shared_ptr< std::thread > _tf_t
 
std::map< rs2_stream, int > _unit_step_size
 
std::condition_variable _update_functions_cv
 
std::shared_ptr< std::thread > _update_functions_t
 
std::vector< std::function< void()> > _update_functions_v
 
std::vector< unsigned int > _valid_pc_indices
 
std::map< rs2_stream, std::vector< std::function< void()> > > _video_functions_stack
 
std::map< stream_index_pair, int > _width
 

Detailed Description

Definition at line 120 of file base_realsense_node.h.

Member Typedef Documentation

◆ OptionTemperatureDiag

Definition at line 331 of file base_realsense_node.h.

Member Enumeration Documentation

◆ imu_sync_method

Enumerator
NONE 
COPY 
LINEAR_INTERPOLATION 

Definition at line 134 of file base_realsense_node.h.

Constructor & Destructor Documentation

◆ BaseRealSenseNode()

BaseRealSenseNode::BaseRealSenseNode ( ros::NodeHandle nodeHandle,
ros::NodeHandle privateNodeHandle,
rs2::device  dev,
const std::string serial_no 
)

Definition at line 83 of file base_realsense_node.cpp.

◆ ~BaseRealSenseNode()

BaseRealSenseNode::~BaseRealSenseNode ( )
virtual

Definition at line 137 of file base_realsense_node.cpp.

Member Function Documentation

◆ calcAndPublishStaticTransform()

void BaseRealSenseNode::calcAndPublishStaticTransform ( const stream_index_pair stream,
const rs2::stream_profile base_profile 
)
protectedvirtual

Reimplemented in realsense2_camera::T265RealsenseNode.

Definition at line 2001 of file base_realsense_node.cpp.

◆ clip_depth()

void BaseRealSenseNode::clip_depth ( rs2::depth_frame  depth_frame,
float  clipping_dist 
)
private

Definition at line 1325 of file base_realsense_node.cpp.

◆ CreateUnitedMessage()

sensor_msgs::Imu BaseRealSenseNode::CreateUnitedMessage ( const CimuData  accel_data,
const CimuData  gyro_data 
)
private

Definition at line 1350 of file base_realsense_node.cpp.

◆ enable_devices()

void BaseRealSenseNode::enable_devices ( )
private

Definition at line 1058 of file base_realsense_node.cpp.

◆ FillImuData_Copy()

void BaseRealSenseNode::FillImuData_Copy ( const CimuData  imu_data,
std::deque< sensor_msgs::Imu > &  imu_msgs 
)
private

Definition at line 1416 of file base_realsense_node.cpp.

◆ FillImuData_LinearInterpolation()

void BaseRealSenseNode::FillImuData_LinearInterpolation ( const CimuData  imu_data,
std::deque< sensor_msgs::Imu > &  imu_msgs 
)
private

Definition at line 1371 of file base_realsense_node.cpp.

◆ fix_depth_scale()

cv::Mat & BaseRealSenseNode::fix_depth_scale ( const cv::Mat &  from_image,
cv::Mat &  to_image 
)
private

Definition at line 1285 of file base_realsense_node.cpp.

◆ frame_callback()

void BaseRealSenseNode::frame_callback ( rs2::frame  frame)
private

Definition at line 1631 of file base_realsense_node.cpp.

◆ frameSystemTimeSec()

double BaseRealSenseNode::frameSystemTimeSec ( rs2::frame  frame)
private

Definition at line 1815 of file base_realsense_node.cpp.

◆ getAProfile()

rs2::stream_profile BaseRealSenseNode::getAProfile ( const stream_index_pair stream)
protected

Definition at line 2324 of file base_realsense_node.cpp.

◆ getDeviceInfo()

bool BaseRealSenseNode::getDeviceInfo ( realsense2_camera::DeviceInfo::Request &  req,
realsense2_camera::DeviceInfo::Response &  res 
)
protected

Definition at line 2562 of file base_realsense_node.cpp.

◆ getEnabledProfile()

bool BaseRealSenseNode::getEnabledProfile ( const stream_index_pair stream_index,
rs2::stream_profile profile 
)
private

Definition at line 2477 of file base_realsense_node.cpp.

◆ getImuInfo()

IMUInfo BaseRealSenseNode::getImuInfo ( const stream_index_pair stream_index)
private

Definition at line 2333 of file base_realsense_node.cpp.

◆ getNamespaceStr()

std::string BaseRealSenseNode::getNamespaceStr ( )
staticprivate

Definition at line 76 of file base_realsense_node.cpp.

◆ getParameters()

void BaseRealSenseNode::getParameters ( )
private

Definition at line 715 of file base_realsense_node.cpp.

◆ imu_callback()

void BaseRealSenseNode::imu_callback ( rs2::frame  frame)
private

Definition at line 1493 of file base_realsense_node.cpp.

◆ imu_callback_sync()

void BaseRealSenseNode::imu_callback_sync ( rs2::frame  frame,
imu_sync_method  sync_method = imu_sync_method::COPY 
)
private

Definition at line 1445 of file base_realsense_node.cpp.

◆ ImuMessage_AddDefaultValues()

void BaseRealSenseNode::ImuMessage_AddDefaultValues ( sensor_msgs::Imu imu_msg)
private

Definition at line 1432 of file base_realsense_node.cpp.

◆ monitor_update_functions()

void BaseRealSenseNode::monitor_update_functions ( )
private

Definition at line 684 of file base_realsense_node.cpp.

◆ multiple_message_callback()

void BaseRealSenseNode::multiple_message_callback ( rs2::frame  frame,
imu_sync_method  sync_method 
)
private

Definition at line 1784 of file base_realsense_node.cpp.

◆ pose_callback()

void BaseRealSenseNode::pose_callback ( rs2::frame  frame)
private

Definition at line 1538 of file base_realsense_node.cpp.

◆ publish_frequency_update()

void BaseRealSenseNode::publish_frequency_update ( )
private

Definition at line 2535 of file base_realsense_node.cpp.

◆ publish_static_tf()

void BaseRealSenseNode::publish_static_tf ( const ros::Time t,
const float3 trans,
const tf::Quaternion q,
const std::string from,
const std::string to 
)
protected

Definition at line 1981 of file base_realsense_node.cpp.

◆ publish_temperature()

void BaseRealSenseNode::publish_temperature ( )
private

Definition at line 2514 of file base_realsense_node.cpp.

◆ publishAlignedDepthToOthers()

void realsense2_camera::BaseRealSenseNode::publishAlignedDepthToOthers ( rs2::frameset  frames,
const ros::Time t 
)
private

◆ publishDynamicTransforms()

void BaseRealSenseNode::publishDynamicTransforms ( )
private

Definition at line 2122 of file base_realsense_node.cpp.

◆ publishFrame()

void BaseRealSenseNode::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 
)
private

Definition at line 2363 of file base_realsense_node.cpp.

◆ publishIntrinsics()

void BaseRealSenseNode::publishIntrinsics ( )
private

Definition at line 2141 of file base_realsense_node.cpp.

◆ publishMetadata()

void BaseRealSenseNode::publishMetadata ( rs2::frame  f,
const ros::Time header_time,
const std::string frame_id 
)
private

Definition at line 2437 of file base_realsense_node.cpp.

◆ publishPointCloud()

void BaseRealSenseNode::publishPointCloud ( rs2::points  f,
const ros::Time t,
const rs2::frameset frameset 
)
private

Definition at line 2167 of file base_realsense_node.cpp.

◆ publishServices()

void BaseRealSenseNode::publishServices ( )
private

Definition at line 2557 of file base_realsense_node.cpp.

◆ publishStaticTransforms()

void BaseRealSenseNode::publishStaticTransforms ( )
private

Definition at line 2062 of file base_realsense_node.cpp.

◆ publishTopics()

void BaseRealSenseNode::publishTopics ( )
overridevirtual

◆ readAndSetDynamicParam()

void BaseRealSenseNode::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 
)
private

Definition at line 401 of file base_realsense_node.cpp.

◆ registerAutoExposureROIOptions()

void BaseRealSenseNode::registerAutoExposureROIOptions ( ros::NodeHandle nh)
private

Definition at line 414 of file base_realsense_node.cpp.

◆ registerDynamicOption()

void BaseRealSenseNode::registerDynamicOption ( ros::NodeHandle nh,
rs2::options  sensor,
std::string module_name 
)
private

Definition at line 447 of file base_realsense_node.cpp.

◆ registerDynamicReconfigCb()

void BaseRealSenseNode::registerDynamicReconfigCb ( ros::NodeHandle nh)
overridevirtual

◆ registerHDRoptions()

void BaseRealSenseNode::registerHDRoptions ( )
private

Definition at line 620 of file base_realsense_node.cpp.

◆ rotationMatrixToQuaternion()

tf::Quaternion BaseRealSenseNode::rotationMatrixToQuaternion ( const float  rotation[9]) const
protected

Definition at line 1969 of file base_realsense_node.cpp.

◆ rs2_string_to_stream()

rs2_stream BaseRealSenseNode::rs2_string_to_stream ( std::string  str)
private

Definition at line 702 of file base_realsense_node.cpp.

◆ rsExtrinsicsToMsg()

Extrinsics BaseRealSenseNode::rsExtrinsicsToMsg ( const rs2_extrinsics extrinsics,
const std::string frame_id 
) const
private

Definition at line 2310 of file base_realsense_node.cpp.

◆ runFirstFrameInitialization()

void BaseRealSenseNode::runFirstFrameInitialization ( rs2_stream  stream_type)
private

Definition at line 260 of file base_realsense_node.cpp.

◆ set_auto_exposure_roi()

void BaseRealSenseNode::set_auto_exposure_roi ( const std::string  option_name,
rs2::sensor  sensor,
int  new_value 
)
private

Definition at line 369 of file base_realsense_node.cpp.

◆ set_sensor_auto_exposure_roi()

void BaseRealSenseNode::set_sensor_auto_exposure_roi ( rs2::sensor  sensor)
private

Definition at line 388 of file base_realsense_node.cpp.

◆ set_sensor_parameter_to_ros()

void BaseRealSenseNode::set_sensor_parameter_to_ros ( const std::string module_name,
rs2::options  sensor,
rs2_option  option 
)
private

Definition at line 663 of file base_realsense_node.cpp.

◆ SetBaseStream()

void BaseRealSenseNode::SetBaseStream ( )
private

Definition at line 2044 of file base_realsense_node.cpp.

◆ setBaseTime()

bool BaseRealSenseNode::setBaseTime ( double  frame_time,
rs2_timestamp_domain  time_domain 
)
private

Definition at line 1802 of file base_realsense_node.cpp.

◆ setupDevice()

void BaseRealSenseNode::setupDevice ( )
private

Definition at line 820 of file base_realsense_node.cpp.

◆ setupErrorCallback()

void BaseRealSenseNode::setupErrorCallback ( )
private

Definition at line 218 of file base_realsense_node.cpp.

◆ setupFilters()

void BaseRealSenseNode::setupFilters ( )
private

Definition at line 1185 of file base_realsense_node.cpp.

◆ setupPublishers()

void BaseRealSenseNode::setupPublishers ( )
private

Definition at line 962 of file base_realsense_node.cpp.

◆ setupStreams()

void BaseRealSenseNode::setupStreams ( )
private

Definition at line 1828 of file base_realsense_node.cpp.

◆ startMonitoring()

void BaseRealSenseNode::startMonitoring ( )
private

Definition at line 2491 of file base_realsense_node.cpp.

◆ toggleSensors()

void BaseRealSenseNode::toggleSensors ( bool  enabled)
overridevirtual

◆ updateStreamCalibData()

void BaseRealSenseNode::updateStreamCalibData ( const rs2::video_stream_profile video_profile)
private

Definition at line 1883 of file base_realsense_node.cpp.

Member Data Documentation

◆ _align_depth

bool realsense2_camera::BaseRealSenseNode::_align_depth
protected

Definition at line 166 of file base_realsense_node.h.

◆ _allow_no_texture_points

bool realsense2_camera::BaseRealSenseNode::_allow_no_texture_points
private

Definition at line 267 of file base_realsense_node.h.

◆ _angular_velocity_cov

double realsense2_camera::BaseRealSenseNode::_angular_velocity_cov
private

Definition at line 272 of file base_realsense_node.h.

◆ _auto_exposure_roi

std::map<std::string, rs2::region_of_interest> realsense2_camera::BaseRealSenseNode::_auto_exposure_roi
private

Definition at line 327 of file base_realsense_node.h.

◆ _base_frame_id

std::string realsense2_camera::BaseRealSenseNode::_base_frame_id
protected

Definition at line 160 of file base_realsense_node.h.

◆ _base_stream

stream_index_pair realsense2_camera::BaseRealSenseNode::_base_stream
private

Definition at line 337 of file base_realsense_node.h.

◆ _camera_info

std::map<stream_index_pair, sensor_msgs::CameraInfo> realsense2_camera::BaseRealSenseNode::_camera_info
private

Definition at line 300 of file base_realsense_node.h.

◆ _camera_time_base

double realsense2_camera::BaseRealSenseNode::_camera_time_base
private

Definition at line 302 of file base_realsense_node.h.

◆ _clipping_distance

float realsense2_camera::BaseRealSenseNode::_clipping_distance
private

Definition at line 266 of file base_realsense_node.h.

◆ _colorizer

std::shared_ptr<rs2::filter> realsense2_camera::BaseRealSenseNode::_colorizer
private

Definition at line 315 of file base_realsense_node.h.

◆ _cv_monitoring

std::condition_variable realsense2_camera::BaseRealSenseNode::_cv_monitoring
mutableprivate

Definition at line 335 of file base_realsense_node.h.

◆ _cv_tf

std::condition_variable realsense2_camera::BaseRealSenseNode::_cv_tf
mutableprivate

Definition at line 335 of file base_realsense_node.h.

◆ _ddynrec

std::vector<std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> > realsense2_camera::BaseRealSenseNode::_ddynrec
private

Definition at line 261 of file base_realsense_node.h.

◆ _depth_aligned_camera_info

std::map<stream_index_pair, sensor_msgs::CameraInfo> realsense2_camera::BaseRealSenseNode::_depth_aligned_camera_info
private

Definition at line 321 of file base_realsense_node.h.

◆ _depth_aligned_encoding

std::map<rs2_stream, std::string> realsense2_camera::BaseRealSenseNode::_depth_aligned_encoding
private

Definition at line 320 of file base_realsense_node.h.

◆ _depth_aligned_frame_id

std::map<stream_index_pair, std::string> realsense2_camera::BaseRealSenseNode::_depth_aligned_frame_id
protected

Definition at line 164 of file base_realsense_node.h.

◆ _depth_aligned_image

std::map<stream_index_pair, cv::Mat> realsense2_camera::BaseRealSenseNode::_depth_aligned_image
private

Definition at line 318 of file base_realsense_node.h.

◆ _depth_aligned_image_publishers

std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics> realsense2_camera::BaseRealSenseNode::_depth_aligned_image_publishers
private

Definition at line 324 of file base_realsense_node.h.

◆ _depth_aligned_info_publisher

std::map<stream_index_pair, ros::Publisher> realsense2_camera::BaseRealSenseNode::_depth_aligned_info_publisher
private

Definition at line 323 of file base_realsense_node.h.

◆ _depth_aligned_seq

std::map<stream_index_pair, int> realsense2_camera::BaseRealSenseNode::_depth_aligned_seq
private

Definition at line 322 of file base_realsense_node.h.

◆ _depth_scale_meters

float realsense2_camera::BaseRealSenseNode::_depth_scale_meters
private

Definition at line 265 of file base_realsense_node.h.

◆ _depth_scaled_image

std::map<stream_index_pair, cv::Mat> realsense2_camera::BaseRealSenseNode::_depth_scaled_image
private

Definition at line 319 of file base_realsense_node.h.

◆ _depth_to_other_extrinsics

std::map<stream_index_pair, rs2_extrinsics> realsense2_camera::BaseRealSenseNode::_depth_to_other_extrinsics
private

Definition at line 326 of file base_realsense_node.h.

◆ _depth_to_other_extrinsics_publishers

std::map<stream_index_pair, ros::Publisher> realsense2_camera::BaseRealSenseNode::_depth_to_other_extrinsics_publishers
private

Definition at line 325 of file base_realsense_node.h.

◆ _dev

rs2::device realsense2_camera::BaseRealSenseNode::_dev
private

Definition at line 258 of file base_realsense_node.h.

◆ _dev_sensors

std::vector<rs2::sensor> realsense2_camera::BaseRealSenseNode::_dev_sensors
private

Definition at line 316 of file base_realsense_node.h.

◆ _device_info_srv

std::shared_ptr<ros::ServiceServer> realsense2_camera::BaseRealSenseNode::_device_info_srv
protected

Definition at line 168 of file base_realsense_node.h.

◆ _dynamic_tf_broadcaster

tf2_ros::TransformBroadcaster realsense2_camera::BaseRealSenseNode::_dynamic_tf_broadcaster
private

Definition at line 285 of file base_realsense_node.h.

◆ _enable

std::map<stream_index_pair, bool> realsense2_camera::BaseRealSenseNode::_enable
private

Definition at line 280 of file base_realsense_node.h.

◆ _enabled_profiles

std::map<stream_index_pair, std::vector<rs2::stream_profile> > realsense2_camera::BaseRealSenseNode::_enabled_profiles
private

Definition at line 303 of file base_realsense_node.h.

◆ _encoding

std::map<rs2_stream, std::string> realsense2_camera::BaseRealSenseNode::_encoding
private

Definition at line 296 of file base_realsense_node.h.

◆ _filters

std::vector<NamedFilter> realsense2_camera::BaseRealSenseNode::_filters
private

Definition at line 314 of file base_realsense_node.h.

◆ _filters_str

std::string realsense2_camera::BaseRealSenseNode::_filters_str
private

Definition at line 311 of file base_realsense_node.h.

◆ _format

std::map<rs2_stream, int> realsense2_camera::BaseRealSenseNode::_format
private

Definition at line 279 of file base_realsense_node.h.

◆ _fps

std::map<stream_index_pair, int> realsense2_camera::BaseRealSenseNode::_fps
private

Definition at line 278 of file base_realsense_node.h.

◆ _frame_id

std::map<stream_index_pair, std::string> realsense2_camera::BaseRealSenseNode::_frame_id
protected

Definition at line 162 of file base_realsense_node.h.

◆ _height

std::map<stream_index_pair, int> realsense2_camera::BaseRealSenseNode::_height
private

Definition at line 277 of file base_realsense_node.h.

◆ _hold_back_imu_for_frames

bool realsense2_camera::BaseRealSenseNode::_hold_back_imu_for_frames
private

Definition at line 273 of file base_realsense_node.h.

◆ _image

std::map<stream_index_pair, cv::Mat> realsense2_camera::BaseRealSenseNode::_image
private

Definition at line 295 of file base_realsense_node.h.

◆ _image_format

std::map<rs2_stream, int> realsense2_camera::BaseRealSenseNode::_image_format
private

Definition at line 292 of file base_realsense_node.h.

◆ _image_publishers

std::map<stream_index_pair, ImagePublisherWithFrequencyDiagnostics> realsense2_camera::BaseRealSenseNode::_image_publishers
private

Definition at line 289 of file base_realsense_node.h.

◆ _imu_publishers

std::map<stream_index_pair, ros::Publisher> realsense2_camera::BaseRealSenseNode::_imu_publishers
private

Definition at line 290 of file base_realsense_node.h.

◆ _imu_sync_method

imu_sync_method realsense2_camera::BaseRealSenseNode::_imu_sync_method
private

Definition at line 310 of file base_realsense_node.h.

◆ _info_publisher

std::map<stream_index_pair, ros::Publisher> realsense2_camera::BaseRealSenseNode::_info_publisher
private

Definition at line 293 of file base_realsense_node.h.

◆ _is_first_frame

std::map<rs2_stream, bool> realsense2_camera::BaseRealSenseNode::_is_first_frame
private

Definition at line 328 of file base_realsense_node.h.

◆ _is_initialized_time_base

std::atomic_bool realsense2_camera::BaseRealSenseNode::_is_initialized_time_base
private

Definition at line 301 of file base_realsense_node.h.

◆ _is_running

bool realsense2_camera::BaseRealSenseNode::_is_running
protected

Definition at line 159 of file base_realsense_node.h.

◆ _json_file_path

std::string realsense2_camera::BaseRealSenseNode::_json_file_path
private

Definition at line 263 of file base_realsense_node.h.

◆ _linear_accel_cov

double realsense2_camera::BaseRealSenseNode::_linear_accel_cov
private

Definition at line 271 of file base_realsense_node.h.

◆ _metadata_publishers

std::map<stream_index_pair, std::shared_ptr<ros::Publisher> > realsense2_camera::BaseRealSenseNode::_metadata_publishers
private

Definition at line 294 of file base_realsense_node.h.

◆ _monitor_options

std::vector<rs2_option> realsense2_camera::BaseRealSenseNode::_monitor_options
protected

Definition at line 167 of file base_realsense_node.h.

◆ _monitoring_t

std::shared_ptr<std::thread> realsense2_camera::BaseRealSenseNode::_monitoring_t
private

Definition at line 333 of file base_realsense_node.h.

◆ _msg_pointcloud

sensor_msgs::PointCloud2 realsense2_camera::BaseRealSenseNode::_msg_pointcloud
private

Definition at line 340 of file base_realsense_node.h.

◆ _namespace

const std::string realsense2_camera::BaseRealSenseNode::_namespace
private

Definition at line 338 of file base_realsense_node.h.

◆ _node_handle

ros::NodeHandle& realsense2_camera::BaseRealSenseNode::_node_handle
protected

Definition at line 165 of file base_realsense_node.h.

◆ _odom_frame_id

std::string realsense2_camera::BaseRealSenseNode::_odom_frame_id
protected

Definition at line 161 of file base_realsense_node.h.

◆ _optical_frame_id

std::map<stream_index_pair, std::string> realsense2_camera::BaseRealSenseNode::_optical_frame_id
protected

Definition at line 163 of file base_realsense_node.h.

◆ _ordered_pc

bool realsense2_camera::BaseRealSenseNode::_ordered_pc
private

Definition at line 268 of file base_realsense_node.h.

◆ _pnh

ros::NodeHandle realsense2_camera::BaseRealSenseNode::_pnh
protected

Definition at line 165 of file base_realsense_node.h.

◆ _pointcloud

bool realsense2_camera::BaseRealSenseNode::_pointcloud
private

Definition at line 308 of file base_realsense_node.h.

◆ _pointcloud_filter

std::shared_ptr<rs2::filter> realsense2_camera::BaseRealSenseNode::_pointcloud_filter
private

Definition at line 315 of file base_realsense_node.h.

◆ _pointcloud_publisher

ros::Publisher realsense2_camera::BaseRealSenseNode::_pointcloud_publisher
private

Definition at line 305 of file base_realsense_node.h.

◆ _pointcloud_texture

stream_index_pair realsense2_camera::BaseRealSenseNode::_pointcloud_texture
private

Definition at line 312 of file base_realsense_node.h.

◆ _publish_odom_tf

bool realsense2_camera::BaseRealSenseNode::_publish_odom_tf
private

Definition at line 309 of file base_realsense_node.h.

◆ _publish_tf

bool realsense2_camera::BaseRealSenseNode::_publish_tf
private

Definition at line 282 of file base_realsense_node.h.

◆ _ros_time_base

ros::Time realsense2_camera::BaseRealSenseNode::_ros_time_base
private

Definition at line 306 of file base_realsense_node.h.

◆ _sensors

std::map<stream_index_pair, rs2::sensor> realsense2_camera::BaseRealSenseNode::_sensors
private

Definition at line 259 of file base_realsense_node.h.

◆ _sensors_callback

std::map<std::string, std::function<void(rs2::frame)> > realsense2_camera::BaseRealSenseNode::_sensors_callback
private

Definition at line 260 of file base_realsense_node.h.

◆ _seq

std::map<stream_index_pair, int> realsense2_camera::BaseRealSenseNode::_seq
private

Definition at line 298 of file base_realsense_node.h.

◆ _serial_no

std::string realsense2_camera::BaseRealSenseNode::_serial_no
private

Definition at line 264 of file base_realsense_node.h.

◆ _static_tf_broadcaster

tf2_ros::StaticTransformBroadcaster realsense2_camera::BaseRealSenseNode::_static_tf_broadcaster
private

Definition at line 284 of file base_realsense_node.h.

◆ _static_tf_msgs

std::vector<geometry_msgs::TransformStamped> realsense2_camera::BaseRealSenseNode::_static_tf_msgs
private

Definition at line 286 of file base_realsense_node.h.

◆ _stream_intrinsics

std::map<stream_index_pair, rs2_intrinsics> realsense2_camera::BaseRealSenseNode::_stream_intrinsics
private

Definition at line 275 of file base_realsense_node.h.

◆ _stream_name

std::map<rs2_stream, std::string> realsense2_camera::BaseRealSenseNode::_stream_name
private

Definition at line 281 of file base_realsense_node.h.

◆ _sync_frames

bool realsense2_camera::BaseRealSenseNode::_sync_frames
private

Definition at line 307 of file base_realsense_node.h.

◆ _synced_imu_publisher

std::shared_ptr<SyncedImuPublisher> realsense2_camera::BaseRealSenseNode::_synced_imu_publisher
private

Definition at line 291 of file base_realsense_node.h.

◆ _syncer

PipelineSyncer realsense2_camera::BaseRealSenseNode::_syncer
private

Definition at line 313 of file base_realsense_node.h.

◆ _temperature_nodes

std::vector< OptionTemperatureDiag > realsense2_camera::BaseRealSenseNode::_temperature_nodes
private

Definition at line 332 of file base_realsense_node.h.

◆ _tf_publish_rate

double realsense2_camera::BaseRealSenseNode::_tf_publish_rate
private

Definition at line 283 of file base_realsense_node.h.

◆ _tf_t

std::shared_ptr<std::thread> realsense2_camera::BaseRealSenseNode::_tf_t
private

Definition at line 287 of file base_realsense_node.h.

◆ _unit_step_size

std::map<rs2_stream, int> realsense2_camera::BaseRealSenseNode::_unit_step_size
private

Definition at line 299 of file base_realsense_node.h.

◆ _update_functions_cv

std::condition_variable realsense2_camera::BaseRealSenseNode::_update_functions_cv
mutableprivate

Definition at line 335 of file base_realsense_node.h.

◆ _update_functions_t

std::shared_ptr<std::thread> realsense2_camera::BaseRealSenseNode::_update_functions_t
private

Definition at line 287 of file base_realsense_node.h.

◆ _update_functions_v

std::vector<std::function<void()> > realsense2_camera::BaseRealSenseNode::_update_functions_v
private

Definition at line 334 of file base_realsense_node.h.

◆ _valid_pc_indices

std::vector< unsigned int > realsense2_camera::BaseRealSenseNode::_valid_pc_indices
private

Definition at line 341 of file base_realsense_node.h.

◆ _video_functions_stack

std::map<rs2_stream, std::vector<std::function<void()> > > realsense2_camera::BaseRealSenseNode::_video_functions_stack
private

Definition at line 329 of file base_realsense_node.h.

◆ _width

std::map<stream_index_pair, int> realsense2_camera::BaseRealSenseNode::_width
private

Definition at line 276 of file base_realsense_node.h.


The documentation for this class was generated from the following files:


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