15 #ifndef JOINT_STATE_BROADCASTER__JOINT_STATE_BROADCASTER_HPP_
16 #define JOINT_STATE_BROADCASTER__JOINT_STATE_BROADCASTER_HPP_
20 #include <unordered_map>
23 #include "control_msgs/msg/dynamic_joint_state.hpp"
24 #include "controller_interface/controller_interface.hpp"
25 #include "joint_state_broadcaster/visibility_control.h"
27 #include "joint_state_broadcaster_parameters.hpp"
28 #include "realtime_tools/realtime_publisher.hpp"
29 #include "sensor_msgs/msg/joint_state.hpp"
30 #include "urdf/model.h"
32 namespace joint_state_broadcaster
61 JOINT_STATE_BROADCASTER_PUBLIC
64 JOINT_STATE_BROADCASTER_PUBLIC
67 JOINT_STATE_BROADCASTER_PUBLIC
70 JOINT_STATE_BROADCASTER_PUBLIC
71 controller_interface::return_type
update(
72 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
74 JOINT_STATE_BROADCASTER_PUBLIC
75 controller_interface::CallbackReturn
on_init()
override;
77 JOINT_STATE_BROADCASTER_PUBLIC
78 controller_interface::CallbackReturn on_configure(
79 const rclcpp_lifecycle::State & previous_state)
override;
81 JOINT_STATE_BROADCASTER_PUBLIC
82 controller_interface::CallbackReturn on_activate(
83 const rclcpp_lifecycle::State & previous_state)
override;
85 JOINT_STATE_BROADCASTER_PUBLIC
86 controller_interface::CallbackReturn on_deactivate(
87 const rclcpp_lifecycle::State & previous_state)
override;
90 bool init_joint_data();
92 void init_dynamic_joint_state_msg();
93 bool use_all_available_interfaces()
const;
97 std::shared_ptr<ParamListener> param_listener_;
99 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
103 std::vector<std::string> joint_names_;
104 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
105 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
106 realtime_joint_state_publisher_;
110 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
111 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
112 dynamic_joint_state_publisher_;
113 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
114 realtime_dynamic_joint_state_publisher_;
117 bool is_model_loaded_ =
false;
Definition: controller_interface.hpp:28
Joint State Broadcaster for all or some state in a ros2_control system.
Definition: joint_state_broadcaster.hpp:59
JOINT_STATE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition: joint_state_broadcaster.cpp:67
JOINT_STATE_BROADCASTER_PUBLIC controller_interface::return_type update(const rclcpp::Time &time, const rclcpp::Duration &period) override
Definition: joint_state_broadcaster.cpp:351
JOINT_STATE_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition: joint_state_broadcaster.cpp:44
JOINT_STATE_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition: joint_state_broadcaster.cpp:61
void init_joint_state_msg()
Definition: joint_state_broadcaster.cpp:295
Configuring what command/state interfaces to claim.
Definition: controller_interface_base.hpp:58