19#ifndef FORCE_TORQUE_SENSOR_BROADCASTER__FORCE_TORQUE_SENSOR_BROADCASTER_HPP_
20#define FORCE_TORQUE_SENSOR_BROADCASTER__FORCE_TORQUE_SENSOR_BROADCASTER_HPP_
26#include "controller_interface/chainable_controller_interface.hpp"
27#include "filters/filter_chain.hpp"
28#include "geometry_msgs/msg/wrench_stamped.hpp"
29#include "rclcpp_lifecycle/state.hpp"
30#include "realtime_tools/realtime_publisher.hpp"
31#include "semantic_components/force_torque_sensor.hpp"
34#include "force_torque_sensor_broadcaster/force_torque_sensor_broadcaster_parameters.hpp"
36namespace force_torque_sensor_broadcaster
38using WrenchMsgType = geometry_msgs::msg::WrenchStamped;
48 controller_interface::CallbackReturn
on_init()
override;
50 controller_interface::CallbackReturn on_configure(
51 const rclcpp_lifecycle::State & previous_state)
override;
53 controller_interface::CallbackReturn on_activate(
54 const rclcpp_lifecycle::State & previous_state)
override;
56 controller_interface::CallbackReturn on_deactivate(
57 const rclcpp_lifecycle::State & previous_state)
override;
60 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
63 const rclcpp::Time & time,
const rclcpp::Duration & period)
override;
68 void apply_sensor_offset(
const Params & params, geometry_msgs::msg::WrenchStamped & msg);
69 void apply_sensor_multiplier(
const Params & params, geometry_msgs::msg::WrenchStamped & msg);
71 std::shared_ptr<ParamListener> param_listener_;
74 std::unique_ptr<semantic_components::ForceTorqueSensor> force_torque_sensor_;
75 bool has_filter_chain_ =
false;
77 WrenchMsgType wrench_raw_;
78 WrenchMsgType wrench_filtered_;
79 std::unique_ptr<filters::FilterChain<WrenchMsgType>> filter_chain_;
81 using StatePublisher = rclcpp::Publisher<WrenchMsgType>::SharedPtr;
83 StatePublisher sensor_raw_state_publisher_;
84 StatePublisher sensor_filtered_state_publisher_;
85 std::unique_ptr<StateRTPublisher> realtime_raw_publisher_;
86 std::unique_ptr<StateRTPublisher> realtime_filtered_publisher_;
Definition chainable_controller_interface.hpp:37
Definition force_torque_sensor_broadcaster.hpp:41
controller_interface::InterfaceConfiguration command_interface_configuration() const override
Get configuration for controller's required command interfaces.
Definition force_torque_sensor_broadcaster.cpp:145
std::vector< hardware_interface::StateInterface > on_export_state_interfaces() override
Definition force_torque_sensor_broadcaster.cpp:214
controller_interface::return_type update_reference_from_subscribers(const rclcpp::Time &time, const rclcpp::Duration &period) override
Update reference from input topics when not in chained mode.
Definition force_torque_sensor_broadcaster.cpp:207
controller_interface::CallbackReturn on_init() override
Extending interface with initialization method which is individual for each controller.
Definition force_torque_sensor_broadcaster.cpp:34
controller_interface::return_type update_and_write_commands(const rclcpp::Time &time, const rclcpp::Duration &period) override
Execute calculations of the controller and update command interfaces.
Definition force_torque_sensor_broadcaster.cpp:175
controller_interface::InterfaceConfiguration state_interface_configuration() const override
Get configuration for controller's required state interfaces.
Definition force_torque_sensor_broadcaster.cpp:153
Configuring what command/state interfaces to claim.
Definition controller_interface_base.hpp:61