41 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
44 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
47 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
50 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC CallbackReturn on_init()
override;
52 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
53 CallbackReturn on_configure(
const rclcpp_lifecycle::State & previous_state)
override;
55 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
56 CallbackReturn on_activate(
const rclcpp_lifecycle::State & previous_state)
override;
58 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
59 CallbackReturn on_deactivate(
const rclcpp_lifecycle::State & previous_state)
override;
61 FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC
62 controller_interface::return_type update(
63 const rclcpp::Time & time,
const rclcpp::Duration & period)
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_;