Class BaseRealSenseNode

Nested Relationships

Nested Types

Class Documentation

class BaseRealSenseNode

Public Types

enum class imu_sync_method

Values:

enumerator NONE
enumerator COPY
enumerator LINEAR_INTERPOLATION

Public Functions

BaseRealSenseNode(rclcpp::Node &node, rs2::device dev, std::shared_ptr<Parameters> parameters, bool use_intra_process = false)
~BaseRealSenseNode()
void publishTopics()

Protected Functions

void restartStaticTransformBroadcaster()
void publishExtrinsicsTopic(const stream_index_pair &sip, const rs2_extrinsics &ex)
void calcAndAppendTransformMsgs(const rs2::stream_profile &profile, const rs2::stream_profile &base_profile)
void getDeviceInfo(const realsense2_camera_msgs::srv::DeviceInfo::Request::SharedPtr req, realsense2_camera_msgs::srv::DeviceInfo::Response::SharedPtr res)
tf2::Quaternion rotationMatrixToQuaternion(const float rotation[9]) const
void append_static_tf_msg(const rclcpp::Time &t, const float3 &trans, const tf2::Quaternion &q, const std::string &from, const std::string &to)
void erase_static_tf_msg(const std::string &frame_id, const std::string &child_frame_id)
void eraseTransformMsgs(const stream_index_pair &sip, const rs2::stream_profile &profile)
void setup()

Protected Attributes

std::string _base_frame_id
bool _is_running
rclcpp::Node &_node
std::string _camera_name
std::vector<rs2_option> _monitor_options
rclcpp::Logger _logger
rclcpp::Service<realsense2_camera_msgs::srv::DeviceInfo>::SharedPtr _device_info_srv
std::shared_ptr<Parameters> _parameters
std::list<std::string> _parameters_names
class float3

Public Functions

inline float3 &operator*=(const float &factor)
inline float3 &operator+=(const float3 &other)

Public Members

float x
float y
float z