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_;
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:49