Class BaseRealSenseNode
Defined in File base_realsense_node.h
Nested Relationships
Nested Types
Class Documentation
-
class BaseRealSenseNode
Public Types
-
enum class imu_sync_method
Values:
-
enumerator NONE
-
enumerator COPY
-
enumerator LINEAR_INTERPOLATION
-
enumerator NONE
-
using TriggeredCalibration = realsense2_camera_msgs::action::TriggeredCalibration
-
using GoalHandleTriggeredCalibration = rclcpp_action::ServerGoalHandle<TriggeredCalibration>
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)
-
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
-
RosNodeBase &_node
-
std::string _camera_name
-
std::vector<rs2_option> _monitor_options
-
rclcpp::Logger _logger
-
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr _reset_srv
-
rclcpp::Service<realsense2_camera_msgs::srv::DeviceInfo>::SharedPtr _device_info_srv
-
rclcpp::Service<realsense2_camera_msgs::srv::CalibConfigRead>::SharedPtr _calib_config_read_srv
-
rclcpp::Service<realsense2_camera_msgs::srv::CalibConfigWrite>::SharedPtr _calib_config_write_srv
-
rclcpp_action::Server<TriggeredCalibration>::SharedPtr _triggered_calibration_action_server
-
std::shared_ptr<Parameters> _parameters
-
std::list<std::string> _parameters_names
-
enum class imu_sync_method