63 JOINT_STATE_BROADCASTER_PUBLIC
66 JOINT_STATE_BROADCASTER_PUBLIC
69 JOINT_STATE_BROADCASTER_PUBLIC
72 JOINT_STATE_BROADCASTER_PUBLIC
73 controller_interface::return_type
update(
74 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
76 JOINT_STATE_BROADCASTER_PUBLIC
77 controller_interface::CallbackReturn
on_init()
override;
79 JOINT_STATE_BROADCASTER_PUBLIC
80 controller_interface::CallbackReturn on_configure(
81 const rclcpp_lifecycle::State & previous_state)
override;
83 JOINT_STATE_BROADCASTER_PUBLIC
84 controller_interface::CallbackReturn on_activate(
85 const rclcpp_lifecycle::State & previous_state)
override;
87 JOINT_STATE_BROADCASTER_PUBLIC
88 controller_interface::CallbackReturn on_deactivate(
89 const rclcpp_lifecycle::State & previous_state)
override;
92 bool init_joint_data();
94 void init_dynamic_joint_state_msg();
95 bool use_all_available_interfaces()
const;
99 std::shared_ptr<ParamListener> param_listener_;
101 std::unordered_map<std::string, std::string> map_interface_to_joint_state_;
105 std::vector<std::string> joint_names_;
106 std::shared_ptr<rclcpp::Publisher<sensor_msgs::msg::JointState>> joint_state_publisher_;
107 std::shared_ptr<realtime_tools::RealtimePublisher<sensor_msgs::msg::JointState>>
108 realtime_joint_state_publisher_;
112 std::unordered_map<std::string, std::unordered_map<std::string, double>> name_if_value_mapping_;
113 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::DynamicJointState>>
114 dynamic_joint_state_publisher_;
115 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::DynamicJointState>>
116 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