15#ifndef SEMANTIC_COMPONENTS__FORCE_TORQUE_SENSOR_HPP_
16#define SEMANTIC_COMPONENTS__FORCE_TORQUE_SENSOR_HPP_
23#include "geometry_msgs/msg/wrench.hpp"
24#include "hardware_interface/loaned_state_interface.hpp"
25#include "semantic_components/semantic_component_interface.hpp"
27namespace semantic_components
37 {{name +
"/" +
"force.x"},
38 {name +
"/" +
"force.y"},
39 {name +
"/" +
"force.z"},
40 {name +
"/" +
"torque.x"},
41 {name +
"/" +
"torque.y"},
42 {name +
"/" +
"torque.z"}}),
45 data_.fill(std::numeric_limits<double>::quiet_NaN());
58 const std::string & interface_force_x,
const std::string & interface_force_y,
59 const std::string & interface_force_z,
const std::string & interface_torque_x,
60 const std::string & interface_torque_y,
const std::string & interface_torque_z)
63 data_.fill(std::numeric_limits<double>::quiet_NaN());
64 auto check_and_add_interface =
65 [
this](
const std::string & interface_name,
const std::size_t index)
67 if (!interface_name.empty())
69 interface_names_.emplace_back(interface_name);
78 check_and_add_interface(interface_force_x, 0);
79 check_and_add_interface(interface_force_y, 1);
80 check_and_add_interface(interface_force_z, 2);
81 check_and_add_interface(interface_torque_x, 3);
82 check_and_add_interface(interface_torque_y, 4);
83 check_and_add_interface(interface_torque_z, 5);
95 std::array<double, 3> forces;
96 std::copy(
data_.begin(),
data_.begin() + 3, forces.begin());
109 std::array<double, 3> torques;
110 std::copy(
data_.begin() + 3,
data_.end(), torques.begin());
125 message.force.x =
data_[0];
126 message.force.y =
data_[1];
127 message.force.z =
data_[2];
128 message.torque.x =
data_[3];
129 message.torque.y =
data_[4];
130 message.torque.z =
data_[5];
144 std::size_t interface_counter{0};
145 for (
auto i = 0u; i <
data_.size(); ++i)
149 const auto data = state_interfaces_[interface_counter].get().get_optional();
150 if (data.has_value())
152 data_[i] = data.value();
160 mutable std::array<double, 6>
data_;
Definition force_torque_sensor.hpp:30
std::array< bool, 6 > existing_axes_
Vector with existing axes for sensors with less then 6D axes.
Definition force_torque_sensor.hpp:162
bool get_values_as_message(geometry_msgs::msg::Wrench &message) const
Return Wrench message with forces and torques.
Definition force_torque_sensor.hpp:122
ForceTorqueSensor(const std::string &name)
Constructor for "standard" 6D FTS.
Definition force_torque_sensor.hpp:33
std::array< double, 3 > get_forces() const
Return forces.
Definition force_torque_sensor.hpp:92
std::array< double, 3 > get_torques() const
Return torque.
Definition force_torque_sensor.hpp:106
std::array< double, 6 > data_
Array to store the data of the FT sensors.
Definition force_torque_sensor.hpp:160
void update_data_from_interfaces() const
Update the data from the state interfaces.
Definition force_torque_sensor.hpp:142
ForceTorqueSensor(const std::string &interface_force_x, const std::string &interface_force_y, const std::string &interface_force_z, const std::string &interface_torque_x, const std::string &interface_torque_y, const std::string &interface_torque_z)
Constructor for 6D FTS with custom interface names.
Definition force_torque_sensor.hpp:57
Definition semantic_component_interface.hpp:28