ros2_control - humble
Loading...
Searching...
No Matches
force_torque_sensor.hpp
1// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef SEMANTIC_COMPONENTS__FORCE_TORQUE_SENSOR_HPP_
16#define SEMANTIC_COMPONENTS__FORCE_TORQUE_SENSOR_HPP_
17
18#include <limits>
19#include <string>
20#include <vector>
21
22#include "geometry_msgs/msg/wrench.hpp"
23#include "hardware_interface/loaned_state_interface.hpp"
24#include "semantic_components/semantic_component_interface.hpp"
25
26namespace semantic_components
27{
28class ForceTorqueSensor : public SemanticComponentInterface<geometry_msgs::msg::Wrench>
29{
30public:
32 explicit ForceTorqueSensor(const std::string & name) : SemanticComponentInterface(name, 6)
33 {
34 // If 6D FTS use standard names
35 interface_names_.emplace_back(name_ + "/" + "force.x");
36 interface_names_.emplace_back(name_ + "/" + "force.y");
37 interface_names_.emplace_back(name_ + "/" + "force.z");
38 interface_names_.emplace_back(name_ + "/" + "torque.x");
39 interface_names_.emplace_back(name_ + "/" + "torque.y");
40 interface_names_.emplace_back(name_ + "/" + "torque.z");
41
42 // Set all interfaces existing
43 std::fill(existing_axes_.begin(), existing_axes_.end(), true);
44
45 // Set default force and torque values to NaN
46 std::fill(forces_.begin(), forces_.end(), std::numeric_limits<double>::quiet_NaN());
47 std::fill(torques_.begin(), torques_.end(), std::numeric_limits<double>::quiet_NaN());
48 }
49
51
60 const std::string & interface_force_x, const std::string & interface_force_y,
61 const std::string & interface_force_z, const std::string & interface_torque_x,
62 const std::string & interface_torque_y, const std::string & interface_torque_z)
64 {
65 auto check_and_add_interface = [this](const std::string & interface_name, const size_t index)
66 {
67 if (!interface_name.empty())
68 {
69 interface_names_.emplace_back(interface_name);
70 existing_axes_[index] = true;
71 }
72 else
73 {
74 existing_axes_[index] = false;
75 }
76 };
77
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);
84
85 // Set default force and torque values to NaN
86 std::fill(forces_.begin(), forces_.end(), std::numeric_limits<double>::quiet_NaN());
87 std::fill(torques_.begin(), torques_.end(), std::numeric_limits<double>::quiet_NaN());
88 }
89
90 virtual ~ForceTorqueSensor() = default;
91
93
98 std::array<double, 3> get_forces()
99 {
100 size_t interface_counter = 0;
101 for (size_t i = 0; i < 3; ++i)
102 {
103 if (existing_axes_[i])
104 {
105 forces_[i] = state_interfaces_[interface_counter].get().get_value();
106 ++interface_counter;
107 }
108 }
109 return forces_;
110 }
111
113
118 std::array<double, 3> get_torques()
119 {
120 // find out how many force interfaces are being used
121 // torque interfaces will be found from the next index onward
122 auto torque_interface_counter =
123 static_cast<size_t>(std::count(existing_axes_.begin(), existing_axes_.begin() + 3, true));
124
125 for (size_t i = 3; i < 6; ++i)
126 {
127 if (existing_axes_[i])
128 {
129 torques_[i - 3] = state_interfaces_[torque_interface_counter].get().get_value();
130 ++torque_interface_counter;
131 }
132 }
133 return torques_;
134 }
135
137
144 bool get_values_as_message(geometry_msgs::msg::Wrench & message)
145 {
146 // call get_forces() and get_troque() to update with the latest values
147 get_forces();
148 get_torques();
149
150 // update the message values
151 message.force.x = forces_[0];
152 message.force.y = forces_[1];
153 message.force.z = forces_[2];
154 message.torque.x = torques_[0];
155 message.torque.y = torques_[1];
156 message.torque.z = torques_[2];
157
158 return true;
159 }
160
161protected:
163 // Order is: force X, force Y, force Z, torque X, torque Y, torque Z.
164 std::array<bool, 6> existing_axes_;
165 std::array<double, 3> forces_;
166 std::array<double, 3> torques_;
167};
168
169} // namespace semantic_components
170
171#endif // SEMANTIC_COMPONENTS__FORCE_TORQUE_SENSOR_HPP_
Definition force_torque_sensor.hpp:29
std::array< bool, 6 > existing_axes_
Vector with existing axes for sensors with less then 6D axes.
Definition force_torque_sensor.hpp:164
ForceTorqueSensor(const std::string &name)
Constructor for "standard" 6D FTS.
Definition force_torque_sensor.hpp:32
std::array< double, 3 > get_forces()
Return forces.
Definition force_torque_sensor.hpp:98
std::array< double, 3 > get_torques()
Return torque.
Definition force_torque_sensor.hpp:118
bool get_values_as_message(geometry_msgs::msg::Wrench &message)
Return Wrench message with forces and torques.
Definition force_torque_sensor.hpp:144
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:59
Definition semantic_component_interface.hpp:28