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     }
00065     ;
00066 
00067     ~SrActuatorWrapper()
00068     {
00069     }
00070     ;
00071 
00072 
00073     //actuator
00074     sr_actuator::SrGenericActuator* actuator;
00075 
00080     bool actuator_ok;
00085     bool bad_data;
00086   };
00087 
00088   class MotorWrapper : public SrActuatorWrapper
00089   {
00090   public:
00091     MotorWrapper()
00092         : SrActuatorWrapper(), motor_id(0), msg_motor_id(0)
00093     {
00094     }
00095     ;
00096 
00097     ~MotorWrapper()
00098     {
00099     }
00100     ;
00101 
00102     //the position of the motor in the motor array
00103     // coming from the hardware
00104     int motor_id;
00105 
00106     //the position of the motor in the message array
00107     int msg_motor_id;
00108 
00113     ros::ServiceServer force_pid_service;
00114 
00119     ros::ServiceServer reset_motor_service;
00120   };
00121 
00122   class MuscleDriver
00123   {
00124   public:
00125     MuscleDriver(int id=0)
00126       : muscle_driver_id(id),
00127         can_msgs_received_(0),
00128         can_msgs_transmitted_(0),
00129         pic_firmware_svn_revision_(0),
00130         server_firmware_svn_revision_(0),
00131         firmware_modified_(0),
00132         serial_number(0),
00133         assembly_date_year(0),
00134         assembly_date_month(0),
00135         assembly_date_day(0),
00136         can_err_tx(0),
00137         can_err_rx(0),
00138         driver_ok(false),
00139         bad_data(false)
00140     {
00141     };
00142 
00143     ~MuscleDriver()
00144     {
00145     };
00146 
00147     int muscle_driver_id;
00148     unsigned int pic_firmware_svn_revision_;
00149     unsigned int server_firmware_svn_revision_;
00150     bool firmware_modified_;
00151     unsigned int serial_number;
00152     unsigned int assembly_date_year;
00153     unsigned int assembly_date_month;
00154     unsigned int assembly_date_day;
00155 
00156     unsigned int        can_err_tx;
00157     unsigned int        can_err_rx;
00158     uint64_t              can_msgs_transmitted_;
00159     uint64_t              can_msgs_received_;
00160 
00161     bool driver_ok;
00162     bool bad_data;
00163 
00168     ros::ServiceServer reset_driver_service;
00169   };
00170 
00171   class MuscleWrapper : public SrActuatorWrapper
00172   {
00173   public:
00174     MuscleWrapper()
00175         : SrActuatorWrapper()
00176     {
00177       muscle_id[0] = 0;
00178       muscle_id[1] = 0;
00179       muscle_driver_id[0] = 0;
00180       muscle_driver_id[1] = 0;
00181     }
00182     ;
00183 
00184     ~MuscleWrapper()
00185     {
00186     }
00187     ;
00188 
00190     int muscle_driver_id[2];
00192     int muscle_id[2];
00193   };
00194 
00195   struct Joint
00196   {
00197     std::string joint_name;
00198 
00199     //the indexes of the joints in the joint array
00200     // coming from the hardware which are used to
00201     // compute the joint data.
00202     JointToSensor joint_to_sensor;
00203 
00204     //used to filter the position and the velocity
00205     sr_math_utils::filters::LowPassFilter pos_filter;
00206     //used to filter the effort
00207     sr_math_utils::filters::LowPassFilter effort_filter;
00208 
00209     bool has_actuator;
00210     boost::shared_ptr<SrActuatorWrapper> actuator_wrapper;
00211   };
00212 
00213   typedef threadsafe::Map<boost::shared_ptr<shadow_robot::JointCalibration> > CalibrationMap;
00214 }
00215 
00216 /* For the emacs weenies in the crowd.
00217  Local Variables:
00218  c-basic-offset: 2
00219  End:
00220  */
00221 
00222 #endif /* SR_JOINT_MOTOR_HPP_ */


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:37:50