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   class Motor
00053   {
00054   public:
00055     Motor()
00056         : motor_id(0), msg_motor_id(0), actuator(NULL), motor_ok(false), bad_data(false)
00057     {
00058     }
00059     ;
00060 
00061     ~Motor()
00062     {
00063     }
00064     ;
00065 
00066     //the position of the motor in the motor array
00067     // coming from the hardware
00068     int motor_id;
00069 
00070     //the position of the motor in the message array
00071     int msg_motor_id;
00072 
00073     //actuator
00074     sr_actuator::SrActuator* actuator;
00075 
00080     bool motor_ok;
00085     bool bad_data;
00086 
00091     ros::ServiceServer force_pid_service;
00092 
00097     ros::ServiceServer reset_motor_service;
00098   };
00099 
00100   struct Joint
00101   {
00102     std::string joint_name;
00103 
00104     //the indexes of the joints in the joint array
00105     // coming from the hardware which are used to
00106     // compute the joint data.
00107     JointToSensor joint_to_sensor;
00108 
00109     //used to filter the position and the velocity
00110     sr_math_utils::filters::LowPassFilter pos_filter;
00111     //used to filter the effort
00112     sr_math_utils::filters::LowPassFilter effort_filter;
00113 
00114     bool has_motor;
00115     boost::shared_ptr<Motor> motor;
00116   };
00117 
00118   typedef threadsafe::Map<boost::shared_ptr<shadow_robot::JointCalibration> > CalibrationMap;
00119 }
00120 
00121 /* For the emacs weenies in the crowd.
00122  Local Variables:
00123  c-basic-offset: 2
00124  End:
00125  */
00126 
00127 #endif /* SR_JOINT_MOTOR_HPP_ */


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:02:17