15#ifndef TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
16#define TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
23#include "hardware_interface/types/hardware_interface_type_values.hpp"
24#include "transmission_interface/exception.hpp"
25#include "transmission_interface/transmission.hpp"
89 const double joint_to_actuator_reduction,
const double joint_offset = 0.0);
99 const std::vector<JointHandle> & joint_handles,
100 const std::vector<ActuatorHandle> & actuator_handles)
override;
119 double get_actuator_reduction()
const {
return reduction_; }
120 double get_joint_offset()
const {
return jnt_offset_; }
126 JointHandle joint_position_ = {
"",
"",
nullptr};
127 JointHandle joint_velocity_ = {
"",
"",
nullptr};
128 JointHandle joint_effort_ = {
"",
"",
nullptr};
130 ActuatorHandle actuator_position_ = {
"",
"",
nullptr};
131 ActuatorHandle actuator_velocity_ = {
"",
"",
nullptr};
132 ActuatorHandle actuator_effort_ = {
"",
"",
nullptr};
136 const double joint_to_actuator_reduction,
const double joint_offset)
137: reduction_(joint_to_actuator_reduction), jnt_offset_(joint_offset)
139 if (reduction_ == 0.0)
141 throw Exception(
"Transmission reduction ratio cannot be zero.");
145template <
class HandleType>
146HandleType get_by_interface(
147 const std::vector<HandleType> & handles,
const std::string & interface_name)
149 const auto result = std::find_if(
150 handles.cbegin(), handles.cend(),
151 [&interface_name](
const auto handle) { return handle.get_interface_name() == interface_name; });
152 if (result == handles.cend())
154 return HandleType(handles.cbegin()->get_name(), interface_name,
nullptr);
160bool are_names_identical(
const std::vector<T> & handles)
162 std::vector<std::string> names;
164 handles.cbegin(), handles.cend(), std::back_inserter(names),
165 [](
const auto & handle) { return handle.get_name(); });
166 return std::equal(names.cbegin() + 1, names.cend(), names.cbegin());
170 const std::vector<JointHandle> & joint_handles,
171 const std::vector<ActuatorHandle> & actuator_handles)
173 if (joint_handles.empty())
175 throw Exception(
"No joint handles were passed in");
178 if (actuator_handles.empty())
180 throw Exception(
"No actuator handles were passed in");
183 if (!are_names_identical(joint_handles))
185 throw Exception(
"Joint names given to transmissions should be identical");
188 if (!are_names_identical(actuator_handles))
190 throw Exception(
"Actuator names given to transmissions should be identical");
197 if (!joint_position_ && !joint_velocity_ && !joint_effort_)
199 throw Exception(
"None of the provided joint handles are valid or from the required interfaces");
206 if (!actuator_position_ && !actuator_velocity_ && !actuator_effort_)
208 throw Exception(
"None of the provided joint handles are valid or from the required interfaces");
214 if (joint_effort_ && actuator_effort_)
216 joint_effort_.set_value(actuator_effort_.get_value() * reduction_);
219 if (joint_velocity_ && actuator_velocity_)
221 joint_velocity_.set_value(actuator_velocity_.get_value() / reduction_);
224 if (joint_position_ && actuator_position_)
226 joint_position_.set_value(actuator_position_.get_value() / reduction_ + jnt_offset_);
232 if (joint_effort_ && actuator_effort_)
234 actuator_effort_.set_value(joint_effort_.get_value() / reduction_);
237 if (joint_velocity_ && actuator_velocity_)
239 actuator_velocity_.set_value(joint_velocity_.get_value() * reduction_);
242 if (joint_position_ && actuator_position_)
244 actuator_position_.set_value((joint_position_.get_value() - jnt_offset_) * reduction_);
Definition exception.hpp:23
Implementation of a simple reducer transmission.
Definition simple_transmission.hpp:81
SimpleTransmission(const double joint_to_actuator_reduction, const double joint_offset=0.0)
Definition simple_transmission.hpp:135
std::size_t num_actuators() const override
Definition simple_transmission.hpp:116
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition simple_transmission.hpp:212
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition simple_transmission.hpp:230
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Set up the data the transmission operates on.
Definition simple_transmission.hpp:169
std::size_t num_joints() const override
Definition simple_transmission.hpp:117
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