simple_transmission.h
Go to the documentation of this file.
00001 
00002 // Copyright (C) 2013, PAL Robotics S.L.
00003 //
00004 // Redistribution and use in source and binary forms, with or without
00005 // modification, are permitted provided that the following conditions are met:
00006 //   * Redistributions of source code must retain the above copyright notice,
00007 //     this list of conditions and the following disclaimer.
00008 //   * Redistributions in binary form must reproduce the above copyright
00009 //     notice, this list of conditions and the following disclaimer in the
00010 //     documentation and/or other materials provided with the distribution.
00011 //   * Neither the name of PAL Robotics S.L. nor the names of its
00012 //     contributors may be used to endorse or promote products derived from
00013 //     this software without specific prior written permission.
00014 //
00015 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00016 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00017 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00018 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00019 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00020 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00021 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00022 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00023 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00024 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00025 // POSSIBILITY OF SUCH DAMAGE.
00027 
00029 
00030 #ifndef TRANSMISSION_INTERFACE_SIMPLE_TRANSMISSION_H
00031 #define TRANSMISSION_INTERFACE_SIMPLE_TRANSMISSION_H
00032 
00033 #include <cassert>
00034 #include <string>
00035 #include <vector>
00036 
00037 #include <transmission_interface/transmission.h>
00038 #include <transmission_interface/transmission_interface_exception.h>
00039 
00040 namespace transmission_interface
00041 {
00042 
00095 class SimpleTransmission : public Transmission
00096 {
00097 public:
00103   SimpleTransmission(const double reduction,
00104                      const double joint_offset = 0.0);
00105 
00113   void actuatorToJointEffort(const ActuatorData& act_data,
00114                                    JointData&    jnt_data);
00115 
00123   void actuatorToJointVelocity(const ActuatorData& act_data,
00124                                      JointData&    jnt_data);
00125 
00133   void actuatorToJointPosition(const ActuatorData& act_data,
00134                                      JointData&    jnt_data);
00135 
00143   void jointToActuatorEffort(const JointData&    jnt_data,
00144                                    ActuatorData& act_data);
00145 
00153   void jointToActuatorVelocity(const JointData&    jnt_data,
00154                                      ActuatorData& act_data);
00155 
00163   void jointToActuatorPosition(const JointData&    jnt_data,
00164                                      ActuatorData& act_data);
00165 
00166   std::size_t numActuators() const {return 1;}
00167   std::size_t numJoints()    const {return 1;}
00168 
00169   double getActuatorReduction() const {return reduction_;}
00170   double getJointOffset()       const {return jnt_offset_;}
00171 
00172 private:
00173   double reduction_;
00174   double jnt_offset_;
00175 };
00176 
00177 inline SimpleTransmission::SimpleTransmission(const double reduction,
00178                                               const double joint_offset)
00179   : Transmission(),
00180     reduction_(reduction),
00181     jnt_offset_(joint_offset)
00182 {
00183   if (0.0 == reduction_)
00184   {
00185     throw TransmissionInterfaceException("Transmission reduction ratio cannot be zero.");
00186   }
00187 }
00188 
00189 inline void SimpleTransmission::actuatorToJointEffort(const ActuatorData& act_data,
00190                                                             JointData&    jnt_data)
00191 {
00192   assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
00193   assert(act_data.effort[0] && jnt_data.effort[0]);
00194 
00195   *jnt_data.effort[0] = *act_data.effort[0] * reduction_;
00196 }
00197 
00198 inline void SimpleTransmission::actuatorToJointVelocity(const ActuatorData& act_data,
00199                                                               JointData&    jnt_data)
00200 {
00201   assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
00202   assert(act_data.velocity[0] && jnt_data.velocity[0]);
00203 
00204   *jnt_data.velocity[0] = *act_data.velocity[0] / reduction_;
00205 }
00206 
00207 inline void SimpleTransmission::actuatorToJointPosition(const ActuatorData& act_data,
00208                                                               JointData&    jnt_data)
00209 {
00210   assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
00211   assert(act_data.position[0] && jnt_data.position[0]);
00212 
00213   *jnt_data.position[0] = *act_data.position[0] / reduction_ + jnt_offset_;
00214 }
00215 
00216 inline void SimpleTransmission::jointToActuatorEffort(const JointData&    jnt_data,
00217                                                             ActuatorData& act_data)
00218 {
00219   assert(numActuators() == act_data.effort.size() && numJoints() == jnt_data.effort.size());
00220   assert(act_data.effort[0] && jnt_data.effort[0]);
00221 
00222   *act_data.effort[0] = *jnt_data.effort[0] / reduction_;
00223 }
00224 
00225 inline void SimpleTransmission::jointToActuatorVelocity(const JointData&    jnt_data,
00226                                                               ActuatorData& act_data)
00227 {
00228   assert(numActuators() == act_data.velocity.size() && numJoints() == jnt_data.velocity.size());
00229   assert(act_data.velocity[0] && jnt_data.velocity[0]);
00230 
00231   *act_data.velocity[0] = *jnt_data.velocity[0] * reduction_;
00232 }
00233 
00234 inline void SimpleTransmission::jointToActuatorPosition(const JointData&    jnt_data,
00235                                                               ActuatorData& act_data)
00236 {
00237   assert(numActuators() == act_data.position.size() && numJoints() == jnt_data.position.size());
00238   assert(act_data.position[0] && jnt_data.position[0]);
00239 
00240   *act_data.position[0] = (*jnt_data.position[0] - jnt_offset_) * reduction_;
00241 }
00242 
00243 } // transmission_interface
00244 
00245 #endif // TRANSMISSION_INTERFACE_SIMPLE_TRANSMISSION_H


transmission_interface
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Sat Jun 8 2019 20:09:31