sr_joint_motor.hpp
Go to the documentation of this file.
1 /*
2 * @file sr_joint_motor.hpp
3 * @author toni <toni@shadowrobot.com>
4 * @date 26 Oct 2011
5 *
6 /* Copyright 2011 Shadow Robot Company Ltd.
7 *
8 * This program is free software: you can redistribute it and/or modify it
9 * under the terms of the GNU General Public License as published by the Free
10 * Software Foundation version 2 of the License.
11 *
12 * This program is distributed in the hope that it will be useful, but WITHOUT
13 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
14 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
15 * more details.
16 *
17 * You should have received a copy of the GNU General Public License along
18 * with this program. If not, see <http://www.gnu.org/licenses/>.
19 *
20 *
21 * @brief Contains the definitions of Motor and Joint
22 *
23 *
24 */
25 
26 #ifndef SR_JOINT_MOTOR_HPP_
27 #define SR_JOINT_MOTOR_HPP_
28 
29 #include <sr_hardware_interface/sr_actuator.hpp>
30 
31 #include <sr_utilities/sr_math_utils.hpp>
32 #include <sr_utilities/calibration.hpp>
33 #include <sr_utilities/thread_safe_map.hpp>
34 
35 #include <string>
36 #include <vector>
37 
38 namespace shadow_joints
39 {
41 {
42  int sensor_id;
43  double coeff;
44 };
45 
47 {
48  std::vector<std::string> sensor_names;
49  std::vector<PartialJointToSensor> joint_to_sensor_vector;
51 };
52 
54 {
55  int muscle_driver_id[2];
56  int muscle_id[2];
57 };
58 
60 {
61 public:
63  : actuator(NULL),
64  actuator_ok(false),
65  bad_data(false)
66  {
67  }
68 
69  // actuator
70  ros_ethercat_model::Actuator *actuator;
71 
72  /*
73  * this boolean is set to true as long as we receive the
74  * data from the actuator.
75  */
77  /*
78  * this boolean is set to true if the data coming from the actuator
79  * through the CAN bus are messed up.
80  */
81  bool bad_data;
82 };
83 
84 class MotorWrapper :
85  public SrActuatorWrapper
86 {
87 public:
89  : motor_id(0),
90  msg_motor_id(0)
91  {
92  }
93 
94  // the position of the motor in the motor array
95  // coming from the hardware
96  int motor_id;
97 
98  // the position of the motor in the message array
100 
101  /*
102  * A service used to set the force PID settings on the
103  * motor.
104  */
106 
107  /*
108  * A service used to reset the
109  * motors.
110  */
112 };
113 
115 {
116 public:
117  explicit MuscleDriver(int id = 0)
118  : muscle_driver_id(id),
119  can_msgs_received_(0),
120  can_msgs_transmitted_(0),
121  pic_firmware_git_revision_(0),
122  server_firmware_git_revision_(0),
123  firmware_modified_(0),
124  serial_number(0),
125  assembly_date_year(0),
126  assembly_date_month(0),
127  assembly_date_day(0),
128  can_err_tx(0),
129  can_err_rx(0),
130  driver_ok(false),
131  bad_data(false)
132  {
133  }
134 
139  unsigned int serial_number;
140  unsigned int assembly_date_year;
141  unsigned int assembly_date_month;
142  unsigned int assembly_date_day;
143 
144  unsigned int can_err_tx;
145  unsigned int can_err_rx;
148 
149  bool driver_ok;
150  bool bad_data;
151 
152  /*
153  * A service used to reset the HW
154  * muscle controller
155  */
157 };
158 
160  public SrActuatorWrapper
161 {
162 public:
164  : muscle_id(),
165  muscle_driver_id()
166  {
167  }
168 
170  // by different muscle drivers.
171  int muscle_driver_id[2];
173  int muscle_id[2];
174 };
175 
176 struct Joint
177 {
178  std::string joint_name;
179 
180  // the indexes of the joints in the joint array
181  // coming from the hardware which are used to
182  // compute the joint data.
184 
185  // used to filter the position and the velocity
186  sr_math_utils::filters::LowPassFilter pos_filter;
187  // used to filter the effort
188  sr_math_utils::filters::LowPassFilter effort_filter;
189 
192 };
193 
194 typedef threadsafe::Map<boost::shared_ptr<shadow_robot::JointCalibration> > CalibrationMap;
195 } // namespace shadow_joints
196 
197 /* For the emacs weenies in the crowd.
198  Local Variables:
199  c-basic-offset: 2
200  End:
201 */
202 
203 #endif /* SR_JOINT_MOTOR_HPP_ */
JointToSensor joint_to_sensor
std::vector< std::string > sensor_names
ros::ServiceServer reset_motor_service
ros_ethercat_model::Actuator * actuator
std::vector< PartialJointToSensor > joint_to_sensor_vector
sr_math_utils::filters::LowPassFilter pos_filter
ros::ServiceServer force_pid_service
boost::shared_ptr< SrActuatorWrapper > actuator_wrapper
ros::ServiceServer reset_driver_service
threadsafe::Map< boost::shared_ptr< shadow_robot::JointCalibration > > CalibrationMap
sr_math_utils::filters::LowPassFilter effort_filter
unsigned int server_firmware_git_revision_


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Tue Oct 13 2020 04:01:57