ros2_control - humble
Loading...
Searching...
No Matches
simple_transmission.hpp
1// Copyright 2020 PAL Robotics S.L.
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 TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
16#define TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
17
18#include <algorithm>
19#include <cassert>
20#include <string>
21#include <vector>
22
23#include "hardware_interface/types/hardware_interface_type_values.hpp"
24#include "transmission_interface/exception.hpp"
25#include "transmission_interface/transmission.hpp"
26
28{
30
84{
85public:
91 explicit SimpleTransmission(
92 const double joint_to_actuator_reduction, const double joint_offset = 0.0);
93
95
101 void configure(
102 const std::vector<JointHandle> & joint_handles,
103 const std::vector<ActuatorHandle> & actuator_handles) override;
104
106
111 void actuator_to_joint() override;
112
114
119 void joint_to_actuator() override;
120
121 std::size_t num_actuators() const override { return 1; }
122 std::size_t num_joints() const override { return 1; }
123
124 double get_actuator_reduction() const { return reduction_; }
125 double get_joint_offset() const { return jnt_offset_; }
126
127protected:
128 double reduction_;
129 double jnt_offset_;
130
131 JointHandle joint_position_ = {"", "", nullptr};
132 JointHandle joint_velocity_ = {"", "", nullptr};
133 JointHandle joint_effort_ = {"", "", nullptr};
134
135 ActuatorHandle actuator_position_ = {"", "", nullptr};
136 ActuatorHandle actuator_velocity_ = {"", "", nullptr};
137 ActuatorHandle actuator_effort_ = {"", "", nullptr};
138};
139
141 const double joint_to_actuator_reduction, const double joint_offset)
142: reduction_(joint_to_actuator_reduction), jnt_offset_(joint_offset)
143{
144 if (reduction_ == 0.0)
145 {
146 throw Exception("Transmission reduction ratio cannot be zero.");
147 }
148}
149
150template <class HandleType>
151HandleType get_by_interface(
152 const std::vector<HandleType> & handles, const std::string & interface_name)
153{
154 const auto result = std::find_if(
155 handles.cbegin(), handles.cend(),
156 [&interface_name](const auto handle) { return handle.get_interface_name() == interface_name; });
157 if (result == handles.cend())
158 {
159 return HandleType(handles.cbegin()->get_prefix_name(), interface_name, nullptr);
160 }
161 return *result;
162}
163
164template <class T>
165bool are_names_identical(const std::vector<T> & handles)
166{
167 std::vector<std::string> names;
168 std::transform(
169 handles.cbegin(), handles.cend(), std::back_inserter(names),
170 [](const auto & handle) { return handle.get_prefix_name(); });
171 return std::equal(names.cbegin() + 1, names.cend(), names.cbegin());
172}
173
175 const std::vector<JointHandle> & joint_handles,
176 const std::vector<ActuatorHandle> & actuator_handles)
177{
178 if (joint_handles.empty())
179 {
180 throw Exception("No joint handles were passed in");
181 }
182
183 if (actuator_handles.empty())
184 {
185 throw Exception("No actuator handles were passed in");
186 }
187
188 if (!are_names_identical(joint_handles))
189 {
190 throw Exception("Joint names given to transmissions should be identical");
191 }
192
193 if (!are_names_identical(actuator_handles))
194 {
195 throw Exception("Actuator names given to transmissions should be identical");
196 }
197
198 joint_position_ = get_by_interface(joint_handles, hardware_interface::HW_IF_POSITION);
199 joint_velocity_ = get_by_interface(joint_handles, hardware_interface::HW_IF_VELOCITY);
200 joint_effort_ = get_by_interface(joint_handles, hardware_interface::HW_IF_EFFORT);
201
202 if (!joint_position_ && !joint_velocity_ && !joint_effort_)
203 {
204 throw Exception("None of the provided joint handles are valid or from the required interfaces");
205 }
206
207 actuator_position_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_POSITION);
208 actuator_velocity_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_VELOCITY);
209 actuator_effort_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_EFFORT);
210
211 if (!actuator_position_ && !actuator_velocity_ && !actuator_effort_)
212 {
213 throw Exception("None of the provided joint handles are valid or from the required interfaces");
214 }
215}
216
218{
219 if (joint_effort_ && actuator_effort_)
220 {
221 joint_effort_.set_value(actuator_effort_.get_value() * reduction_);
222 }
223
224 if (joint_velocity_ && actuator_velocity_)
225 {
226 joint_velocity_.set_value(actuator_velocity_.get_value() / reduction_);
227 }
228
229 if (joint_position_ && actuator_position_)
230 {
231 joint_position_.set_value(actuator_position_.get_value() / reduction_ + jnt_offset_);
232 }
233}
234
236{
237 if (joint_effort_ && actuator_effort_)
238 {
239 actuator_effort_.set_value(joint_effort_.get_value() / reduction_);
240 }
241
242 if (joint_velocity_ && actuator_velocity_)
243 {
244 actuator_velocity_.set_value(joint_velocity_.get_value() * reduction_);
245 }
246
247 if (joint_position_ && actuator_position_)
248 {
249 actuator_position_.set_value((joint_position_.get_value() - jnt_offset_) * reduction_);
250 }
251}
252
253} // namespace transmission_interface
254
255#endif // TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
Definition exception.hpp:23
Implementation of a simple reducer transmission.
Definition simple_transmission.hpp:84
SimpleTransmission(const double joint_to_actuator_reduction, const double joint_offset=0.0)
Definition simple_transmission.hpp:140
std::size_t num_actuators() const override
Definition simple_transmission.hpp:121
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition simple_transmission.hpp:217
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition simple_transmission.hpp:235
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Set up the data the transmission operates on.
Definition simple_transmission.hpp:174
std::size_t num_joints() const override
Definition simple_transmission.hpp:122
Abstract base class for representing mechanical transmissions.
Definition transmission.hpp:48
constexpr char HW_IF_EFFORT[]
Constant defining effort interface.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface.
Definition hardware_interface_type_values.hpp:21
Definition accessor.hpp:24