17#ifndef TRANSMISSION_INTERFACE__FOUR_BAR_LINKAGE_TRANSMISSION_HPP_
18#define TRANSMISSION_INTERFACE__FOUR_BAR_LINKAGE_TRANSMISSION_HPP_
24#include "transmission_interface/accessor.hpp"
25#include "transmission_interface/exception.hpp"
26#include "transmission_interface/transmission.hpp"
113 const std::vector<double> & actuator_reduction,
const std::vector<double> & joint_reduction,
114 const std::vector<double> & joint_offset = std::vector<double>(2, 0.0));
122 const std::vector<JointHandle> & joint_handles,
123 const std::vector<ActuatorHandle> & actuator_handles)
override;
142 const std::vector<double> & get_actuator_reduction()
const {
return actuator_reduction_; }
143 const std::vector<double> & get_joint_reduction()
const {
return joint_reduction_; }
144 const std::vector<double> & get_joint_offset()
const {
return joint_offset_; }
150 std::vector<double> actuator_reduction_;
151 std::vector<double> joint_reduction_;
152 std::vector<double> joint_offset_;
154 std::vector<JointHandle> joint_position_;
155 std::vector<JointHandle> joint_velocity_;
156 std::vector<JointHandle> joint_effort_;
158 std::vector<ActuatorHandle> actuator_position_;
159 std::vector<ActuatorHandle> actuator_velocity_;
160 std::vector<ActuatorHandle> actuator_effort_;
164 const std::vector<double> & actuator_reduction,
const std::vector<double> & joint_reduction,
165 const std::vector<double> & joint_offset)
166: actuator_reduction_(actuator_reduction),
167 joint_reduction_(joint_reduction),
168 joint_offset_(joint_offset)
174 throw Exception(
"Reduction and offset vectors must have size 2.");
177 0.0 == actuator_reduction_[0] || 0.0 == actuator_reduction_[1] || 0.0 == joint_reduction_[0] ||
178 0.0 == joint_reduction_[1])
180 throw Exception(
"Transmission reduction ratios cannot be zero.");
185 const std::vector<JointHandle> & joint_handles,
186 const std::vector<ActuatorHandle> & actuator_handles)
188 if (joint_handles.empty())
190 throw Exception(
"No joint handles were passed in");
193 if (actuator_handles.empty())
195 throw Exception(
"No actuator handles were passed in");
198 const auto joint_names = get_names(joint_handles);
199 if (joint_names.size() != 2)
202 "There should be exactly two unique joint names but was given " + to_string(joint_names));
204 const auto actuator_names = get_names(actuator_handles);
205 if (actuator_names.size() != 2)
208 "There should be exactly two unique actuator names but was given " +
209 to_string(actuator_names));
218 if (joint_position_.size() != 2 && joint_velocity_.size() != 2 && joint_effort_.size() != 2)
220 throw Exception(
"Not enough valid or required joint handles were presented.");
231 actuator_position_.size() != 2 && actuator_velocity_.size() != 2 &&
232 actuator_effort_.size() != 2)
235 "Not enough valid or required actuator handles were presented. \n" +
get_handles_info());
239 joint_position_.size() != actuator_position_.size() &&
240 joint_velocity_.size() != actuator_velocity_.size() &&
241 joint_effort_.size() != actuator_effort_.size())
249 const auto & ar = actuator_reduction_;
250 const auto & jr = joint_reduction_;
253 auto & act_pos = actuator_position_;
254 auto & joint_pos = joint_position_;
257 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
259 joint_pos[0].set_value(act_pos[0].get_value() / (jr[0] * ar[0]) + joint_offset_[0]);
260 joint_pos[1].set_value(
261 (act_pos[1].get_value() / ar[1] - act_pos[0].get_value() / (jr[0] * ar[0])) / jr[1] +
266 auto & act_vel = actuator_velocity_;
267 auto & joint_vel = joint_velocity_;
270 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
272 joint_vel[0].set_value(act_vel[0].get_value() / (jr[0] * ar[0]));
273 joint_vel[1].set_value(
274 (act_vel[1].get_value() / ar[1] - act_vel[0].get_value() / (jr[0] * ar[0])) / jr[1]);
278 auto & act_eff = actuator_effort_;
279 auto & joint_eff = joint_effort_;
282 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
284 joint_eff[0].set_value(jr[0] * act_eff[0].get_value() * ar[0]);
285 joint_eff[1].set_value(
286 jr[1] * (act_eff[1].get_value() * ar[1] - act_eff[0].get_value() * ar[0] * jr[0]));
292 const auto & ar = actuator_reduction_;
293 const auto & jr = joint_reduction_;
296 auto & act_pos = actuator_position_;
297 auto & joint_pos = joint_position_;
300 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
302 double joints_offset_applied[2] = {
303 joint_pos[0].get_value() - joint_offset_[0], joint_pos[1].get_value() - joint_offset_[1]};
304 act_pos[0].set_value(joints_offset_applied[0] * jr[0] * ar[0]);
305 act_pos[1].set_value((joints_offset_applied[0] + joints_offset_applied[1] * jr[1]) * ar[1]);
309 auto & act_vel = actuator_velocity_;
310 auto & joint_vel = joint_velocity_;
313 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
315 act_vel[0].set_value(joint_vel[0].get_value() * jr[0] * ar[0]);
316 act_vel[1].set_value((joint_vel[0].get_value() + joint_vel[1].get_value() * jr[1]) * ar[1]);
320 auto & act_eff = actuator_effort_;
321 auto & joint_eff = joint_effort_;
324 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
326 act_eff[0].set_value(joint_eff[0].get_value() / (ar[0] * jr[0]));
327 act_eff[1].set_value((joint_eff[0].get_value() + joint_eff[1].get_value() / jr[1]) / ar[1]);
333 return std::string(
"Got the following handles:\n") +
334 "Joint position: " + to_string(get_names(joint_position_)) +
335 ", Actuator position: " + to_string(get_names(actuator_position_)) +
"\n" +
336 "Joint velocity: " + to_string(get_names(joint_velocity_)) +
337 ", Actuator velocity: " + to_string(get_names(actuator_velocity_)) +
"\n" +
338 "Joint effort: " + to_string(get_names(joint_effort_)) +
339 ", Actuator effort: " + to_string(get_names(actuator_effort_));
Definition exception.hpp:23
Implementation of a four-bar-linkage transmission.
Definition four_bar_linkage_transmission.hpp:104
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition four_bar_linkage_transmission.hpp:290
std::size_t num_actuators() const override
Definition four_bar_linkage_transmission.hpp:139
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:163
std::size_t num_joints() const override
Definition four_bar_linkage_transmission.hpp:140
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition four_bar_linkage_transmission.hpp:247
std::string get_handles_info() const
Get human-friendly report of handles.
Definition four_bar_linkage_transmission.hpp:331
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Definition four_bar_linkage_transmission.hpp:184
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