transmission_interface_loader.h
Go to the documentation of this file.
1 // Copyright (C) 2013, PAL Robotics S.L.
3 //
4 // Redistribution and use in source and binary forms, with or without
5 // modification, are permitted provided that the following conditions are met:
6 // * Redistributions of source code must retain the above copyright notice,
7 // this list of conditions and the following disclaimer.
8 // * Redistributions in binary form must reproduce the above copyright
9 // notice, this list of conditions and the following disclaimer in the
10 // documentation and/or other materials provided with the distribution.
11 // * Neither the name of PAL Robotics S.L. nor the names of its
12 // contributors may be used to endorse or promote products derived from
13 // this software without specific prior written permission.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 // POSSIBILITY OF SUCH DAMAGE.
27 
29 
30 #pragma once
31 
32 
33 // C++ standard
34 #include <algorithm>
35 #include <limits>
36 #include <map>
37 #include <string>
38 #include <utility>
39 #include <vector>
40 #include <memory>
41 
42 // ROS
43 #include <ros/console.h>
44 
45 // pluginlib
47 
48 // ros_control
55 
62 
63 namespace transmission_interface
64 {
65 
72 // TODO: Don't assume interfaces?
74 {
75  double position = {std::numeric_limits<double>::quiet_NaN()};
76  double velocity = {std::numeric_limits<double>::quiet_NaN()};
77  double effort = {std::numeric_limits<double>::quiet_NaN()};
78  double position_cmd = {std::numeric_limits<double>::quiet_NaN()};
79  double velocity_cmd = {std::numeric_limits<double>::quiet_NaN()};
80  double effort_cmd = {std::numeric_limits<double>::quiet_NaN()};
81  double absolute_position = {std::numeric_limits<double>::quiet_NaN()};
82  double torque_sensor = {std::numeric_limits<double>::quiet_NaN()};
83 
84  bool hasAbsolutePosition = {true};
85  bool hasTorqueSensor = {true};
86 };
87 
88 typedef std::map<std::string, RawJointData> RawJointDataMap;
89 
94 {
99 };
100 
102 {
107 };
108 
110 {
115 };
116 
118 {
125  std::vector<TransmissionSharedPtr> transmission_data;
126 };
127 
128 class RequisiteProvider // TODO: There must be a more descriptive name for this class!
129 {
130 public:
131  virtual ~RequisiteProvider() = default;
132 
147  virtual bool updateJointInterfaces(const TransmissionInfo& transmission_info,
148  hardware_interface::RobotHW* robot_hw,
149  JointInterfaces& joint_interfaces,
150  RawJointDataMap& raw_joint_data_map) = 0;
151 
152  bool loadTransmissionMaps(const TransmissionInfo& transmission_info,
153  TransmissionLoaderData& loader_data,
154  TransmissionSharedPtr transmission);
155 protected:
157  {
158  std::string name;
164  };
165 
166  virtual bool getJointStateData(const TransmissionInfo& transmission_info,
167  const RawJointDataMap& raw_joint_data_map,
168  JointData& jnt_state_data) = 0;
169 
170  virtual bool getJointCommandData(const TransmissionInfo& transmission_info,
171  const RawJointDataMap& raw_joint_data_map,
172  JointData& jnt_cmd_data) = 0;
173 
174  virtual bool getActuatorStateData(const TransmissionInfo& transmission_info,
175  hardware_interface::RobotHW* robot_hw,
176  ActuatorData& act_state_data) = 0;
177 
178  virtual bool getActuatorCommandData(const TransmissionInfo& transmission_info,
179  hardware_interface::RobotHW* robot_hw,
180  ActuatorData& act_cmd_data) = 0;
181 
182  virtual bool registerTransmission(TransmissionLoaderData& loader_data,
183  TransmissionHandleData& handle_data) = 0;
184 
185  template <class Interface>
186  static bool hasResource(const std::string& name, const Interface& iface)
187  {
189 
190  // Do nothing if resource already exists on the interface
191  const std::vector<std::string>& existing_resources = iface.getNames();
192  if (existing_resources.end() != std::find(existing_resources.begin(), existing_resources.end(), name))
193  {
194  ROS_DEBUG_STREAM_NAMED("parser", "Resource '" << name << "' already exists on interface '" <<
195  demangledTypeName<Interface>());
196  return true;
197  }
198  else
199  {
200  ROS_DEBUG_STREAM_NAMED("parser", "Resource '" << name << "' does not exist on interface '" <<
201  demangledTypeName<Interface>());
202  return false;
203  }
204  }
205 
206  template <class HardwareInterface, class Handle>
207  bool getActuatorHandles(const std::vector<ActuatorInfo>& actuators_info,
208  hardware_interface::RobotHW* robot_hw,
209  std::vector<Handle>& handles)
210  {
214 
215  HardwareInterface* hw_iface = robot_hw->get<HardwareInterface>();
216 
217  // Check required hardware interface
218  if (!hw_iface)
219  {
220  ROS_ERROR_STREAM_NAMED("parser", "Robot does not have the required hardware interface '" <<
221  demangledTypeName<HardwareInterface>() << "'.");
222  return false;
223  }
224 
225  // Get handles to all required resource
226  for (const auto& info : actuators_info)
227  {
228  try
229  {
230  handles.push_back(hw_iface->getHandle(info.name_));
231  }
232  catch(const HardwareInterfaceException& ex)
233  {
234  ROS_ERROR_STREAM_NAMED("parser", "Actuator '" << info.name_ <<
235  "' does not expose the required hardware interface '" <<
236  demangledTypeName<HardwareInterface>() << "'.");
237  return false;
238  }
239  }
240  return true;
241  }
242 };
243 
318 {
319 public:
325  RobotTransmissions* robot_transmissions);
326 
335  bool load(const std::string& urdf);
336 
345  bool load(const std::vector<TransmissionInfo>& transmission_info_vec);
346 
355  bool load(const TransmissionInfo& transmission_info);
356 
358 
359 private:
361  typedef std::shared_ptr<TransmissionClassLoader> TransmissionClassLoaderPtr;
363  typedef std::shared_ptr<RequisiteProviderClassLoader> RequisiteProviderClassLoaderPtr;
364 
365  typedef std::shared_ptr<RequisiteProvider> RequisiteProviderPtr;
366 
369 
370 private:
373 
375 };
376 
377 } // namespace
actuator_state_interface.h
demangle_symbol.h
transmission_interface::RawJointData::absolute_position
double absolute_position
Definition: transmission_interface_loader.h:81
transmission_interface::RawJointData::hasTorqueSensor
bool hasTorqueSensor
Definition: transmission_interface_loader.h:85
transmission_interface::RequisiteProvider::updateJointInterfaces
virtual bool updateJointInterfaces(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, JointInterfaces &joint_interfaces, RawJointDataMap &raw_joint_data_map)=0
Update a robot's joint interfaces with joint information contained in a transmission.
transmission_interface::InverseTransmissionInterfaces::act_to_jnt_eff_cmd
ActuatorToJointEffortInterface act_to_jnt_eff_cmd
Definition: transmission_interface_loader.h:114
transmission_interface::ActuatorToJointVelocityInterface
Definition: transmission_interface.h:423
transmission_interface::TransmissionSharedPtr
std::shared_ptr< Transmission > TransmissionSharedPtr
Definition: transmission.h:184
transmission_interface::InverseTransmissionInterfaces::act_to_jnt_vel_cmd
ActuatorToJointVelocityInterface act_to_jnt_vel_cmd
Definition: transmission_interface_loader.h:113
transmission_interface::JointInterfaces
Joint interfaces of a robot. Only used interfaces need to be populated.
Definition: transmission_interface_loader.h:93
transmission_interface::RequisiteProvider::TransmissionHandleData::name
std::string name
Definition: transmission_interface_loader.h:158
transmission_interface::ForwardTransmissionInterfaces::act_to_jnt_state
ActuatorToJointStateInterface act_to_jnt_state
Definition: transmission_interface_loader.h:103
transmission_interface::JointToActuatorVelocityInterface
Definition: transmission_interface.h:435
transmission_interface::RawJointData::position
double position
Definition: transmission_interface_loader.h:75
hardware_interface::JointStateInterface
ROS_DEBUG_STREAM_NAMED
#define ROS_DEBUG_STREAM_NAMED(name, args)
hardware_interface::InterfaceManager::get
T * get()
transmission_interface
Definition: bidirectional_effort_joint_interface_provider.h:36
transmission_interface::RequisiteProvider::getActuatorStateData
virtual bool getActuatorStateData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_state_data)=0
transmission_interface::RawJointData::effort
double effort
Definition: transmission_interface_loader.h:77
transmission_interface::TransmissionInterfaceLoader::req_provider_loader_
RequisiteProviderClassLoaderPtr req_provider_loader_
Definition: transmission_interface_loader.h:368
robot_transmissions.h
transmission_interface::TransmissionInterfaceLoader::TransmissionClassLoaderPtr
std::shared_ptr< TransmissionClassLoader > TransmissionClassLoaderPtr
Definition: transmission_interface_loader.h:361
transmission_interface::TransmissionLoaderData
Definition: transmission_interface_loader.h:117
transmission_interface::TransmissionInterfaceLoader::loader_data_
TransmissionLoaderData loader_data_
Definition: transmission_interface_loader.h:374
transmission_interface::RequisiteProvider
Definition: transmission_interface_loader.h:128
actuator_command_interface.h
transmission_interface::TransmissionLoaderData::robot_transmissions
RobotTransmissions * robot_transmissions
Lifecycle is externally controlled (ie. hardware abstraction)
Definition: transmission_interface_loader.h:120
transmission_interface::RawJointData::hasAbsolutePosition
bool hasAbsolutePosition
Definition: transmission_interface_loader.h:84
hardware_interface::internal::demangledTypeName
std::string demangledTypeName()
transmission_loader.h
transmission_interface::ForwardTransmissionInterfaces
Definition: transmission_interface_loader.h:101
transmission_interface::ActuatorToJointStateInterface
Definition: transmission_interface.h:417
transmission_interface::RequisiteProvider::TransmissionHandleData
Definition: transmission_interface_loader.h:156
transmission_interface::TransmissionInterfaceLoader::RequisiteProviderClassLoader
pluginlib::ClassLoader< RequisiteProvider > RequisiteProviderClassLoader
Definition: transmission_interface_loader.h:362
transmission_interface::RequisiteProvider::~RequisiteProvider
virtual ~RequisiteProvider()=default
console.h
hardware_interface::VelocityJointInterface
transmission_interface::JointInterfaces::velocity_joint_interface
hardware_interface::VelocityJointInterface velocity_joint_interface
Definition: transmission_interface_loader.h:97
transmission_interface::TransmissionInterfaceLoader::robot_hw_ptr_
hardware_interface::RobotHW * robot_hw_ptr_
Definition: transmission_interface_loader.h:371
transmission_interface::JointData
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
Definition: transmission.h:63
transmission_interface::RawJointDataMap
std::map< std::string, RawJointData > RawJointDataMap
Definition: transmission_interface_loader.h:88
transmission_interface::RawJointData::velocity_cmd
double velocity_cmd
Definition: transmission_interface_loader.h:79
joint_command_interface.h
transmission_interface::RequisiteProvider::getJointStateData
virtual bool getJointStateData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_state_data)=0
hardware_interface::RobotHW
transmission_interface::InverseTransmissionInterfaces::jnt_to_act_state
JointToActuatorStateInterface jnt_to_act_state
Definition: transmission_interface_loader.h:111
transmission_parser.h
Parses <transmission> elements into corresponding structs from XML (URDF).
transmission_interface::TransmissionInterfaceLoader::TransmissionClassLoader
pluginlib::ClassLoader< TransmissionLoader > TransmissionClassLoader
Definition: transmission_interface_loader.h:360
transmission_interface::TransmissionInterfaceLoader::robot_transmissions_ptr_
RobotTransmissions * robot_transmissions_ptr_
Definition: transmission_interface_loader.h:372
ROS_ERROR_STREAM_NAMED
#define ROS_ERROR_STREAM_NAMED(name, args)
transmission_interface::RobotTransmissions
Robot transmissions interface.
Definition: robot_transmissions.h:48
transmission_interface::RequisiteProvider::loadTransmissionMaps
bool loadTransmissionMaps(const TransmissionInfo &transmission_info, TransmissionLoaderData &loader_data, TransmissionSharedPtr transmission)
Definition: transmission_interface_loader.cpp:40
transmission_interface::RawJointData::position_cmd
double position_cmd
Definition: transmission_interface_loader.h:78
hardware_interface::EffortJointInterface
transmission_interface::ActuatorToJointEffortInterface
Definition: transmission_interface.h:426
transmission_interface::TransmissionInterfaceLoader::load
bool load(const std::string &urdf)
Load all transmissions in a URDF.
Definition: transmission_interface_loader.cpp:110
transmission_interface::InverseTransmissionInterfaces::act_to_jnt_pos_cmd
ActuatorToJointPositionInterface act_to_jnt_pos_cmd
Definition: transmission_interface_loader.h:112
transmission.h
transmission_interface::TransmissionLoaderData::raw_joint_data_map
RawJointDataMap raw_joint_data_map
Definition: transmission_interface_loader.h:122
pluginlib::ClassLoader
transmission_interface::TransmissionLoaderData::inverse_transmission_interfaces
InverseTransmissionInterfaces inverse_transmission_interfaces
Definition: transmission_interface_loader.h:124
transmission_interface::RequisiteProvider::getActuatorHandles
bool getActuatorHandles(const std::vector< ActuatorInfo > &actuators_info, hardware_interface::RobotHW *robot_hw, std::vector< Handle > &handles)
Definition: transmission_interface_loader.h:207
class_loader.hpp
transmission_interface::JointInterfaces::joint_state_interface
hardware_interface::JointStateInterface joint_state_interface
Definition: transmission_interface_loader.h:95
transmission_interface::TransmissionInterfaceLoader::RequisiteProviderClassLoaderPtr
std::shared_ptr< RequisiteProviderClassLoader > RequisiteProviderClassLoaderPtr
Definition: transmission_interface_loader.h:363
transmission_interface::TransmissionInterfaceLoader::getData
TransmissionLoaderData * getData()
Definition: transmission_interface_loader.h:357
transmission_interface::TransmissionInterfaceLoader::transmission_class_loader_
TransmissionClassLoaderPtr transmission_class_loader_
Definition: transmission_interface_loader.h:367
transmission_interface::InverseTransmissionInterfaces
Definition: transmission_interface_loader.h:109
transmission_interface::ActuatorToJointPositionInterface
Definition: transmission_interface.h:420
transmission_interface::TransmissionLoaderData::joint_interfaces
JointInterfaces joint_interfaces
Definition: transmission_interface_loader.h:121
transmission_interface::ForwardTransmissionInterfaces::jnt_to_act_pos_cmd
JointToActuatorPositionInterface jnt_to_act_pos_cmd
Definition: transmission_interface_loader.h:104
hardware_interface::HardwareInterfaceException
joint_state_interface.h
transmission_interface::JointToActuatorStateInterface
Definition: transmission_interface.h:429
transmission_interface::RawJointData::effort_cmd
double effort_cmd
Definition: transmission_interface_loader.h:80
transmission_interface.h
transmission_interface::RequisiteProvider::getJointCommandData
virtual bool getJointCommandData(const TransmissionInfo &transmission_info, const RawJointDataMap &raw_joint_data_map, JointData &jnt_cmd_data)=0
transmission_interface::ForwardTransmissionInterfaces::jnt_to_act_eff_cmd
JointToActuatorEffortInterface jnt_to_act_eff_cmd
Definition: transmission_interface_loader.h:106
transmission_interface::RequisiteProvider::TransmissionHandleData::act_state_data
ActuatorData act_state_data
Definition: transmission_interface_loader.h:159
transmission_interface::RequisiteProvider::TransmissionHandleData::transmission
TransmissionSharedPtr transmission
Definition: transmission_interface_loader.h:163
transmission_interface::JointInterfaces::effort_joint_interface
hardware_interface::EffortJointInterface effort_joint_interface
Definition: transmission_interface_loader.h:98
transmission_interface::RequisiteProvider::TransmissionHandleData::jnt_state_data
JointData jnt_state_data
Definition: transmission_interface_loader.h:161
transmission_interface::JointInterfaces::position_joint_interface
hardware_interface::PositionJointInterface position_joint_interface
Definition: transmission_interface_loader.h:96
robot_hw.h
transmission_interface::RequisiteProvider::TransmissionHandleData::act_cmd_data
ActuatorData act_cmd_data
Definition: transmission_interface_loader.h:160
transmission_interface::ActuatorData
Contains pointers to raw data representing the position, velocity and acceleration of a transmission'...
Definition: transmission.h:50
transmission_interface::RawJointData
Raw data for a set of joints.
Definition: transmission_interface_loader.h:73
transmission_interface::TransmissionInterfaceLoader::RequisiteProviderPtr
std::shared_ptr< RequisiteProvider > RequisiteProviderPtr
Definition: transmission_interface_loader.h:365
transmission_interface::JointToActuatorEffortInterface
Definition: transmission_interface.h:438
transmission_interface::ForwardTransmissionInterfaces::jnt_to_act_vel_cmd
JointToActuatorVelocityInterface jnt_to_act_vel_cmd
Definition: transmission_interface_loader.h:105
hardware_interface::PositionJointInterface
transmission_info.h
Structs to hold transmission data loaded straight from XML (URDF).
transmission_interface::TransmissionLoaderData::transmission_interfaces
ForwardTransmissionInterfaces transmission_interfaces
Definition: transmission_interface_loader.h:123
transmission_interface::TransmissionLoaderData::robot_hw
hardware_interface::RobotHW * robot_hw
Lifecycle is externally controlled (ie. hardware abstraction)
Definition: transmission_interface_loader.h:119
transmission_interface::RawJointData::velocity
double velocity
Definition: transmission_interface_loader.h:76
transmission_interface::TransmissionLoaderData::transmission_data
std::vector< TransmissionSharedPtr > transmission_data
Definition: transmission_interface_loader.h:125
transmission_interface::RawJointData::torque_sensor
double torque_sensor
Definition: transmission_interface_loader.h:82
transmission_interface::RequisiteProvider::hasResource
static bool hasResource(const std::string &name, const Interface &iface)
Definition: transmission_interface_loader.h:186
transmission_interface::TransmissionInterfaceLoader
Class for loading transmissions from a URDF description into ros_control interfaces.
Definition: transmission_interface_loader.h:317
transmission_interface::TransmissionInfo
Contains semantic info about a given transmission loaded from XML (URDF)
Definition: transmission_info.h:78
transmission_interface::TransmissionInterfaceLoader::TransmissionInterfaceLoader
TransmissionInterfaceLoader(hardware_interface::RobotHW *robot_hw, RobotTransmissions *robot_transmissions)
Definition: transmission_interface_loader.cpp:89
transmission_interface::RequisiteProvider::registerTransmission
virtual bool registerTransmission(TransmissionLoaderData &loader_data, TransmissionHandleData &handle_data)=0
transmission_interface::RequisiteProvider::getActuatorCommandData
virtual bool getActuatorCommandData(const TransmissionInfo &transmission_info, hardware_interface::RobotHW *robot_hw, ActuatorData &act_cmd_data)=0
transmission_interface::RequisiteProvider::TransmissionHandleData::jnt_cmd_data
JointData jnt_cmd_data
Definition: transmission_interface_loader.h:162
transmission_interface::JointToActuatorPositionInterface
Definition: transmission_interface.h:432


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Tue Oct 15 2024 02:08:29