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"
116 const std::vector<double> & actuator_reduction,
const std::vector<double> & joint_reduction,
117 const std::vector<double> & joint_offset = std::vector<double>(2, 0.0));
125 const std::vector<JointHandle> & joint_handles,
126 const std::vector<ActuatorHandle> & actuator_handles)
override;
147 const std::vector<double> & get_actuator_reduction()
const {
return actuator_reduction_; }
148 const std::vector<double> & get_joint_reduction()
const {
return joint_reduction_; }
149 const std::vector<double> & get_joint_offset()
const {
return joint_offset_; }
155 std::vector<double> actuator_reduction_;
156 std::vector<double> joint_reduction_;
157 std::vector<double> joint_offset_;
159 std::vector<JointHandle> joint_position_;
160 std::vector<JointHandle> joint_velocity_;
161 std::vector<JointHandle> joint_effort_;
163 std::vector<ActuatorHandle> actuator_position_;
164 std::vector<ActuatorHandle> actuator_velocity_;
165 std::vector<ActuatorHandle> actuator_effort_;
169 const std::vector<double> & actuator_reduction,
const std::vector<double> & joint_reduction,
170 const std::vector<double> & joint_offset)
171: actuator_reduction_(actuator_reduction),
172 joint_reduction_(joint_reduction),
173 joint_offset_(joint_offset)
179 throw Exception(
"Reduction and offset vectors must have size 2.");
182 0.0 == actuator_reduction_[0] || 0.0 == actuator_reduction_[1] || 0.0 == joint_reduction_[0] ||
183 0.0 == joint_reduction_[1])
185 throw Exception(
"Transmission reduction ratios cannot be zero.");
190 const std::vector<JointHandle> & joint_handles,
191 const std::vector<ActuatorHandle> & actuator_handles)
193 if (joint_handles.empty())
195 throw Exception(
"No joint handles were passed in");
198 if (actuator_handles.empty())
200 throw Exception(
"No actuator handles were passed in");
203 const auto joint_names = get_names(joint_handles);
204 if (joint_names.size() != 2)
207 "There should be exactly two unique joint names but was given " + to_string(joint_names));
209 const auto actuator_names = get_names(actuator_handles);
210 if (actuator_names.size() != 2)
213 "There should be exactly two unique actuator names but was given " +
214 to_string(actuator_names));
223 if (joint_position_.size() != 2 && joint_velocity_.size() != 2 && joint_effort_.size() != 2)
225 throw Exception(
"Not enough valid or required joint handles were presented.");
236 actuator_position_.size() != 2 && actuator_velocity_.size() != 2 &&
237 actuator_effort_.size() != 2)
240 "Not enough valid or required actuator handles were presented. \n" +
get_handles_info());
244 joint_position_.size() != actuator_position_.size() &&
245 joint_velocity_.size() != actuator_velocity_.size() &&
246 joint_effort_.size() != actuator_effort_.size())
254 const auto & ar = actuator_reduction_;
255 const auto & jr = joint_reduction_;
258 auto & act_pos = actuator_position_;
259 auto & joint_pos = joint_position_;
262 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
264 joint_pos[0].set_value(act_pos[0].get_value() / (jr[0] * ar[0]) + joint_offset_[0]);
265 joint_pos[1].set_value(
266 (act_pos[1].get_value() / ar[1] - act_pos[0].get_value() / (jr[0] * ar[0])) / jr[1] +
271 auto & act_vel = actuator_velocity_;
272 auto & joint_vel = joint_velocity_;
275 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
277 joint_vel[0].set_value(act_vel[0].get_value() / (jr[0] * ar[0]));
278 joint_vel[1].set_value(
279 (act_vel[1].get_value() / ar[1] - act_vel[0].get_value() / (jr[0] * ar[0])) / jr[1]);
283 auto & act_eff = actuator_effort_;
284 auto & joint_eff = joint_effort_;
287 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
289 joint_eff[0].set_value(jr[0] * act_eff[0].get_value() * ar[0]);
290 joint_eff[1].set_value(
291 jr[1] * (act_eff[1].get_value() * ar[1] - jr[0] * act_eff[0].get_value() * ar[0]));
297 const auto & ar = actuator_reduction_;
298 const auto & jr = joint_reduction_;
301 auto & act_pos = actuator_position_;
302 auto & joint_pos = joint_position_;
305 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
307 double joints_offset_applied[2] = {
308 joint_pos[0].get_value() - joint_offset_[0], joint_pos[1].get_value() - joint_offset_[1]};
309 act_pos[0].set_value(joints_offset_applied[0] * jr[0] * ar[0]);
310 act_pos[1].set_value((joints_offset_applied[0] + joints_offset_applied[1] * jr[1]) * ar[1]);
314 auto & act_vel = actuator_velocity_;
315 auto & joint_vel = joint_velocity_;
318 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
320 act_vel[0].set_value(joint_vel[0].get_value() * jr[0] * ar[0]);
321 act_vel[1].set_value((joint_vel[0].get_value() + joint_vel[1].get_value() * jr[1]) * ar[1]);
325 auto & act_eff = actuator_effort_;
326 auto & joint_eff = joint_effort_;
329 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
331 act_eff[0].set_value(joint_eff[0].get_value() / (ar[0] * jr[0]));
332 act_eff[1].set_value((joint_eff[0].get_value() + joint_eff[1].get_value() / jr[1]) / ar[1]);
338 return std::string(
"Got the following handles:\n") +
339 "Joint position: " + to_string(get_names(joint_position_)) +
340 ", Actuator position: " + to_string(get_names(actuator_position_)) +
"\n" +
341 "Joint velocity: " + to_string(get_names(joint_velocity_)) +
342 ", Actuator velocity: " + to_string(get_names(actuator_velocity_)) +
"\n" +
343 "Joint effort: " + to_string(get_names(joint_effort_)) +
344 ", 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:107
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition four_bar_linkage_transmission.hpp:295
std::size_t num_actuators() const override
Definition four_bar_linkage_transmission.hpp:144
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:168
std::size_t num_joints() const override
Definition four_bar_linkage_transmission.hpp:145
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition four_bar_linkage_transmission.hpp:252
std::string get_handles_info() const
Get human-friendly report of handles.
Definition four_bar_linkage_transmission.hpp:336
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Definition four_bar_linkage_transmission.hpp:189
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