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