41 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
44 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
47 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
50 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn
on_init()
override;
52 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
53 controller_interface::CallbackReturn on_configure(
54 const rclcpp_lifecycle::State & previous_state)
override;
56 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
57 controller_interface::CallbackReturn on_activate(
58 const rclcpp_lifecycle::State & previous_state)
override;
60 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
61 controller_interface::CallbackReturn on_deactivate(
62 const rclcpp_lifecycle::State & previous_state)
override;
64 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
65 controller_interface::return_type
update(
66 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
69 std::shared_ptr<ParamListener> param_listener_;
72 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
75 rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr sensor_state_publisher_;
76 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