62 JOINT_STATE_BROADCASTER_PUBLIC
65 JOINT_STATE_BROADCASTER_PUBLIC
68 JOINT_STATE_BROADCASTER_PUBLIC
71 JOINT_STATE_BROADCASTER_PUBLIC
72 controller_interface::return_type update(
73 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
75 JOINT_STATE_BROADCASTER_PUBLIC
76 CallbackReturn on_init()
override;
78 JOINT_STATE_BROADCASTER_PUBLIC
79 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
81 JOINT_STATE_BROADCASTER_PUBLIC
82 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
84 JOINT_STATE_BROADCASTER_PUBLIC
85 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
88 bool init_joint_data();
90 void init_dynamic_joint_state_msg();
91 bool use_all_available_interfaces()
const;
95 bool use_local_topics_;
96 std::vector<std::string> joints_;
97 std::vector<std::string> interfaces_;
98 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
102 std::vector<std::string> joint_names_;
103 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
104 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
105 realtime_joint_state_publisher_;
109 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
110 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
111 dynamic_joint_state_publisher_;
112 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
113 realtime_dynamic_joint_state_publisher_;