four_bar_linkage_transmission.h
Go to the documentation of this file.
1 
3 // Copyright (C) 2013, PAL Robotics S.L.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
7 // * Redistributions of source code must retain the above copyright notice,
8 // this list of conditions and the following disclaimer.
9 // * Redistributions in binary form must reproduce the above copyright
10 // notice, this list of conditions and the following disclaimer in the
11 // documentation and/or other materials provided with the distribution.
12 // * Neither the name of PAL Robotics S.L. nor the names of its
13 // contributors may be used to endorse or promote products derived from
14 // this software without specific prior written permission.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 // POSSIBILITY OF SUCH DAMAGE.
28 
30 
31 #ifndef TRANSMISSION_INTERFACE_FOUR_BAR_LINKAGE_TRANSMISSION_H
32 #define TRANSMISSION_INTERFACE_FOUR_BAR_LINKAGE_TRANSMISSION_H
33 
34 #include <cassert>
35 #include <string>
36 #include <vector>
37 
40 
41 namespace transmission_interface
42 {
43 
118 {
119 public:
126  FourBarLinkageTransmission(const std::vector<double>& actuator_reduction,
127  const std::vector<double>& joint_reduction,
128  const std::vector<double>& joint_offset = std::vector<double>(2, 0.0));
129 
137  void actuatorToJointEffort(const ActuatorData& act_data,
138  JointData& jnt_data);
139 
147  void actuatorToJointVelocity(const ActuatorData& act_data,
148  JointData& jnt_data);
149 
157  void actuatorToJointPosition(const ActuatorData& act_data,
158  JointData& jnt_data);
159 
167  void jointToActuatorEffort(const JointData& jnt_data,
168  ActuatorData& act_data);
169 
177  void jointToActuatorVelocity(const JointData& jnt_data,
178  ActuatorData& act_data);
179 
187  void jointToActuatorPosition(const JointData& jnt_data,
188  ActuatorData& act_data);
189 
190  std::size_t numActuators() const {return 2;}
191  std::size_t numJoints() const {return 2;}
192 
193  const std::vector<double>& getActuatorReduction() const {return act_reduction_;}
194  const std::vector<double>& getJointReduction() const {return jnt_reduction_;}
195  const std::vector<double>& getJointOffset() const {return jnt_offset_;}
196 
197 protected:
198  std::vector<double> act_reduction_;
199  std::vector<double> jnt_reduction_;
200  std::vector<double> jnt_offset_;
201 };
202 
203 inline FourBarLinkageTransmission::FourBarLinkageTransmission(const std::vector<double>& actuator_reduction,
204  const std::vector<double>& joint_reduction,
205  const std::vector<double>& joint_offset)
206  : Transmission(),
207  act_reduction_(actuator_reduction),
208  jnt_reduction_(joint_reduction),
209  jnt_offset_(joint_offset)
210 {
211  if (numActuators() != act_reduction_.size() ||
212  numJoints() != jnt_reduction_.size() ||
213  numJoints() != jnt_offset_.size())
214  {
215  throw TransmissionInterfaceException("Reduction and offset vectors of a four-bar linkage transmission must have size 2.");
216  }
217  if (0.0 == act_reduction_[0] ||
218  0.0 == act_reduction_[1] ||
219  0.0 == jnt_reduction_[0] ||
220  0.0 == jnt_reduction_[1])
221  {
222  throw TransmissionInterfaceException("Transmission reduction ratios cannot be zero.");
223  }
224 }
225 
227  JointData& jnt_data)
228 {
229  assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
230  assert(act_data.effort[0] && act_data.effort[1] && jnt_data.effort[0] && jnt_data.effort[1]);
231 
232  std::vector<double>& ar = act_reduction_;
233  std::vector<double>& jr = jnt_reduction_;
234 
235  *jnt_data.effort[0] = jr[0] * (*act_data.effort[0] * ar[0]);
236  *jnt_data.effort[1] = jr[1] * (*act_data.effort[1] * ar[1] - *act_data.effort[0] * ar[0] * jr[0]);
237 }
238 
240  JointData& jnt_data)
241 {
242  assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
243  assert(act_data.velocity[0] && act_data.velocity[1] && jnt_data.velocity[0] && jnt_data.velocity[1]);
244 
245  std::vector<double>& ar = act_reduction_;
246  std::vector<double>& jr = jnt_reduction_;
247 
248  *jnt_data.velocity[0] = *act_data.velocity[0] / (jr[0] * ar[0]);
249  *jnt_data.velocity[1] = (*act_data.velocity[1] / ar[1] - *act_data.velocity[0] / (jr[0] * ar[0])) / jr[1];
250 }
251 
253  JointData& jnt_data)
254 {
255  assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
256  assert(act_data.position[0] && act_data.position[1] && jnt_data.position[0] && jnt_data.position[1]);
257 
258  std::vector<double>& ar = act_reduction_;
259  std::vector<double>& jr = jnt_reduction_;
260 
261  *jnt_data.position[0] = *act_data.position[0] /(jr[0] * ar[0]) + jnt_offset_[0];
262  *jnt_data.position[1] = (*act_data.position[1] / ar[1] - *act_data.position[0] / (jr[0] * ar[0])) / jr[1]
263  + jnt_offset_[1];
264 }
265 
267  ActuatorData& act_data)
268 {
269  assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
270  assert(act_data.effort[0] && act_data.effort[1] && jnt_data.effort[0] && jnt_data.effort[1]);
271 
272  std::vector<double>& ar = act_reduction_;
273  std::vector<double>& jr = jnt_reduction_;
274 
275  *act_data.effort[0] = *jnt_data.effort[0] / (ar[0] * jr[0]);
276  *act_data.effort[1] = (*jnt_data.effort[0] + *jnt_data.effort[1] / jr[1]) / ar[1];
277 }
278 
280  ActuatorData& act_data)
281 {
282  assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
283  assert(act_data.velocity[0] && act_data.velocity[1] && jnt_data.velocity[0] && jnt_data.velocity[1]);
284 
285  std::vector<double>& ar = act_reduction_;
286  std::vector<double>& jr = jnt_reduction_;
287 
288  *act_data.velocity[0] = *jnt_data.velocity[0] * jr[0] * ar[0];
289  *act_data.velocity[1] = (*jnt_data.velocity[0] + *jnt_data.velocity[1] * jr[1]) * ar[1];
290 }
291 
293  ActuatorData& act_data)
294 {
295  assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
296  assert(act_data.position[0] && act_data.position[1] && jnt_data.position[0] && jnt_data.position[1]);
297 
298  std::vector<double>& ar = act_reduction_;
299  std::vector<double>& jr = jnt_reduction_;
300 
301  double jnt_pos_off[2] = {*jnt_data.position[0] - jnt_offset_[0], *jnt_data.position[1] - jnt_offset_[1]};
302 
303  *act_data.position[0] = jnt_pos_off[0] * jr[0] * ar[0];
304  *act_data.position[1] = (jnt_pos_off[0] + jnt_pos_off[1] * jr[1]) * ar[1];
305 }
306 
307 } // transmission_interface
308 
309 #endif // TRANSMISSION_INTERFACE_FOUR_BAR_LINKAGE_TRANSMISSION_H
std::vector< double * > velocity
Definition: transmission.h:64
void actuatorToJointPosition(const ActuatorData &act_data, JointData &jnt_data)
Transform position variables from actuator to joint space.
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
FourBarLinkageTransmission(const std::vector< double > &actuator_reduction, const std::vector< double > &joint_reduction, const std::vector< double > &joint_offset=std::vector< double >(2, 0.0))
void actuatorToJointVelocity(const ActuatorData &act_data, JointData &jnt_data)
Transform velocity variables from actuator to joint space.
void actuatorToJointEffort(const ActuatorData &act_data, JointData &jnt_data)
Transform effort variables from actuator to joint space.
Implementation of a four-bar-linkage transmission.
void jointToActuatorVelocity(const JointData &jnt_data, ActuatorData &act_data)
Transform velocity 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
std::vector< double * > velocity
Definition: transmission.h:53
void jointToActuatorEffort(const JointData &jnt_data, ActuatorData &act_data)
Transform effort variables from joint to actuator space.
std::vector< double * > position
Definition: transmission.h:63
std::vector< double * > effort
Definition: transmission.h:65
std::vector< double * > effort
Definition: transmission.h:54
Abstract base class for representing mechanical transmissions.
Definition: transmission.h:87
void jointToActuatorPosition(const JointData &jnt_data, ActuatorData &act_data)
Transform position variables from joint to actuator space.


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