17#ifndef TRANSMISSION_INTERFACE__FOUR_BAR_LINKAGE_TRANSMISSION_HPP_
18#define TRANSMISSION_INTERFACE__FOUR_BAR_LINKAGE_TRANSMISSION_HPP_
20#include <fmt/compile.h>
26#include "hardware_interface/types/hardware_interface_type_values.hpp"
27#include "transmission_interface/accessor.hpp"
28#include "transmission_interface/exception.hpp"
29#include "transmission_interface/transmission.hpp"
119 const std::vector<double> & actuator_reduction,
const std::vector<double> & joint_reduction,
120 const std::vector<double> & joint_offset = std::vector<double>(2, 0.0));
128 const std::vector<JointHandle> & joint_handles,
129 const std::vector<ActuatorHandle> & actuator_handles)
override;
150 const std::vector<double> & get_actuator_reduction()
const {
return actuator_reduction_; }
151 const std::vector<double> & get_joint_reduction()
const {
return joint_reduction_; }
152 const std::vector<double> & get_joint_offset()
const {
return joint_offset_; }
172 std::vector<double> actuator_reduction_;
173 std::vector<double> joint_reduction_;
174 std::vector<double> joint_offset_;
176 std::vector<JointHandle> joint_position_;
177 std::vector<JointHandle> joint_velocity_;
178 std::vector<JointHandle> joint_effort_;
180 std::vector<ActuatorHandle> actuator_position_;
181 std::vector<ActuatorHandle> actuator_velocity_;
182 std::vector<ActuatorHandle> actuator_effort_;
186 const std::vector<double> & actuator_reduction,
const std::vector<double> & joint_reduction,
187 const std::vector<double> & joint_offset)
188: actuator_reduction_(actuator_reduction),
189 joint_reduction_(joint_reduction),
190 joint_offset_(joint_offset)
196 throw Exception(
"Reduction and offset vectors must have size 2.");
199 0.0 == actuator_reduction_[0] || 0.0 == actuator_reduction_[1] || 0.0 == joint_reduction_[0] ||
200 0.0 == joint_reduction_[1])
202 throw Exception(
"Transmission reduction ratios cannot be zero.");
207 const std::vector<JointHandle> & joint_handles,
208 const std::vector<ActuatorHandle> & actuator_handles)
210 if (joint_handles.empty())
212 throw Exception(
"No joint handles were passed in");
215 if (actuator_handles.empty())
217 throw Exception(
"No actuator handles were passed in");
220 const auto joint_names = get_names(joint_handles);
221 if (joint_names.size() != 2)
225 FMT_COMPILE(
"There should be exactly two unique joint names but was given '{}'."),
226 to_string(joint_names)));
228 const auto actuator_names = get_names(actuator_handles);
229 if (actuator_names.size() != 2)
233 FMT_COMPILE(
"There should be exactly two unique actuator names but was given '{}'."),
234 to_string(actuator_names)));
243 if (joint_position_.size() != 2 && joint_velocity_.size() != 2 && joint_effort_.size() != 2)
245 throw Exception(
"Not enough valid or required joint handles were presented.");
256 actuator_position_.size() != 2 && actuator_velocity_.size() != 2 &&
257 actuator_effort_.size() != 2)
261 FMT_COMPILE(
"Not enough valid or required actuator handles were presented. \n{}"),
266 joint_position_.size() != actuator_position_.size() &&
267 joint_velocity_.size() != actuator_velocity_.size() &&
268 joint_effort_.size() != actuator_effort_.size())
271 fmt::format(FMT_COMPILE(
"Pair-wise mismatch on interfaces. \n{}"),
get_handles_info()));
277 const auto & ar = actuator_reduction_;
278 const auto & jr = joint_reduction_;
281 auto & act_pos = actuator_position_;
282 auto & joint_pos = joint_position_;
285 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
287 joint_pos[0].set_value(act_pos[0].get_value() / (jr[0] * ar[0]) + joint_offset_[0]);
288 joint_pos[1].set_value(
289 (act_pos[1].get_value() / ar[1] - act_pos[0].get_value() / (jr[0] * ar[0])) / jr[1] +
294 auto & act_vel = actuator_velocity_;
295 auto & joint_vel = joint_velocity_;
298 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
300 joint_vel[0].set_value(act_vel[0].get_value() / (jr[0] * ar[0]));
301 joint_vel[1].set_value(
302 (act_vel[1].get_value() / ar[1] - act_vel[0].get_value() / (jr[0] * ar[0])) / jr[1]);
306 auto & act_eff = actuator_effort_;
307 auto & joint_eff = joint_effort_;
310 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
312 joint_eff[0].set_value(jr[0] * act_eff[0].get_value() * ar[0] + act_eff[1].get_value() * ar[1]);
313 joint_eff[1].set_value(jr[1] * act_eff[1].get_value() * ar[1]);
319 const auto & ar = actuator_reduction_;
320 const auto & jr = joint_reduction_;
323 auto & act_pos = actuator_position_;
324 auto & joint_pos = joint_position_;
327 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
329 double joints_offset_applied[2] = {
330 joint_pos[0].get_value() - joint_offset_[0], joint_pos[1].get_value() - joint_offset_[1]};
331 act_pos[0].set_value(joints_offset_applied[0] * jr[0] * ar[0]);
332 act_pos[1].set_value((joints_offset_applied[0] + joints_offset_applied[1] * jr[1]) * ar[1]);
336 auto & act_vel = actuator_velocity_;
337 auto & joint_vel = joint_velocity_;
340 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
342 act_vel[0].set_value(joint_vel[0].get_value() * jr[0] * ar[0]);
343 act_vel[1].set_value((joint_vel[0].get_value() + joint_vel[1].get_value() * jr[1]) * ar[1]);
347 auto & act_eff = actuator_effort_;
348 auto & joint_eff = joint_effort_;
351 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
353 act_eff[0].set_value(
354 (joint_eff[0].get_value() - joint_eff[1].get_value() / jr[1]) / (jr[0] * ar[0]));
355 act_eff[1].set_value(joint_eff[1].get_value() / (ar[1] * jr[1]));
363 "Got the following handles:\n"
364 "Joint position: {}, Actuator position: {}\n"
365 "Joint velocity: {}, Actuator velocity: {}\n"
366 "Joint effort: {}, Actuator effort: {}"),
367 to_string(get_names(joint_position_)), to_string(get_names(actuator_position_)),
368 to_string(get_names(joint_velocity_)), to_string(get_names(actuator_velocity_)),
369 to_string(get_names(joint_effort_)), to_string(get_names(actuator_effort_)));
Definition exception.hpp:23
Implementation of a four-bar-linkage transmission.
Definition four_bar_linkage_transmission.hpp:110
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition four_bar_linkage_transmission.hpp:317
std::vector< std::string > get_supported_joint_interfaces() const override
Definition four_bar_linkage_transmission.hpp:164
std::size_t num_actuators() const override
Definition four_bar_linkage_transmission.hpp:147
std::vector< std::string > get_supported_actuator_interfaces() const override
Definition four_bar_linkage_transmission.hpp:157
FourBarLinkageTransmission(const std::vector< double > &actuator_reduction, const std::vector< double > &joint_reduction, const std::vector< double > &joint_offset=std::vector< double >(2, 0.0))
Definition four_bar_linkage_transmission.hpp:185
std::size_t num_joints() const override
Definition four_bar_linkage_transmission.hpp:148
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition four_bar_linkage_transmission.hpp:275
std::string get_handles_info() const
Get human-friendly report of handles.
Definition four_bar_linkage_transmission.hpp:359
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Definition four_bar_linkage_transmission.hpp:206
Abstract base class for representing mechanical transmissions.
Definition transmission.hpp:48
constexpr char HW_IF_EFFORT[]
Constant defining effort interface name.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition hardware_interface_type_values.hpp:21
Definition accessor.hpp:25