40 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
43 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
46 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
49 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn
on_init()
override;
51 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
52 controller_interface::CallbackReturn on_configure(
53 const rclcpp_lifecycle::State & previous_state)
override;
55 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
56 controller_interface::CallbackReturn on_activate(
57 const rclcpp_lifecycle::State & previous_state)
override;
59 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
60 controller_interface::CallbackReturn on_deactivate(
61 const rclcpp_lifecycle::State & previous_state)
override;
63 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
64 controller_interface::return_type
update(
65 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
68 std::shared_ptr<ParamListener> param_listener_;
71 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
74 rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr sensor_state_publisher_;
75 std::unique_ptr<StatePublisher> realtime_publisher_;
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition force_torque_sensor_broadcaster.cpp:31