sr_joint_motor.hpp
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 
00037 namespace shadow_joints
00038 {
00039   struct PartialJointToSensor
00040   {
00041     int sensor_id;
00042     double coeff;
00043   };
00044 
00045   struct JointToSensor
00046   {
00047     std::vector<std::string> sensor_names;
00048     std::vector<PartialJointToSensor> joint_to_sensor_vector;
00049     bool calibrate_after_combining_sensors;
00050   };
00051 
00052   struct JointToMuscle
00053   {
00054     int muscle_driver_id[2];
00055     int muscle_id[2];
00056   };
00057 
00058   class SrActuatorWrapper
00059   {
00060   public:
00061     SrActuatorWrapper()
00062         : actuator(NULL), actuator_ok(false), bad_data(false) {}
00063     
00064     ~SrActuatorWrapper() {}
00065 
00066     //actuator
00067     sr_actuator::SrGenericActuator* actuator;
00068 
00073     bool actuator_ok;
00078     bool bad_data;
00079   };
00080 
00081   class MotorWrapper : public SrActuatorWrapper
00082   {
00083   public:
00084     MotorWrapper()
00085         : SrActuatorWrapper(), motor_id(0), msg_motor_id(0) {}
00086 
00087     ~MotorWrapper() {}
00088 
00089     //the position of the motor in the motor array
00090     // coming from the hardware
00091     int motor_id;
00092 
00093     //the position of the motor in the message array
00094     int msg_motor_id;
00095 
00100     ros::ServiceServer force_pid_service;
00101 
00106     ros::ServiceServer reset_motor_service;
00107   };
00108 
00109   class MuscleDriver
00110   {
00111   public:
00112     MuscleDriver(int id=0)
00113       : muscle_driver_id(id),
00114         can_msgs_received_(0),
00115         can_msgs_transmitted_(0),
00116         pic_firmware_svn_revision_(0),
00117         server_firmware_svn_revision_(0),
00118         firmware_modified_(0),
00119         serial_number(0),
00120         assembly_date_year(0),
00121         assembly_date_month(0),
00122         assembly_date_day(0),
00123         can_err_tx(0),
00124         can_err_rx(0),
00125         driver_ok(false),
00126         bad_data(false)
00127     {}
00128 
00129     ~MuscleDriver() {}
00130 
00131     int muscle_driver_id;
00132     unsigned int pic_firmware_svn_revision_;
00133     unsigned int server_firmware_svn_revision_;
00134     bool firmware_modified_;
00135     unsigned int serial_number;
00136     unsigned int assembly_date_year;
00137     unsigned int assembly_date_month;
00138     unsigned int assembly_date_day;
00139 
00140     unsigned int        can_err_tx;
00141     unsigned int        can_err_rx;
00142     uint64_t              can_msgs_transmitted_;
00143     uint64_t              can_msgs_received_;
00144 
00145     bool driver_ok;
00146     bool bad_data;
00147 
00152     ros::ServiceServer reset_driver_service;
00153   };
00154 
00155   class MuscleWrapper : public SrActuatorWrapper
00156   {
00157   public:
00158     MuscleWrapper()
00159         : SrActuatorWrapper()
00160     {
00161       muscle_id[0] = 0;
00162       muscle_id[1] = 0;
00163       muscle_driver_id[0] = 0;
00164       muscle_driver_id[1] = 0;
00165     }
00166 
00167     ~MuscleWrapper() {}
00168 
00170     int muscle_driver_id[2];
00172     int muscle_id[2];
00173   };
00174 
00175   struct Joint
00176   {
00177     std::string joint_name;
00178 
00179     //the indexes of the joints in the joint array
00180     // coming from the hardware which are used to
00181     // compute the joint data.
00182     JointToSensor joint_to_sensor;
00183 
00184     //used to filter the position and the velocity
00185     sr_math_utils::filters::LowPassFilter pos_filter;
00186     //used to filter the effort
00187     sr_math_utils::filters::LowPassFilter effort_filter;
00188 
00189     bool has_actuator;
00190     boost::shared_ptr<SrActuatorWrapper> actuator_wrapper;
00191   };
00192 
00193   typedef threadsafe::Map<boost::shared_ptr<shadow_robot::JointCalibration> > CalibrationMap;
00194 }
00195 
00196 /* For the emacs weenies in the crowd.
00197  Local Variables:
00198  c-basic-offset: 2
00199  End:
00200  */
00201 
00202 #endif /* SR_JOINT_MOTOR_HPP_ */


sr_robot_lib
Author(s): Ugo Cupcic, Toni Oliver
autogenerated on Thu Aug 27 2015 15:16:37