36 JOINT_STATE_BROADCASTER_PUBLIC
39 JOINT_STATE_BROADCASTER_PUBLIC
40 controller_interface::return_type init(
const std::string & controller_name)
override;
42 JOINT_STATE_BROADCASTER_PUBLIC
45 JOINT_STATE_BROADCASTER_PUBLIC
48 JOINT_STATE_BROADCASTER_PUBLIC
49 controller_interface::return_type update()
override;
51 JOINT_STATE_BROADCASTER_PUBLIC
52 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure(
53 const rclcpp_lifecycle::State & previous_state)
override;
55 JOINT_STATE_BROADCASTER_PUBLIC
56 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate(
57 const rclcpp_lifecycle::State & previous_state)
override;
59 JOINT_STATE_BROADCASTER_PUBLIC
60 rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate(
61 const rclcpp_lifecycle::State & previous_state)
override;
64 bool init_joint_data();
66 void init_dynamic_joint_state_msg();
69 bool use_local_topics_;
73 std::vector<std::string> joint_names_;
74 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
75 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
76 realtime_joint_state_publisher_;
80 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
81 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
82 dynamic_joint_state_publisher_;
83 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
84 realtime_dynamic_joint_state_publisher_;