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_H
00031 #define TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_H
00032
00033 #include <map>
00034 #include <string>
00035 #include <vector>
00036
00037 #include <hardware_interface/internal/resource_manager.h>
00038 #include <transmission_interface/transmission.h>
00039 #include <transmission_interface/transmission_interface_exception.h>
00040
00041 namespace transmission_interface
00042 {
00043
00048 class TransmissionHandle
00049 {
00050 public:
00052 std::string getName() const {return name_;}
00053
00054 protected:
00055 std::string name_;
00056 Transmission* transmission_;
00057 ActuatorData actuator_data_;
00058 JointData joint_data_;
00059
00070 TransmissionHandle(const std::string& name,
00071 Transmission* transmission,
00072 const ActuatorData& actuator_data,
00073 const JointData& joint_data)
00074 : name_(name),
00075 transmission_(transmission),
00076 actuator_data_(actuator_data),
00077 joint_data_(joint_data)
00078 {
00079
00080 if (!transmission_)
00081 {
00082 throw TransmissionInterfaceException("Unspecified transmission.");
00083 }
00084
00085
00086 if (actuator_data.position.empty() && actuator_data.velocity.empty() && actuator_data.effort.empty() &&
00087 joint_data.position.empty() && joint_data.velocity.empty() && joint_data.effort.empty())
00088 {
00089 throw TransmissionInterfaceException("All data vectors are empty. Transmission instance can't do anything!.");
00090 }
00091
00092
00093 if (!actuator_data.position.empty() && actuator_data.position.size() != transmission_->numActuators())
00094 {
00095 throw TransmissionInterfaceException("Actuator position data size does not match transmission.");
00096 }
00097 if (!actuator_data.velocity.empty() && actuator_data.velocity.size() != transmission_->numActuators())
00098 {
00099 throw TransmissionInterfaceException("Actuator velocity data size does not match transmission.");
00100 }
00101 if (!actuator_data.effort.empty() && actuator_data.effort.size() != transmission_->numActuators())
00102 {
00103 throw TransmissionInterfaceException("Actuator effort data size does not match transmission.");
00104 }
00105
00106 if (!joint_data.position.empty() && joint_data.position.size() != transmission_->numJoints())
00107 {
00108 throw TransmissionInterfaceException("Joint position data size does not match transmission.");
00109 }
00110 if (!joint_data.velocity.empty() && joint_data.velocity.size() != transmission_->numJoints())
00111 {
00112 throw TransmissionInterfaceException("Joint velocity data size does not match transmission.");
00113 }
00114 if (!joint_data.effort.empty() && joint_data.effort.size() != transmission_->numJoints())
00115 {
00116 throw TransmissionInterfaceException("Joint effort data size does not match transmission.");
00117 }
00118
00119
00120 if (!hasValidPointers(actuator_data.position))
00121 {
00122 throw TransmissionInterfaceException("Actuator position data contains null pointers.");
00123 }
00124 if (!hasValidPointers(actuator_data.velocity))
00125 {
00126 throw TransmissionInterfaceException("Actuator velocity data contains null pointers.");
00127 }
00128 if (!hasValidPointers(actuator_data.effort))
00129 {
00130 throw TransmissionInterfaceException("Actuator effort data contains null pointers.");
00131 }
00132
00133 if (!hasValidPointers(joint_data.position))
00134 {
00135 throw TransmissionInterfaceException("Joint position data contains null pointers.");
00136 }
00137 if (!hasValidPointers(joint_data.velocity))
00138 {
00139 throw TransmissionInterfaceException("Joint velocity data contains null pointers.");
00140 }
00141 if (!hasValidPointers(joint_data.effort))
00142 {
00143 throw TransmissionInterfaceException("Joint effort data contains null pointers.");
00144 }
00145 }
00146
00147 private:
00148 static bool hasValidPointers(const std::vector<double*>& data)
00149 {
00150 for (std::vector<double*>::const_iterator it = data.begin(); it != data.end(); ++it)
00151 {
00152 if (!(*it)) {return false;}
00153 }
00154 return true;
00155 }
00156 };
00157
00161 class ActuatorToJointStateHandle : public TransmissionHandle
00162 {
00163 public:
00165 ActuatorToJointStateHandle(const std::string& name,
00166 Transmission* transmission,
00167 const ActuatorData& actuator_data,
00168 const JointData& joint_data)
00169 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00170
00174 void propagate()
00175 {
00176 transmission_->actuatorToJointPosition(actuator_data_, joint_data_);
00177 transmission_->actuatorToJointVelocity(actuator_data_, joint_data_);
00178 transmission_->actuatorToJointEffort( actuator_data_, joint_data_);
00179 }
00180
00181 };
00182
00183
00185 class ActuatorToJointPositionHandle : public TransmissionHandle
00186 {
00187 public:
00189 ActuatorToJointPositionHandle(const std::string& name,
00190 Transmission* transmission,
00191 const ActuatorData& actuator_data,
00192 const JointData& joint_data)
00193 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00194
00198 void propagate() {transmission_->actuatorToJointPosition(actuator_data_, joint_data_);}
00199
00200 };
00201
00202
00204 class ActuatorToJointVelocityHandle : public TransmissionHandle
00205 {
00206 public:
00208 ActuatorToJointVelocityHandle(const std::string& name,
00209 Transmission* transmission,
00210 const ActuatorData& actuator_data,
00211 const JointData& joint_data)
00212 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00213
00217 void propagate() {transmission_->actuatorToJointVelocity(actuator_data_, joint_data_);}
00218
00219 };
00220
00221
00223 class ActuatorToJointEffortHandle : public TransmissionHandle
00224 {
00225 public:
00227 ActuatorToJointEffortHandle(const std::string& name,
00228 Transmission* transmission,
00229 const ActuatorData& actuator_data,
00230 const JointData& joint_data)
00231 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00232
00236 void propagate() {transmission_->actuatorToJointEffort(actuator_data_, joint_data_);}
00237
00238 };
00239
00240
00244 class JointToActuatorStateHandle : public TransmissionHandle
00245 {
00246 public:
00248 JointToActuatorStateHandle(const std::string& name,
00249 Transmission* transmission,
00250 const ActuatorData& actuator_data,
00251 const JointData& joint_data)
00252 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00253
00257 void propagate()
00258 {
00259 transmission_->jointToActuatorPosition(joint_data_, actuator_data_);
00260 transmission_->jointToActuatorVelocity(joint_data_, actuator_data_);
00261 transmission_->jointToActuatorEffort( joint_data_, actuator_data_);
00262 }
00263
00264 };
00265
00266
00268 class JointToActuatorPositionHandle : public TransmissionHandle
00269 {
00270 public:
00272 JointToActuatorPositionHandle(const std::string& name,
00273 Transmission* transmission,
00274 const ActuatorData& actuator_data,
00275 const JointData& joint_data)
00276 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00277
00281 void propagate() {transmission_->jointToActuatorPosition(joint_data_, actuator_data_);}
00282
00283 };
00284
00285
00287 class JointToActuatorVelocityHandle : public TransmissionHandle
00288 {
00289 public:
00291 JointToActuatorVelocityHandle(const std::string& name,
00292 Transmission* transmission,
00293 const ActuatorData& actuator_data,
00294 const JointData& joint_data)
00295 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00296
00300 void propagate() {transmission_->jointToActuatorVelocity(joint_data_, actuator_data_);}
00301
00302 };
00303
00304
00306 class JointToActuatorEffortHandle : public TransmissionHandle
00307 {
00308 public:
00310 JointToActuatorEffortHandle(const std::string& name,
00311 Transmission* transmission,
00312 const ActuatorData& actuator_data,
00313 const JointData& joint_data)
00314 : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
00315
00319 void propagate() {transmission_->jointToActuatorEffort(joint_data_, actuator_data_);}
00320
00321 };
00322
00340 template <class HandleType>
00341 class TransmissionInterface : public hardware_interface::ResourceManager<HandleType>
00342 {
00343 public:
00344
00345 HandleType getHandle(const std::string& name)
00346 {
00347
00348 try
00349 {
00350 return this->hardware_interface::ResourceManager<HandleType>::getHandle(name);
00351 }
00352 catch(const std::logic_error& e)
00353 {
00354 throw TransmissionInterfaceException(e.what());
00355 }
00356 }
00357
00361 void propagate()
00362 {
00363 typedef typename hardware_interface::ResourceManager<HandleType>::ResourceMap::iterator ItratorType;
00364 for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it)
00365 {
00366 it->second.propagate();
00367 }
00368 }
00369
00370 };
00371
00372
00373
00375 class ActuatorToJointStateInterface : public TransmissionInterface<ActuatorToJointStateHandle> {};
00376
00378 class ActuatorToJointPositionInterface : public TransmissionInterface<ActuatorToJointPositionHandle> {};
00379
00381 class ActuatorToJointVelocityInterface : public TransmissionInterface<ActuatorToJointVelocityHandle> {};
00382
00384 class ActuatorToJointEffortInterface : public TransmissionInterface<ActuatorToJointEffortHandle> {};
00385
00387 class JointToActuatorStateInterface : public TransmissionInterface<JointToActuatorStateHandle> {};
00388
00390 class JointToActuatorPositionInterface : public TransmissionInterface<JointToActuatorPositionHandle> {};
00391
00393 class JointToActuatorVelocityInterface : public TransmissionInterface<JointToActuatorVelocityHandle> {};
00394
00396 class JointToActuatorEffortInterface : public TransmissionInterface<JointToActuatorEffortHandle> {};
00397
00398 }
00399
00400 #endif // TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_H