Classes | Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Private Attributes
realsense2_camera::BaseRealSenseNode Class Reference

#include <base_realsense_node.h>

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

List of all members.

Classes

class  CIMUHistory
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
void toggleSensors (bool enabled)
virtual ~BaseRealSenseNode ()

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)
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::map< stream_index_pair,
std::string > 
_frame_id
ros::NodeHandle_node_handle
std::string _odom_frame_id
std::map< stream_index_pair,
std::string > 
_optical_frame_id
ros::NodeHandle _pnh

Private Member Functions

void clip_depth (rs2::depth_frame depth_frame, float clipping_dist)
void enable_devices ()
double FillImuData_Copy (const stream_index_pair stream_index, const CIMUHistory::imuData imu_data, sensor_msgs::Imu &imu_msg)
double FillImuData_LinearInterpolation (const stream_index_pair stream_index, const CIMUHistory::imuData imu_data, sensor_msgs::Imu &imu_msg)
cv::Mat & fix_depth_scale (const cv::Mat &from_image, cv::Mat &to_image)
void frame_callback (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 multiple_message_callback (rs2::frame frame, imu_sync_method sync_method)
void pose_callback (rs2::frame frame)
void publishAlignedDepthToOthers (rs2::frameset frames, const ros::Time &t)
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, std::map< stream_index_pair, int > &seq, std::map< stream_index_pair, sensor_msgs::CameraInfo > &camera_info, const std::map< stream_index_pair, std::string > &optical_frame_id, const std::map< rs2_stream, std::string > &encoding, bool copy_data_from_frame=true)
void publishIntrinsics ()
void publishPointCloud (rs2::points f, const ros::Time &t, const rs2::frameset &frameset)
void publishStaticTransforms ()
void registerDynamicOption (ros::NodeHandle &nh, rs2::options sensor, std::string &module_name)
rs2_stream rs2_string_to_stream (std::string str)
Extrinsics rsExtrinsicsToMsg (const rs2_extrinsics &extrinsics, const std::string &frame_id) const
void setBaseTime (double frame_time, bool warn_no_metadata)
void setupDevice ()
void setupErrorCallback ()
void setupFilters ()
void setupPublishers ()
void setupStreams ()
void updateStreamCalibData (const rs2::video_stream_profile &video_profile)

Static Private Member Functions

static std::string getNamespaceStr ()

Private Attributes

std::map< rs2_stream,
std::shared_ptr< rs2::align > > 
_align
bool _allow_no_texture_points
double _angular_velocity_cov
std::map< stream_index_pair,
sensor_msgs::CameraInfo > 
_camera_info
double _camera_time_base
float _clipping_distance
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
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< 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::atomic_bool _is_initialized_time_base
std::string _json_file_path
double _linear_accel_cov
const std::string _namespace
bool _pointcloud
ros::Publisher _pointcloud_publisher
stream_index_pair _pointcloud_texture
bool _publish_odom_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::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::map< rs2_stream, int > _unit_step_size
std::map< stream_index_pair, int > _width

Detailed Description

Definition at line 94 of file base_realsense_node.h.


Member Enumeration Documentation

Enumerator:
NONE 
COPY 
LINEAR_INTERPOLATION 

Definition at line 108 of file base_realsense_node.h.


Constructor & Destructor Documentation

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

Definition at line 80 of file base_realsense_node.cpp.

Definition at line 105 of file base_realsense_node.h.


Member Function Documentation

void BaseRealSenseNode::calcAndPublishStaticTransform ( const stream_index_pair &  stream,
const rs2::stream_profile &  base_profile 
) [protected, virtual]

Reimplemented in realsense2_camera::T265RealsenseNode.

Definition at line 1707 of file base_realsense_node.cpp.

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

Definition at line 995 of file base_realsense_node.cpp.

Definition at line 777 of file base_realsense_node.cpp.

double BaseRealSenseNode::FillImuData_Copy ( const stream_index_pair  stream_index,
const CIMUHistory::imuData  imu_data,
sensor_msgs::Imu &  imu_msg 
) [private]

Definition at line 1099 of file base_realsense_node.cpp.

double BaseRealSenseNode::FillImuData_LinearInterpolation ( const stream_index_pair  stream_index,
const CIMUHistory::imuData  imu_data,
sensor_msgs::Imu &  imu_msg 
) [private]

Definition at line 1062 of file base_realsense_node.cpp.

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

Definition at line 955 of file base_realsense_node.cpp.

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

Definition at line 1348 of file base_realsense_node.cpp.

rs2::stream_profile BaseRealSenseNode::getAProfile ( const stream_index_pair &  stream) [protected]

Definition at line 1991 of file base_realsense_node.cpp.

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

Definition at line 2099 of file base_realsense_node.cpp.

IMUInfo BaseRealSenseNode::getImuInfo ( const stream_index_pair &  stream_index) [private]

Definition at line 2000 of file base_realsense_node.cpp.

std::string BaseRealSenseNode::getNamespaceStr ( ) [static, private]

Definition at line 73 of file base_realsense_node.cpp.

Definition at line 403 of file base_realsense_node.cpp.

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

Definition at line 1203 of file base_realsense_node.cpp.

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

Definition at line 1116 of file base_realsense_node.cpp.

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

Definition at line 1522 of file base_realsense_node.cpp.

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

Definition at line 1255 of file base_realsense_node.cpp.

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 1687 of file base_realsense_node.cpp.

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

Definition at line 733 of file base_realsense_node.cpp.

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,
std::map< stream_index_pair, int > &  seq,
std::map< stream_index_pair, sensor_msgs::CameraInfo > &  camera_info,
const std::map< stream_index_pair, std::string > &  optical_frame_id,
const std::map< rs2_stream, std::string > &  encoding,
bool  copy_data_from_frame = true 
) [private]

Definition at line 2030 of file base_realsense_node.cpp.

Definition at line 1815 of file base_realsense_node.cpp.

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

Definition at line 1841 of file base_realsense_node.cpp.

Definition at line 1750 of file base_realsense_node.cpp.

void BaseRealSenseNode::publishTopics ( ) [override, virtual]
void BaseRealSenseNode::registerDynamicOption ( ros::NodeHandle nh,
rs2::options  sensor,
std::string &  module_name 
) [private]

Definition at line 264 of file base_realsense_node.cpp.

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

Definition at line 1675 of file base_realsense_node.cpp.

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

Definition at line 390 of file base_realsense_node.cpp.

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

Definition at line 1977 of file base_realsense_node.cpp.

void BaseRealSenseNode::setBaseTime ( double  frame_time,
bool  warn_no_metadata 
) [private]

Definition at line 1540 of file base_realsense_node.cpp.

void BaseRealSenseNode::setupDevice ( ) [private]

Definition at line 494 of file base_realsense_node.cpp.

Definition at line 145 of file base_realsense_node.cpp.

void BaseRealSenseNode::setupFilters ( ) [private]

Definition at line 873 of file base_realsense_node.cpp.

Definition at line 642 of file base_realsense_node.cpp.

void BaseRealSenseNode::setupStreams ( ) [private]

Definition at line 1548 of file base_realsense_node.cpp.

void BaseRealSenseNode::toggleSensors ( bool  enabled)

Definition at line 126 of file base_realsense_node.cpp.

void BaseRealSenseNode::updateStreamCalibData ( const rs2::video_stream_profile &  video_profile) [private]

Definition at line 1608 of file base_realsense_node.cpp.


Member Data Documentation

std::map<rs2_stream, std::shared_ptr<rs2::align> > realsense2_camera::BaseRealSenseNode::_align [private]

Definition at line 276 of file base_realsense_node.h.

Definition at line 139 of file base_realsense_node.h.

Definition at line 236 of file base_realsense_node.h.

Definition at line 239 of file base_realsense_node.h.

Definition at line 133 of file base_realsense_node.h.

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

Definition at line 260 of file base_realsense_node.h.

Definition at line 262 of file base_realsense_node.h.

Definition at line 235 of file base_realsense_node.h.

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

Definition at line 230 of file base_realsense_node.h.

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

Definition at line 281 of file base_realsense_node.h.

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

Definition at line 280 of file base_realsense_node.h.

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

Definition at line 137 of file base_realsense_node.h.

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

Definition at line 278 of file base_realsense_node.h.

Definition at line 284 of file base_realsense_node.h.

Definition at line 283 of file base_realsense_node.h.

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

Definition at line 282 of file base_realsense_node.h.

Definition at line 234 of file base_realsense_node.h.

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

Definition at line 279 of file base_realsense_node.h.

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

Definition at line 286 of file base_realsense_node.h.

Definition at line 285 of file base_realsense_node.h.

Definition at line 227 of file base_realsense_node.h.

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

Definition at line 275 of file base_realsense_node.h.

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

Definition at line 246 of file base_realsense_node.h.

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

Definition at line 263 of file base_realsense_node.h.

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

Definition at line 256 of file base_realsense_node.h.

Definition at line 274 of file base_realsense_node.h.

Definition at line 271 of file base_realsense_node.h.

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

Definition at line 245 of file base_realsense_node.h.

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

Definition at line 135 of file base_realsense_node.h.

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

Definition at line 244 of file base_realsense_node.h.

Definition at line 240 of file base_realsense_node.h.

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

Definition at line 255 of file base_realsense_node.h.

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

Definition at line 253 of file base_realsense_node.h.

Definition at line 250 of file base_realsense_node.h.

Definition at line 251 of file base_realsense_node.h.

Definition at line 270 of file base_realsense_node.h.

Definition at line 254 of file base_realsense_node.h.

Definition at line 261 of file base_realsense_node.h.

Definition at line 232 of file base_realsense_node.h.

Definition at line 238 of file base_realsense_node.h.

Definition at line 288 of file base_realsense_node.h.

Definition at line 138 of file base_realsense_node.h.

Definition at line 134 of file base_realsense_node.h.

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

Definition at line 136 of file base_realsense_node.h.

Definition at line 138 of file base_realsense_node.h.

Definition at line 268 of file base_realsense_node.h.

Definition at line 265 of file base_realsense_node.h.

Definition at line 272 of file base_realsense_node.h.

Definition at line 269 of file base_realsense_node.h.

Definition at line 266 of file base_realsense_node.h.

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

Definition at line 228 of file base_realsense_node.h.

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

Definition at line 229 of file base_realsense_node.h.

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

Definition at line 258 of file base_realsense_node.h.

Definition at line 233 of file base_realsense_node.h.

Definition at line 248 of file base_realsense_node.h.

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

Definition at line 242 of file base_realsense_node.h.

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

Definition at line 247 of file base_realsense_node.h.

Definition at line 267 of file base_realsense_node.h.

Definition at line 252 of file base_realsense_node.h.

Definition at line 273 of file base_realsense_node.h.

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

Definition at line 259 of file base_realsense_node.h.

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

Definition at line 243 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 Sat Jul 6 2019 03:30:09