ros2_control - galactic
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
81{
82public:
88 explicit SimpleTransmission(
89 const double joint_to_actuator_reduction, const double joint_offset = 0.0);
90
92
98 void configure(
99 const std::vector<JointHandle> & joint_handles,
100 const std::vector<ActuatorHandle> & actuator_handles) override;
101
103
107 void actuator_to_joint() override;
108
110
114 void joint_to_actuator() override;
115
116 std::size_t num_actuators() const override { return 1; }
117 std::size_t num_joints() const override { return 1; }
118
119 double get_actuator_reduction() const { return reduction_; }
120 double get_joint_offset() const { return jnt_offset_; }
121
122protected:
123 double reduction_;
124 double jnt_offset_;
125
126 JointHandle joint_position_ = {"", "", nullptr};
127 JointHandle joint_velocity_ = {"", "", nullptr};
128 JointHandle joint_effort_ = {"", "", nullptr};
129
130 ActuatorHandle actuator_position_ = {"", "", nullptr};
131 ActuatorHandle actuator_velocity_ = {"", "", nullptr};
132 ActuatorHandle actuator_effort_ = {"", "", nullptr};
133};
134
136 const double joint_to_actuator_reduction, const double joint_offset)
137: reduction_(joint_to_actuator_reduction), jnt_offset_(joint_offset)
138{
139 if (reduction_ == 0.0)
140 {
141 throw Exception("Transmission reduction ratio cannot be zero.");
142 }
143}
144
145template <class HandleType>
146HandleType get_by_interface(
147 const std::vector<HandleType> & handles, const std::string & interface_name)
148{
149 const auto result = std::find_if(
150 handles.cbegin(), handles.cend(),
151 [&interface_name](const auto handle) { return handle.get_interface_name() == interface_name; });
152 if (result == handles.cend())
153 {
154 return HandleType(handles.cbegin()->get_name(), interface_name, nullptr);
155 }
156 return *result;
157}
158
159template <class T>
160bool are_names_identical(const std::vector<T> & handles)
161{
162 std::vector<std::string> names;
163 std::transform(
164 handles.cbegin(), handles.cend(), std::back_inserter(names),
165 [](const auto & handle) { return handle.get_name(); });
166 return std::equal(names.cbegin() + 1, names.cend(), names.cbegin());
167}
168
170 const std::vector<JointHandle> & joint_handles,
171 const std::vector<ActuatorHandle> & actuator_handles)
172{
173 if (joint_handles.empty())
174 {
175 throw Exception("No joint handles were passed in");
176 }
177
178 if (actuator_handles.empty())
179 {
180 throw Exception("No actuator handles were passed in");
181 }
182
183 if (!are_names_identical(joint_handles))
184 {
185 throw Exception("Joint names given to transmissions should be identical");
186 }
187
188 if (!are_names_identical(actuator_handles))
189 {
190 throw Exception("Actuator names given to transmissions should be identical");
191 }
192
193 joint_position_ = get_by_interface(joint_handles, hardware_interface::HW_IF_POSITION);
194 joint_velocity_ = get_by_interface(joint_handles, hardware_interface::HW_IF_VELOCITY);
195 joint_effort_ = get_by_interface(joint_handles, hardware_interface::HW_IF_EFFORT);
196
197 if (!joint_position_ && !joint_velocity_ && !joint_effort_)
198 {
199 throw Exception("None of the provided joint handles are valid or from the required interfaces");
200 }
201
202 actuator_position_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_POSITION);
203 actuator_velocity_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_VELOCITY);
204 actuator_effort_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_EFFORT);
205
206 if (!actuator_position_ && !actuator_velocity_ && !actuator_effort_)
207 {
208 throw Exception("None of the provided joint handles are valid or from the required interfaces");
209 }
210}
211
213{
214 if (joint_effort_ && actuator_effort_)
215 {
216 joint_effort_.set_value(actuator_effort_.get_value() * reduction_);
217 }
218
219 if (joint_velocity_ && actuator_velocity_)
220 {
221 joint_velocity_.set_value(actuator_velocity_.get_value() / reduction_);
222 }
223
224 if (joint_position_ && actuator_position_)
225 {
226 joint_position_.set_value(actuator_position_.get_value() / reduction_ + jnt_offset_);
227 }
228}
229
231{
232 if (joint_effort_ && actuator_effort_)
233 {
234 actuator_effort_.set_value(joint_effort_.get_value() / reduction_);
235 }
236
237 if (joint_velocity_ && actuator_velocity_)
238 {
239 actuator_velocity_.set_value(joint_velocity_.get_value() * reduction_);
240 }
241
242 if (joint_position_ && actuator_position_)
243 {
244 actuator_position_.set_value((joint_position_.get_value() - jnt_offset_) * reduction_);
245 }
246}
247
248} // namespace transmission_interface
249
250#endif // TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
Definition exception.hpp:23
Implementation of a simple reducer transmission.
Definition simple_transmission.hpp:81
SimpleTransmission(const double joint_to_actuator_reduction, const double joint_offset=0.0)
Definition simple_transmission.hpp:135
std::size_t num_actuators() const override
Definition simple_transmission.hpp:116
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition simple_transmission.hpp:212
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition simple_transmission.hpp:230
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:169
std::size_t num_joints() const override
Definition simple_transmission.hpp:117
Abstract base class for representing mechanical transmissions.
Definition transmission.hpp:46
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