Class ForceTorqueSensorBroadcaster

Inheritance Relationships

Base Type

  • public controller_interface::ControllerInterface

Class Documentation

class ForceTorqueSensorBroadcaster : public controller_interface::ControllerInterface

Public Functions

FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC ForceTorqueSensorBroadcaster()
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration command_interface_configuration () const override
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::InterfaceConfiguration state_interface_configuration () const override
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_init () override
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_configure (const rclcpp_lifecycle::State &previous_state) override
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_activate (const rclcpp_lifecycle::State &previous_state) override
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &previous_state) override
FORCE_TORQUE_SENSOR_BROADCASTER_PUBLIC controller_interface::return_type update (const rclcpp::Time &time, const rclcpp::Duration &period) override

Protected Types

using StatePublisher = realtime_tools::RealtimePublisher<geometry_msgs::msg::WrenchStamped>

Protected Attributes

std::shared_ptr<ParamListener> param_listener_
Params params_
std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_
rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr sensor_state_publisher_
std::unique_ptr<StatePublisher> realtime_publisher_