Go to the documentation of this file.00001
00027 #ifndef SR_JOINT_MOTOR_HPP_
00028 #define SR_JOINT_MOTOR_HPP_
00029
00030 #include <sr_hardware_interface/sr_actuator.hpp>
00031
00032 #include <sr_utilities/sr_math_utils.hpp>
00033 #include <sr_utilities/calibration.hpp>
00034 #include <sr_utilities/thread_safe_map.hpp>
00035
00036 #include <string>
00037 #include <vector>
00038
00039 namespace shadow_joints
00040 {
00041 struct PartialJointToSensor
00042 {
00043 int sensor_id;
00044 double coeff;
00045 };
00046
00047 struct JointToSensor
00048 {
00049 std::vector<std::string> sensor_names;
00050 std::vector<PartialJointToSensor> joint_to_sensor_vector;
00051 bool calibrate_after_combining_sensors;
00052 };
00053
00054 struct JointToMuscle
00055 {
00056 int muscle_driver_id[2];
00057 int muscle_id[2];
00058 };
00059
00060 class SrActuatorWrapper
00061 {
00062 public:
00063 SrActuatorWrapper()
00064 : actuator(NULL),
00065 actuator_ok(false),
00066 bad_data(false)
00067 {
00068 }
00069
00070
00071 ros_ethercat_model::Actuator *actuator;
00072
00077 bool actuator_ok;
00082 bool bad_data;
00083 };
00084
00085 class MotorWrapper :
00086 public SrActuatorWrapper
00087 {
00088 public:
00089 MotorWrapper()
00090 : motor_id(0),
00091 msg_motor_id(0)
00092 {
00093 }
00094
00095
00096
00097 int motor_id;
00098
00099
00100 int msg_motor_id;
00101
00106 ros::ServiceServer force_pid_service;
00107
00112 ros::ServiceServer reset_motor_service;
00113 };
00114
00115 class MuscleDriver
00116 {
00117 public:
00118 explicit MuscleDriver(int id = 0)
00119 : muscle_driver_id(id),
00120 can_msgs_received_(0),
00121 can_msgs_transmitted_(0),
00122 pic_firmware_git_revision_(0),
00123 server_firmware_git_revision_(0),
00124 firmware_modified_(0),
00125 serial_number(0),
00126 assembly_date_year(0),
00127 assembly_date_month(0),
00128 assembly_date_day(0),
00129 can_err_tx(0),
00130 can_err_rx(0),
00131 driver_ok(false),
00132 bad_data(false)
00133 {
00134 }
00135
00136 int muscle_driver_id;
00137 unsigned int pic_firmware_git_revision_;
00138 unsigned int server_firmware_git_revision_;
00139 bool firmware_modified_;
00140 unsigned int serial_number;
00141 unsigned int assembly_date_year;
00142 unsigned int assembly_date_month;
00143 unsigned int assembly_date_day;
00144
00145 unsigned int can_err_tx;
00146 unsigned int can_err_rx;
00147 uint64_t can_msgs_transmitted_;
00148 uint64_t can_msgs_received_;
00149
00150 bool driver_ok;
00151 bool bad_data;
00152
00157 ros::ServiceServer reset_driver_service;
00158 };
00159
00160 class MuscleWrapper :
00161 public SrActuatorWrapper
00162 {
00163 public:
00164 MuscleWrapper()
00165 : muscle_id(),
00166 muscle_driver_id()
00167 {
00168 }
00169
00171
00172 int muscle_driver_id[2];
00174 int muscle_id[2];
00175 };
00176
00177 struct Joint
00178 {
00179 std::string joint_name;
00180
00181
00182
00183
00184 JointToSensor joint_to_sensor;
00185
00186
00187 sr_math_utils::filters::LowPassFilter pos_filter;
00188
00189 sr_math_utils::filters::LowPassFilter effort_filter;
00190
00191 bool has_actuator;
00192 boost::shared_ptr<SrActuatorWrapper> actuator_wrapper;
00193 };
00194
00195 typedef threadsafe::Map<boost::shared_ptr<shadow_robot::JointCalibration> > CalibrationMap;
00196 }
00197
00198
00199
00200
00201
00202
00203
00204 #endif