simple_transmission_for_muscle.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 /*
35  * Author: Stuart Glaser
36  *
37  * modified by Ugo Cupcic
38  */
39 
41 #include <string>
42 
43 using ros_ethercat_model::Transmission;
44 using ros_ethercat_model::RobotState;
46 using std::string;
47 
48 PLUGINLIB_EXPORT_CLASS(sr_mechanism_model::SimpleTransmissionForMuscle, Transmission)
49 
50 namespace sr_mechanism_model
51 {
52 
53  bool SimpleTransmissionForMuscle::initXml(TiXmlElement *elt, RobotState *robot)
54  {
55  if (!SimpleTransmission::Transmission::initXml(elt, robot))
56  {
57  return false;
58  }
59 
60  string act_name = actuator_->name_;
61  delete actuator_; // That's a SrMotorActuator at this point
62  actuator_ = new SrMuscleActuator();
63  actuator_->name_ = act_name;
64  actuator_->command_.enable_ = true;
65 
66  return true;
67  }
68 
69  void SimpleTransmissionForMuscle::propagatePosition()
70  {
71  SrMuscleActuator *act = static_cast<SrMuscleActuator *>(actuator_);
72  joint_->position_ = act->state_.position_;
73  joint_->velocity_ = act->state_.velocity_;
74 
75  // We don't want to define a modified version of JointState, as that would imply using a modified version
76  // of robot_state.hpp, controller manager, ethercat_hardware and ros_etherCAT main loop
77  // So we will encode the two uint16_t that contain the data from the muscle pressure sensors
78  // into the double effort_. (We don't have any measured effort in the muscle hand anyway).
79  // Then in the joint controller we will decode that back into uint16_t.
80  joint_->effort_ = (static_cast<double>(act->muscle_state_.pressure_[1]) * 0x10000)
81  + static_cast<double>(act->muscle_state_.pressure_[0]);
82  }
83 
84  void SimpleTransmissionForMuscle::propagateEffort()
85  {
86  SrMuscleActuator *act = static_cast<SrMuscleActuator *>(actuator_);
87  act->command_.enable_ = true;
88 
89  // We don't want to define a modified version of JointState, as that would imply using a modified version
90  // of robot_state.hpp, controller manager, ethercat_hardware and ros_etherCAT main loop
91  // So the controller encodes the two int16 that contain the valve commands into the double effort_.
92  // (We don't have any real commanded_effort_ in the muscle hand anyway).
93  // Here we decode them back into two int16_t.
94  double valve_0 = fmod(joint_->commanded_effort_, 0x10);
95  int8_t valve_0_tmp = (int8_t) (valve_0 + 0.5);
96  if (valve_0_tmp >= 8)
97  {
98  valve_0_tmp -= 8;
99  valve_0_tmp *= (-1);
100  }
101 
102  int8_t valve_1_tmp = (int8_t) (((fmod(joint_->commanded_effort_, 0x100) - valve_0) / 0x10) + 0.5);
103  if (valve_1_tmp >= 8)
104  {
105  valve_1_tmp -= 8;
106  valve_1_tmp *= (-1);
107  }
108 
109  act->muscle_command_.valve_[0] = valve_0_tmp;
110  act->muscle_command_.valve_[1] = valve_1_tmp;
111  }
112 
113 } // namespace sr_mechanism_model
114 
115 /* For the emacs weenies in the crowd.
116 Local Variables:
117  c-basic-offset: 2
118 End:
119  */
SrMuscleActuatorState muscle_state_
SrMuscleActuatorCommand muscle_command_


sr_mechanism_model
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:44