simple_transmission.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_SIMPLE_TRANSMISSION_H
31 #define TRANSMISSION_INTERFACE_SIMPLE_TRANSMISSION_H
32 
33 #include <cassert>
34 #include <string>
35 #include <vector>
36 
39 
40 namespace transmission_interface
41 {
42 
96 {
97 public:
103  SimpleTransmission(const double reduction,
104  const double joint_offset = 0.0);
105 
113  void actuatorToJointEffort(const ActuatorData& act_data,
114  JointData& jnt_data);
115 
123  void actuatorToJointVelocity(const ActuatorData& act_data,
124  JointData& jnt_data);
125 
133  void actuatorToJointPosition(const ActuatorData& act_data,
134  JointData& jnt_data);
135 
143  void jointToActuatorEffort(const JointData& jnt_data,
144  ActuatorData& act_data);
145 
153  void jointToActuatorVelocity(const JointData& jnt_data,
154  ActuatorData& act_data);
155 
163  void jointToActuatorPosition(const JointData& jnt_data,
164  ActuatorData& act_data);
165 
166  std::size_t numActuators() const {return 1;}
167  std::size_t numJoints() const {return 1;}
168 
169  double getActuatorReduction() const {return reduction_;}
170  double getJointOffset() const {return jnt_offset_;}
171 
172 private:
173  double reduction_;
174  double jnt_offset_;
175 };
176 
177 inline SimpleTransmission::SimpleTransmission(const double reduction,
178  const double joint_offset)
179  : Transmission(),
180  reduction_(reduction),
181  jnt_offset_(joint_offset)
182 {
183  if (0.0 == reduction_)
184  {
185  throw TransmissionInterfaceException("Transmission reduction ratio cannot be zero.");
186  }
187 }
188 
190  JointData& jnt_data)
191 {
192  assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
193  assert(act_data.effort[0] && jnt_data.effort[0]);
194 
195  *jnt_data.effort[0] = *act_data.effort[0] * reduction_;
196 }
197 
199  JointData& jnt_data)
200 {
201  assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
202  assert(act_data.velocity[0] && jnt_data.velocity[0]);
203 
204  *jnt_data.velocity[0] = *act_data.velocity[0] / reduction_;
205 }
206 
208  JointData& jnt_data)
209 {
210  assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
211  assert(act_data.position[0] && jnt_data.position[0]);
212 
213  *jnt_data.position[0] = *act_data.position[0] / reduction_ + jnt_offset_;
214 }
215 
217  ActuatorData& act_data)
218 {
219  assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
220  assert(act_data.effort[0] && jnt_data.effort[0]);
221 
222  *act_data.effort[0] = *jnt_data.effort[0] / reduction_;
223 }
224 
226  ActuatorData& act_data)
227 {
228  assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
229  assert(act_data.velocity[0] && jnt_data.velocity[0]);
230 
231  *act_data.velocity[0] = *jnt_data.velocity[0] * reduction_;
232 }
233 
235  ActuatorData& act_data)
236 {
237  assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
238  assert(act_data.position[0] && jnt_data.position[0]);
239 
240  *act_data.position[0] = (*jnt_data.position[0] - jnt_offset_) * reduction_;
241 }
242 
243 } // transmission_interface
244 
245 #endif // TRANSMISSION_INTERFACE_SIMPLE_TRANSMISSION_H
std::vector< double * > velocity
Definition: transmission.h:64
Contains pointers to raw data representing the position, velocity and acceleration of a transmission&#39;...
Definition: transmission.h:61
void actuatorToJointVelocity(const ActuatorData &act_data, JointData &jnt_data)
Transform velocity variables from actuator to joint space.
std::vector< double * > position
Definition: transmission.h:52
void jointToActuatorPosition(const JointData &jnt_data, ActuatorData &act_data)
Transform position variables from joint to actuator space.
void actuatorToJointEffort(const ActuatorData &act_data, JointData &jnt_data)
Transform effort variables from actuator to joint space.
void jointToActuatorEffort(const JointData &jnt_data, ActuatorData &act_data)
Transform effort variables from joint to actuator space.
Contains pointers to raw data representing the position, velocity and acceleration of a transmission&#39;...
Definition: transmission.h:50
Implementation of a simple reducer transmission.
std::vector< double * > velocity
Definition: transmission.h:53
std::vector< double * > position
Definition: transmission.h:63
void jointToActuatorVelocity(const JointData &jnt_data, ActuatorData &act_data)
Transform velocity variables from joint to actuator space.
std::vector< double * > effort
Definition: transmission.h:65
void actuatorToJointPosition(const ActuatorData &act_data, JointData &jnt_data)
Transform position variables from actuator to joint space.
std::vector< double * > effort
Definition: transmission.h:54
SimpleTransmission(const double reduction, const double joint_offset=0.0)
Abstract base class for representing mechanical transmissions.
Definition: transmission.h:87


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