00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00029
00030 #ifndef TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_LOADER_H
00031 #define TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_LOADER_H
00032
00033
00034 #include <algorithm>
00035 #include <limits>
00036 #include <map>
00037 #include <string>
00038 #include <utility>
00039 #include <vector>
00040
00041
00042 #include <boost/foreach.hpp>
00043 #include <boost/shared_ptr.hpp>
00044
00045
00046 #include <ros/console.h>
00047
00048
00049 #include <pluginlib/class_loader.h>
00050
00051
00052 #include <hardware_interface/actuator_state_interface.h>
00053 #include <hardware_interface/actuator_command_interface.h>
00054 #include <hardware_interface/internal/demangle_symbol.h>
00055 #include <hardware_interface/joint_state_interface.h>
00056 #include <hardware_interface/joint_command_interface.h>
00057 #include <hardware_interface/robot_hw.h>
00058
00059 #include <transmission_interface/robot_transmissions.h>
00060 #include <transmission_interface/transmission.h>
00061 #include <transmission_interface/transmission_interface.h>
00062 #include <transmission_interface/transmission_info.h>
00063 #include <transmission_interface/transmission_loader.h>
00064 #include <transmission_interface/transmission_parser.h>
00065
00066 namespace transmission_interface
00067 {
00068
00069 namespace internal
00070 {
00071
00072
00073 template<class ForwardIt1, class ForwardIt2>
00074 bool is_permutation(ForwardIt1 first, ForwardIt1 last,
00075 ForwardIt2 d_first)
00076 {
00077
00078 std::pair<ForwardIt1, ForwardIt2> pair = std::mismatch(first, last, d_first);
00079 first = pair.first; d_first = pair.second;
00080
00081
00082
00083 if (first != last) {
00084 ForwardIt2 d_last = d_first;
00085 std::advance(d_last, std::distance(first, last));
00086 for (ForwardIt1 i = first; i != last; ++i) {
00087 if (i != std::find(first, i, *i)) continue;
00088
00089 int m = std::count(d_first, d_last, *i);
00090 if (m==0 || std::count(i, last, *i) != m) {
00091 return false;
00092 }
00093 }
00094 }
00095 return true;
00096 }
00097
00098 }
00099
00100
00107
00108 struct RawJointData
00109 {
00110 RawJointData()
00111 : position(std::numeric_limits<double>::quiet_NaN()),
00112 velocity(std::numeric_limits<double>::quiet_NaN()),
00113 effort(std::numeric_limits<double>::quiet_NaN()),
00114 position_cmd(std::numeric_limits<double>::quiet_NaN()),
00115 velocity_cmd(std::numeric_limits<double>::quiet_NaN()),
00116 effort_cmd(std::numeric_limits<double>::quiet_NaN())
00117 {}
00118
00119 double position;
00120 double velocity;
00121 double effort;
00122 double position_cmd;
00123 double velocity_cmd;
00124 double effort_cmd;
00125 };
00126
00127 typedef std::map<std::string, RawJointData> RawJointDataMap;
00128
00132 struct JointInterfaces
00133 {
00134 hardware_interface::JointStateInterface joint_state_interface;
00135 hardware_interface::PositionJointInterface position_joint_interface;
00136 hardware_interface::VelocityJointInterface velocity_joint_interface;
00137 hardware_interface::EffortJointInterface effort_joint_interface;
00138 };
00139
00140 struct ForwardTransmissionInterfaces
00141 {
00142 ActuatorToJointStateInterface act_to_jnt_state;
00143 JointToActuatorPositionInterface jnt_to_act_pos_cmd;
00144 JointToActuatorVelocityInterface jnt_to_act_vel_cmd;
00145 JointToActuatorEffortInterface jnt_to_act_eff_cmd;
00146 };
00147
00148 struct TransmissionLoaderData
00149 {
00150 typedef boost::shared_ptr<Transmission> TransmissionPtr;
00151
00152 TransmissionLoaderData()
00153 : robot_hw(0),
00154 robot_transmissions(0)
00155 {}
00156
00157 hardware_interface::RobotHW* robot_hw;
00158 RobotTransmissions* robot_transmissions;
00159 JointInterfaces joint_interfaces;
00160 RawJointDataMap raw_joint_data_map;
00161 ForwardTransmissionInterfaces transmission_interfaces;
00162 std::vector<TransmissionSharedPtr> transmission_data;
00163 };
00164
00165 class RequisiteProvider
00166 {
00167 public:
00168
00169 virtual ~RequisiteProvider() {}
00170
00185 virtual bool updateJointInterfaces(const TransmissionInfo& transmission_info,
00186 hardware_interface::RobotHW* robot_hw,
00187 JointInterfaces& joint_interfaces,
00188 RawJointDataMap& raw_joint_data_map) = 0;
00189
00190 bool loadTransmissionMaps(const TransmissionInfo& transmission_info,
00191 TransmissionLoaderData& loader_data,
00192 TransmissionSharedPtr transmission);
00193 protected:
00194 struct TransmissionHandleData
00195 {
00196 std::string name;
00197 ActuatorData act_state_data;
00198 ActuatorData act_cmd_data;
00199 JointData jnt_state_data;
00200 JointData jnt_cmd_data;
00201 TransmissionSharedPtr transmission;
00202 };
00203
00204 virtual bool getJointStateData(const TransmissionInfo& transmission_info,
00205 const RawJointDataMap& raw_joint_data_map,
00206 JointData& jnt_state_data) = 0;
00207
00208 virtual bool getJointCommandData(const TransmissionInfo& transmission_info,
00209 const RawJointDataMap& raw_joint_data_map,
00210 JointData& jnt_cmd_data) = 0;
00211
00212 virtual bool getActuatorStateData(const TransmissionInfo& transmission_info,
00213 hardware_interface::RobotHW* robot_hw,
00214 ActuatorData& act_state_data) = 0;
00215
00216 virtual bool getActuatorCommandData(const TransmissionInfo& transmission_info,
00217 hardware_interface::RobotHW* robot_hw,
00218 ActuatorData& act_cmd_data) = 0;
00219
00220 virtual bool registerTransmission(TransmissionLoaderData& loader_data,
00221 TransmissionHandleData& handle_data) = 0;
00222
00223 template <class Interface>
00224 static bool hasResource(const std::string& name, const Interface& iface)
00225 {
00226 using hardware_interface::internal::demangledTypeName;
00227
00228
00229 const std::vector<std::string>& existing_resources = iface.getNames();
00230 if (existing_resources.end() != std::find(existing_resources.begin(), existing_resources.end(), name))
00231 {
00232 ROS_DEBUG_STREAM_NAMED("parser", "Resource '" << name << "' already exists on interface '" <<
00233 demangledTypeName<Interface>());
00234 return true;
00235 }
00236 else
00237 {
00238 ROS_DEBUG_STREAM_NAMED("parser", "Resource '" << name << "' does not exist on interface '" <<
00239 demangledTypeName<Interface>());
00240 return false;
00241 }
00242 }
00243
00244 template <class HardwareInterface, class Handle>
00245 bool getActuatorHandles(const std::vector<ActuatorInfo>& actuators_info,
00246 hardware_interface::RobotHW* robot_hw,
00247 std::vector<Handle>& handles)
00248 {
00249 using hardware_interface::RobotHW;
00250 using hardware_interface::HardwareInterfaceException;
00251 using hardware_interface::internal::demangledTypeName;
00252
00253 HardwareInterface* hw_iface = robot_hw->get<HardwareInterface>();
00254
00255
00256 if (!hw_iface)
00257 {
00258 ROS_ERROR_STREAM_NAMED("parser", "Robot does not have the required hardware interface '" <<
00259 demangledTypeName<HardwareInterface>() << "'.");
00260 return false;
00261 }
00262
00263
00264 BOOST_FOREACH(const ActuatorInfo& info, actuators_info)
00265 {
00266 try
00267 {
00268 handles.push_back(hw_iface->getHandle(info.name_));
00269 }
00270 catch(const HardwareInterfaceException& ex)
00271 {
00272 ROS_ERROR_STREAM_NAMED("parser", "Actuator '" << info.name_ <<
00273 "' does not expose the required hardware interface '" <<
00274 demangledTypeName<HardwareInterface>() << "'.");
00275 return false;
00276 }
00277 }
00278 return true;
00279 }
00280 };
00281
00355 class TransmissionInterfaceLoader
00356 {
00357 public:
00362 TransmissionInterfaceLoader(hardware_interface::RobotHW* robot_hw,
00363 RobotTransmissions* robot_transmissions);
00364
00373 bool load(const std::string& urdf);
00374
00383 bool load(const std::vector<TransmissionInfo>& transmission_info_vec);
00384
00393 bool load(const TransmissionInfo& transmission_info);
00394
00395 TransmissionLoaderData* getData() {return &loader_data_;}
00396
00397 private:
00398 typedef pluginlib::ClassLoader<TransmissionLoader> TransmissionClassLoader;
00399 typedef boost::shared_ptr<TransmissionClassLoader> TransmissionClassLoaderPtr;
00400 typedef pluginlib::ClassLoader<RequisiteProvider> RequisiteProviderClassLoader;
00401 typedef boost::shared_ptr<RequisiteProviderClassLoader> RequisiteProviderClassLoaderPtr;
00402
00403 typedef boost::shared_ptr<RequisiteProvider> RequisiteProviderPtr;
00404
00405 TransmissionClassLoaderPtr transmission_class_loader_;
00406 RequisiteProviderClassLoaderPtr req_provider_loader_;
00407
00408 private:
00409 hardware_interface::RobotHW* robot_hw_ptr_;
00410 RobotTransmissions* robot_transmissions_ptr_;
00411
00412 TransmissionLoaderData loader_data_;
00413 };
00414
00415 }
00416
00417 #endif // header guard