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 controller_interface::CallbackReturn
on_init()
override;
78 JOINT_STATE_BROADCASTER_PUBLIC
79 controller_interface::CallbackReturn on_configure(
80 const rclcpp_lifecycle::State & previous_state)
override;
82 JOINT_STATE_BROADCASTER_PUBLIC
83 controller_interface::CallbackReturn on_activate(
84 const rclcpp_lifecycle::State & previous_state)
override;
86 JOINT_STATE_BROADCASTER_PUBLIC
87 controller_interface::CallbackReturn on_deactivate(
88 const rclcpp_lifecycle::State & previous_state)
override;
91 bool init_joint_data();
93 void init_dynamic_joint_state_msg();
94 bool use_all_available_interfaces()
const;
98 std::shared_ptr<ParamListener> param_listener_;
100 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
104 std::vector<std::string> joint_names_;
105 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
106 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
107 realtime_joint_state_publisher_;
111 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
112 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
113 dynamic_joint_state_publisher_;
114 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
115 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