Class JointStateBroadcaster
Defined in File joint_state_broadcaster.hpp
Inheritance Relationships
Base Type
public controller_interface::ControllerInterface
Class Documentation
-
class JointStateBroadcaster : public controller_interface::ControllerInterface
Joint State Broadcaster for all or some state in a ros2_control system.
JointStateBroadcaster publishes state interfaces from ros2_control as ROS messages. There is a possibility to publish all available states (typical use), or only specific ones. The latter is, for example, used when hardware provides multiple measurement sources for some of its states, e.g., position. It is possible to define a mapping of measurements from different sources stored in custom interfaces to standard dynamic names in JointState message. If “joints” or “interfaces” parameter is empty, all available states are published.
Publishes to:
joint_states (sensor_msgs::msg::JointState): Joint states related to movement (position, velocity, effort).
dynamic_joint_states (control_msgs::msg::DynamicJointState): Joint states regardless of its interface type.
- Param use_local_topics:
Flag to publish topics in local namespace.
- Param joints:
Names of the joints to publish.
- Param interfaces:
Names of interfaces to publish.
- Param map_interface_to_joint_state.{HW_IF_POSITION|HW_IF_VELOCITY|HW_IF_EFFORT}:
mapping between custom interface names and standard names in sensor_msgs::msg::JointState message.
Public Functions
-
JOINT_STATE_BROADCASTER_PUBLIC JointStateBroadcaster()
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_init () override
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
- JOINT_STATE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
Protected Functions
-
bool init_joint_data()
-
void init_joint_state_msg()
-
void init_dynamic_joint_state_msg()
-
bool use_all_available_interfaces() const
Protected Attributes
-
std::shared_ptr<ParamListener> param_listener_
-
Params params_
-
std::unordered_map<std::string, std::string> map_interface_to_joint_state_
-
std::vector<std::string> joint_names_
-
std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_
-
std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>> realtime_joint_state_publisher_
-
std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_
-
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>> dynamic_joint_state_publisher_
-
std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>> realtime_dynamic_joint_state_publisher_
-
urdf::Model model_
-
bool is_model_loaded_ = false