transmission_interface.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 #ifndef TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_H
31 #define TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_H
32 
33 #include <map>
34 #include <string>
35 #include <vector>
36 
40 
41 namespace transmission_interface
42 {
43 
49 {
50 public:
52  std::string getName() const {return name_;}
53 
54 protected:
55  std::string name_;
59 
70  TransmissionHandle(const std::string& name,
71  Transmission* transmission,
72  const ActuatorData& actuator_data,
73  const JointData& joint_data)
74  : name_(name),
75  transmission_(transmission),
76  actuator_data_(actuator_data),
77  joint_data_(joint_data)
78  {
79  // Precondition: Valid transmission
80  if (!transmission_)
81  {
82  throw TransmissionInterfaceException("Unspecified transmission.");
83  }
84 
85  // Catch trivial error: All data vectors are empty (handle can't do anything without data)
86  if (actuator_data.position.empty() && actuator_data.velocity.empty() && actuator_data.effort.empty() &&
87  joint_data.position.empty() && joint_data.velocity.empty() && joint_data.effort.empty())
88  {
89  throw TransmissionInterfaceException("All data vectors are empty. Transmission instance can't do anything!.");
90  }
91 
92  // Precondition: All non-empty data vectors must have sizes consistent with the transmission
93  if (!actuator_data.position.empty() && actuator_data.position.size() != transmission_->numActuators())
94  {
95  throw TransmissionInterfaceException("Actuator position data size does not match transmission.");
96  }
97  if (!actuator_data.velocity.empty() && actuator_data.velocity.size() != transmission_->numActuators())
98  {
99  throw TransmissionInterfaceException("Actuator velocity data size does not match transmission.");
100  }
101  if (!actuator_data.effort.empty() && actuator_data.effort.size() != transmission_->numActuators())
102  {
103  throw TransmissionInterfaceException("Actuator effort data size does not match transmission.");
104  }
105 
106  if (!joint_data.position.empty() && joint_data.position.size() != transmission_->numJoints())
107  {
108  throw TransmissionInterfaceException("Joint position data size does not match transmission.");
109  }
110  if (!joint_data.velocity.empty() && joint_data.velocity.size() != transmission_->numJoints())
111  {
112  throw TransmissionInterfaceException("Joint velocity data size does not match transmission.");
113  }
114  if (!joint_data.effort.empty() && joint_data.effort.size() != transmission_->numJoints())
115  {
116  throw TransmissionInterfaceException("Joint effort data size does not match transmission.");
117  }
118 
119  // Precondition: Valid pointers to raw data
120  if (!hasValidPointers(actuator_data.position))
121  {
122  throw TransmissionInterfaceException("Actuator position data contains null pointers.");
123  }
124  if (!hasValidPointers(actuator_data.velocity))
125  {
126  throw TransmissionInterfaceException("Actuator velocity data contains null pointers.");
127  }
128  if (!hasValidPointers(actuator_data.effort))
129  {
130  throw TransmissionInterfaceException("Actuator effort data contains null pointers.");
131  }
132 
133  if (!hasValidPointers(joint_data.position))
134  {
135  throw TransmissionInterfaceException("Joint position data contains null pointers.");
136  }
137  if (!hasValidPointers(joint_data.velocity))
138  {
139  throw TransmissionInterfaceException("Joint velocity data contains null pointers.");
140  }
141  if (!hasValidPointers(joint_data.effort))
142  {
143  throw TransmissionInterfaceException("Joint effort data contains null pointers.");
144  }
145  }
146 
147 private:
148  static bool hasValidPointers(const std::vector<double*>& data)
149  {
150  for (std::vector<double*>::const_iterator it = data.begin(); it != data.end(); ++it)
151  {
152  if (!(*it)) {return false;}
153  }
154  return true;
155  }
156 };
157 
162 {
163 public:
165  ActuatorToJointStateHandle(const std::string& name,
166  Transmission* transmission,
167  const ActuatorData& actuator_data,
168  const JointData& joint_data)
169  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
170 
174  void propagate()
175  {
179  }
180  /*\}*/
181 };
182 
183 
186 {
187 public:
189  ActuatorToJointPositionHandle(const std::string& name,
190  Transmission* transmission,
191  const ActuatorData& actuator_data,
192  const JointData& joint_data)
193  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
194 
199  /*\}*/
200 };
201 
202 
205 {
206 public:
208  ActuatorToJointVelocityHandle(const std::string& name,
209  Transmission* transmission,
210  const ActuatorData& actuator_data,
211  const JointData& joint_data)
212  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
213 
218  /*\}*/
219 };
220 
221 
224 {
225 public:
227  ActuatorToJointEffortHandle(const std::string& name,
228  Transmission* transmission,
229  const ActuatorData& actuator_data,
230  const JointData& joint_data)
231  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
232 
237  /*\}*/
238 };
239 
240 
245 {
246 public:
248  JointToActuatorStateHandle(const std::string& name,
249  Transmission* transmission,
250  const ActuatorData& actuator_data,
251  const JointData& joint_data)
252  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
253 
257  void propagate()
258  {
262  }
263  /*\}*/
264 };
265 
266 
269 {
270 public:
272  JointToActuatorPositionHandle(const std::string& name,
273  Transmission* transmission,
274  const ActuatorData& actuator_data,
275  const JointData& joint_data)
276  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
277 
282  /*\}*/
283 };
284 
285 
288 {
289 public:
291  JointToActuatorVelocityHandle(const std::string& name,
292  Transmission* transmission,
293  const ActuatorData& actuator_data,
294  const JointData& joint_data)
295  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
296 
301  /*\}*/
302 };
303 
304 
307 {
308 public:
310  JointToActuatorEffortHandle(const std::string& name,
311  Transmission* transmission,
312  const ActuatorData& actuator_data,
313  const JointData& joint_data)
314  : TransmissionHandle(name, transmission, actuator_data, joint_data) {}
315 
320  /*\}*/
321 };
322 
340 template <class HandleType>
342 {
343 public:
344 
345  HandleType getHandle(const std::string& name)
346  {
347  // Rethrow exception with a meaningful type
348  try
349  {
351  }
352  catch(const std::logic_error& e)
353  {
354  throw TransmissionInterfaceException(e.what());
355  }
356  }
357 
361  void propagate()
362  {
364  for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it)
365  {
366  it->second.propagate();
367  }
368  }
369  /*\}*/
370 };
371 
372 // Convenience typedefs
373 
375 class ActuatorToJointStateInterface : public TransmissionInterface<ActuatorToJointStateHandle> {};
376 
378 class ActuatorToJointPositionInterface : public TransmissionInterface<ActuatorToJointPositionHandle> {};
379 
381 class ActuatorToJointVelocityInterface : public TransmissionInterface<ActuatorToJointVelocityHandle> {};
382 
384 class ActuatorToJointEffortInterface : public TransmissionInterface<ActuatorToJointEffortHandle> {};
385 
387 class JointToActuatorStateInterface : public TransmissionInterface<JointToActuatorStateHandle> {};
388 
390 class JointToActuatorPositionInterface : public TransmissionInterface<JointToActuatorPositionHandle> {};
391 
393 class JointToActuatorVelocityInterface : public TransmissionInterface<JointToActuatorVelocityHandle> {};
394 
396 class JointToActuatorEffortInterface : public TransmissionInterface<JointToActuatorEffortHandle> {};
397 
398 } // transmission_interface
399 
400 #endif // TRANSMISSION_INTERFACE_TRANSMISSION_INTERFACE_H
virtual void jointToActuatorVelocity(const JointData &jnt_data, ActuatorData &act_data)=0
Transform velocity variables from joint to actuator space.
ActuatorToJointEffortHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
void propagate()
Propagate joint velocities to actuator velocities for the stored transmission.
Handle for propagating actuator efforts to joint efforts for a given transmission.
virtual std::size_t numJoints() const =0
std::vector< double * > velocity
Definition: transmission.h:64
virtual void actuatorToJointPosition(const ActuatorData &act_data, JointData &jnt_data)=0
Transform position variables from actuator to joint space.
static bool hasValidPointers(const std::vector< double * > &data)
void propagate()
Propagate the transmission maps of all managed handles.
Interface for propagating a given map on a set of transmissions.
ActuatorToJointStateHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
Contains pointers to raw data representing the position, velocity and acceleration of a transmission&#39;...
Definition: transmission.h:61
std::vector< double * > position
Definition: transmission.h:52
virtual void actuatorToJointEffort(const ActuatorData &act_data, JointData &jnt_data)=0
Transform effort variables from actuator to joint space.
Handle for propagating actuator positions to joint positions for a given transmission.
void propagate()
Propagate actuator positions to joint positions for the stored transmission.
JointToActuatorStateHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
TransmissionHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
JointToActuatorVelocityHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
void propagate()
Propagate actuator efforts to joint efforts for the stored transmission.
ActuatorToJointPositionHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
Handle for propagating actuator velocities to joint velocities for a given transmission.
JointToActuatorEffortHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
ResourceHandle getHandle(const std::string &name)
Handle for propagating actuator state (position, velocity and effort) to joint state for a given tran...
Handle for propagating joint efforts to actuator efforts for a given transmission.
Handle for propagating joint velocities to actuator velocities for a given transmission.
void propagate()
Propagate joint efforts to actuator efforts for the stored transmission.
Contains pointers to raw data representing the position, velocity and acceleration of a transmission&#39;...
Definition: transmission.h:50
virtual void jointToActuatorPosition(const JointData &jnt_data, ActuatorData &act_data)=0
Transform position variables from joint to actuator space.
void propagate()
Propagate actuator velocities to joint velocities for the stored transmission.
std::vector< double * > velocity
Definition: transmission.h:53
ActuatorToJointVelocityHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
std::vector< double * > position
Definition: transmission.h:63
virtual void jointToActuatorEffort(const JointData &jnt_data, ActuatorData &act_data)=0
Transform effort variables from joint to actuator space.
JointToActuatorPositionHandle(const std::string &name, Transmission *transmission, const ActuatorData &actuator_data, const JointData &joint_data)
std::vector< double * > effort
Definition: transmission.h:65
void propagate()
Propagate joint positions to actuator positions for the stored transmission.
virtual std::size_t numActuators() const =0
Handle for propagating a single map (position, velocity, or effort) on a single transmission (eg...
std::vector< double * > effort
Definition: transmission.h:54
virtual void actuatorToJointVelocity(const ActuatorData &act_data, JointData &jnt_data)=0
Transform velocity variables from actuator to joint space.
void propagate()
Propagate joint state to actuator state for the stored transmission.
Handle for propagating joint positions to actuator positions for a given transmission.
Abstract base class for representing mechanical transmissions.
Definition: transmission.h:87
Handle for propagating joint state (position, velocity and effort) to actuator state for a given tran...
HandleType getHandle(const std::string &name)
void propagate()
Propagate actuator state to joint state for the stored transmission.


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Fri Jun 7 2019 22:00:17