ros2_control - galactic
Loading...
Searching...
No Matches
differential_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__DIFFERENTIAL_TRANSMISSION_HPP_
16#define TRANSMISSION_INTERFACE__DIFFERENTIAL_TRANSMISSION_HPP_
17
18#include <cassert>
19#include <set>
20#include <string>
21#include <vector>
22
23#include "hardware_interface/types/hardware_interface_type_values.hpp"
24#include "transmission_interface/accessor.hpp"
25#include "transmission_interface/exception.hpp"
26#include "transmission_interface/transmission.hpp"
27
29{
31
105{
106public:
114 const std::vector<double> & actuator_reduction, const std::vector<double> & joint_reduction,
115 const std::vector<double> & joint_offset = {0.0, 0.0});
116
122 void configure(
123 const std::vector<JointHandle> & joint_handles,
124 const std::vector<ActuatorHandle> & actuator_handles) override;
125
127
131 void actuator_to_joint() override;
132
134
138 void joint_to_actuator() override;
139
140 std::size_t num_actuators() const override { return 2; }
141 std::size_t num_joints() const override { return 2; }
142
143 const std::vector<double> & get_actuator_reduction() const { return actuator_reduction_; }
144 const std::vector<double> & get_joint_reduction() const { return joint_reduction_; }
145 const std::vector<double> & get_joint_offset() const { return joint_offset_; }
146
148 std::string get_handles_info() const;
149
150protected:
151 std::vector<double> actuator_reduction_;
152 std::vector<double> joint_reduction_;
153 std::vector<double> joint_offset_;
154
155 std::vector<JointHandle> joint_position_;
156 std::vector<JointHandle> joint_velocity_;
157 std::vector<JointHandle> joint_effort_;
158
159 std::vector<ActuatorHandle> actuator_position_;
160 std::vector<ActuatorHandle> actuator_velocity_;
161 std::vector<ActuatorHandle> actuator_effort_;
162};
163
165 const std::vector<double> & actuator_reduction, const std::vector<double> & joint_reduction,
166 const std::vector<double> & joint_offset)
167: actuator_reduction_(actuator_reduction),
168 joint_reduction_(joint_reduction),
169 joint_offset_(joint_offset)
170{
171 if (
172 num_actuators() != actuator_reduction_.size() || num_joints() != joint_reduction_.size() ||
173 num_joints() != joint_offset_.size())
174 {
175 throw Exception("Reduction and offset vectors must have size 2.");
176 }
177
178 if (
179 0.0 == actuator_reduction_[0] || 0.0 == actuator_reduction_[1] || 0.0 == joint_reduction_[0] ||
180 0.0 == joint_reduction_[1])
181 {
182 throw Exception("Transmission reduction ratios cannot be zero.");
183 }
184}
185
187 const std::vector<JointHandle> & joint_handles,
188 const std::vector<ActuatorHandle> & actuator_handles)
189{
190 if (joint_handles.empty())
191 {
192 throw Exception("No joint handles were passed in");
193 }
194
195 if (actuator_handles.empty())
196 {
197 throw Exception("No actuator handles were passed in");
198 }
199
200 const auto joint_names = get_names(joint_handles);
201 if (joint_names.size() != 2)
202 {
203 throw Exception(
204 "There should be exactly two unique joint names but was given " + to_string(joint_names));
205 }
206 const auto actuator_names = get_names(actuator_handles);
207 if (actuator_names.size() != 2)
208 {
209 throw Exception(
210 "There should be exactly two unique actuator names but was given " +
211 to_string(actuator_names));
212 }
213
214 joint_position_ =
215 get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_POSITION);
216 joint_velocity_ =
217 get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_VELOCITY);
218 joint_effort_ = get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_EFFORT);
219
220 if (joint_position_.size() != 2 && joint_velocity_.size() != 2 && joint_effort_.size() != 2)
221 {
222 throw Exception("Not enough valid or required joint handles were presented.");
223 }
224
225 actuator_position_ =
226 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_POSITION);
227 actuator_velocity_ =
228 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_VELOCITY);
229 actuator_effort_ =
230 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_EFFORT);
231
232 if (
233 actuator_position_.size() != 2 && actuator_velocity_.size() != 2 &&
234 actuator_effort_.size() != 2)
235 {
236 throw Exception(
237 "Not enough valid or required actuator handles were presented. \n" + get_handles_info());
238 }
239
240 if (
241 joint_position_.size() != actuator_position_.size() &&
242 joint_velocity_.size() != actuator_velocity_.size() &&
243 joint_effort_.size() != actuator_effort_.size())
244 {
245 throw Exception("Pair-wise mismatch on interfaces. \n" + get_handles_info());
246 }
247}
248
250{
251 const auto & ar = actuator_reduction_;
252 const auto & jr = joint_reduction_;
253
254 auto & act_pos = actuator_position_;
255 auto & joint_pos = joint_position_;
256 if (act_pos.size() == num_actuators() && joint_pos.size() == num_joints())
257 {
258 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
259
260 joint_pos[0].set_value(
261 (act_pos[0].get_value() / ar[0] + act_pos[1].get_value() / ar[1]) / (2.0 * jr[0]) +
262 joint_offset_[0]);
263 joint_pos[1].set_value(
264 (act_pos[0].get_value() / ar[0] - act_pos[1].get_value() / ar[1]) / (2.0 * jr[1]) +
265 joint_offset_[1]);
266 }
267
268 auto & act_vel = actuator_velocity_;
269 auto & joint_vel = joint_velocity_;
270 if (act_vel.size() == num_actuators() && joint_vel.size() == num_joints())
271 {
272 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
273
274 joint_vel[0].set_value(
275 (act_vel[0].get_value() / ar[0] + act_vel[1].get_value() / ar[1]) / (2.0 * jr[0]));
276 joint_vel[1].set_value(
277 (act_vel[0].get_value() / ar[0] - act_vel[1].get_value() / ar[1]) / (2.0 * jr[1]));
278 }
279
280 auto & act_eff = actuator_effort_;
281 auto & joint_eff = joint_effort_;
282 if (act_eff.size() == num_actuators() && joint_eff.size() == num_joints())
283 {
284 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
285
286 joint_eff[0].set_value(
287 jr[0] * (act_eff[0].get_value() * ar[0] + act_eff[1].get_value() * ar[1]));
288 joint_eff[1].set_value(
289 jr[1] * (act_eff[0].get_value() * ar[0] - act_eff[1].get_value() * ar[1]));
290 }
291}
292
294{
295 const auto & ar = actuator_reduction_;
296 const auto & jr = joint_reduction_;
297
298 auto & act_pos = actuator_position_;
299 auto & joint_pos = joint_position_;
300 if (act_pos.size() == num_actuators() && joint_pos.size() == num_joints())
301 {
302 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
303
304 double joints_offset_applied[2] = {
305 joint_pos[0].get_value() - joint_offset_[0], joint_pos[1].get_value() - joint_offset_[1]};
306 act_pos[0].set_value(
307 (joints_offset_applied[0] * jr[0] + joints_offset_applied[1] * jr[1]) * ar[0]);
308 act_pos[1].set_value(
309 (joints_offset_applied[0] * jr[0] - joints_offset_applied[1] * jr[1]) * ar[1]);
310 }
311
312 auto & act_vel = actuator_velocity_;
313 auto & joint_vel = joint_velocity_;
314 if (act_vel.size() == num_actuators() && joint_vel.size() == num_joints())
315 {
316 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
317
318 act_vel[0].set_value(
319 (joint_vel[0].get_value() * jr[0] + joint_vel[1].get_value() * jr[1]) * ar[0]);
320 act_vel[1].set_value(
321 (joint_vel[0].get_value() * jr[0] - joint_vel[1].get_value() * jr[1]) * ar[1]);
322 }
323
324 auto & act_eff = actuator_effort_;
325 auto & joint_eff = joint_effort_;
326 if (act_eff.size() == num_actuators() && joint_eff.size() == num_joints())
327 {
328 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
329
330 act_eff[0].set_value(
331 (joint_eff[0].get_value() / jr[0] + joint_eff[1].get_value() / jr[1]) / (2.0 * ar[0]));
332 act_eff[1].set_value(
333 (joint_eff[0].get_value() / jr[0] - joint_eff[1].get_value() / jr[1]) / (2.0 * ar[1]));
334 }
335}
336
338{
339 return std::string("Got the following handles:\n") +
340 "Joint position: " + to_string(get_names(joint_position_)) +
341 ", Actuator position: " + to_string(get_names(actuator_position_)) + "\n" +
342 "Joint velocity: " + to_string(get_names(joint_velocity_)) +
343 ", Actuator velocity: " + to_string(get_names(actuator_velocity_)) + "\n" +
344 "Joint effort: " + to_string(get_names(joint_effort_)) +
345 ", Actuator effort: " + to_string(get_names(actuator_effort_));
346}
347
348} // namespace transmission_interface
349
350#endif // TRANSMISSION_INTERFACE__DIFFERENTIAL_TRANSMISSION_HPP_
Implementation of a differential transmission.
Definition differential_transmission.hpp:105
DifferentialTransmission(const std::vector< double > &actuator_reduction, const std::vector< double > &joint_reduction, const std::vector< double > &joint_offset={0.0, 0.0})
Definition differential_transmission.hpp:164
std::size_t num_joints() const override
Definition differential_transmission.hpp:141
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition differential_transmission.hpp:293
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition differential_transmission.hpp:249
std::string get_handles_info() const
Get human-friendly report of handles.
Definition differential_transmission.hpp:337
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Definition differential_transmission.hpp:186
std::size_t num_actuators() const override
Definition differential_transmission.hpp:140
Definition exception.hpp:23
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