41 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
44 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
45 controller_interface::return_type init(
const std::string & controller_name)
override;
47 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
50 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
53 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
54 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
56 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
57 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
59 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
60 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
62 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
63 controller_interface::return_type update()
override;
66 std::string sensor_name_;
67 std::array<std::string, 6> interface_names_;
68 std::string frame_id_;
70 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
73 rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr sensor_state_publisher_;
74 std::unique_ptr<StatePublisher> realtime_publisher_;