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"
92 const double joint_to_actuator_reduction,
const double joint_offset = 0.0);
102 const std::vector<JointHandle> & joint_handles,
103 const std::vector<ActuatorHandle> & actuator_handles)
override;
124 double get_actuator_reduction()
const {
return reduction_; }
125 double get_joint_offset()
const {
return jnt_offset_; }
131 JointHandle joint_position_ = {
"",
"",
nullptr};
132 JointHandle joint_velocity_ = {
"",
"",
nullptr};
133 JointHandle joint_effort_ = {
"",
"",
nullptr};
135 ActuatorHandle actuator_position_ = {
"",
"",
nullptr};
136 ActuatorHandle actuator_velocity_ = {
"",
"",
nullptr};
137 ActuatorHandle actuator_effort_ = {
"",
"",
nullptr};
141 const double joint_to_actuator_reduction,
const double joint_offset)
142: reduction_(joint_to_actuator_reduction), jnt_offset_(joint_offset)
144 if (reduction_ == 0.0)
146 throw Exception(
"Transmission reduction ratio cannot be zero.");
150template <
class HandleType>
151HandleType get_by_interface(
152 const std::vector<HandleType> & handles,
const std::string & interface_name)
154 const auto result = std::find_if(
155 handles.cbegin(), handles.cend(),
156 [&interface_name](
const auto handle) { return handle.get_interface_name() == interface_name; });
157 if (result == handles.cend())
159 return HandleType(handles.cbegin()->get_prefix_name(), interface_name,
nullptr);
165bool are_names_identical(
const std::vector<T> & handles)
167 std::vector<std::string> names;
169 handles.cbegin(), handles.cend(), std::back_inserter(names),
170 [](
const auto & handle) { return handle.get_prefix_name(); });
171 return std::equal(names.cbegin() + 1, names.cend(), names.cbegin());
175 const std::vector<JointHandle> & joint_handles,
176 const std::vector<ActuatorHandle> & actuator_handles)
178 if (joint_handles.empty())
180 throw Exception(
"No joint handles were passed in");
183 if (actuator_handles.empty())
185 throw Exception(
"No actuator handles were passed in");
188 if (!are_names_identical(joint_handles))
190 throw Exception(
"Joint names given to transmissions should be identical");
193 if (!are_names_identical(actuator_handles))
195 throw Exception(
"Actuator names given to transmissions should be identical");
202 if (!joint_position_ && !joint_velocity_ && !joint_effort_)
204 throw Exception(
"None of the provided joint handles are valid or from the required interfaces");
211 if (!actuator_position_ && !actuator_velocity_ && !actuator_effort_)
213 throw Exception(
"None of the provided joint handles are valid or from the required interfaces");
219 if (joint_effort_ && actuator_effort_)
221 joint_effort_.set_value(actuator_effort_.get_value() * reduction_);
224 if (joint_velocity_ && actuator_velocity_)
226 joint_velocity_.set_value(actuator_velocity_.get_value() / reduction_);
229 if (joint_position_ && actuator_position_)
231 joint_position_.set_value(actuator_position_.get_value() / reduction_ + jnt_offset_);
237 if (joint_effort_ && actuator_effort_)
239 actuator_effort_.set_value(joint_effort_.get_value() / reduction_);
242 if (joint_velocity_ && actuator_velocity_)
244 actuator_velocity_.set_value(joint_velocity_.get_value() * reduction_);
247 if (joint_position_ && actuator_position_)
249 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:84
SimpleTransmission(const double joint_to_actuator_reduction, const double joint_offset=0.0)
Definition simple_transmission.hpp:140
std::size_t num_actuators() const override
Definition simple_transmission.hpp:121
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition simple_transmission.hpp:217
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition simple_transmission.hpp:235
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:174
std::size_t num_joints() const override
Definition simple_transmission.hpp:122
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