motor_test.hpp
Go to the documentation of this file.
00001 
00029 #ifndef _MOTOR_TEST_H_
00030 #define _MOTOR_TEST_H_
00031 
00032 #include <self_test/self_test.h>
00033 #include <sr_hand/hand_commander.hpp>
00034 
00035 namespace shadow_robot
00036 {
00037   class MotorTest
00038   {
00039   public:
00040     MotorTest( self_test::TestRunner* test_runner,
00041                std::string joint_name,
00042                shadowrobot::HandCommander* hand_commander);
00043     virtual ~MotorTest() {};
00044 
00045     void run_test(diagnostic_updater::DiagnosticStatusWrapper& status);
00046 
00047   protected:
00048     ros::NodeHandle nh_;
00049     self_test::TestRunner* test_runner_;
00050     std::string joint_name_;
00051     shadowrobot::HandCommander* hand_commander_;
00052     ros::Publisher effort_pub_;
00053     ros::Subscriber diagnostic_sub_;
00054     double PWM_target_;
00056     short record_data_;
00057 
00058     bool test_current_zero_;
00059     bool test_current_moving_;
00060     bool test_strain_gauge_right_;
00061     bool test_strain_gauge_left_;
00062 
00063     static const double STANDARD_PWM_TARGET_;
00064     static const double WRJ1_PWM_TARGET_;
00065     static const double WRJ2_PWM_TARGET_;
00066     static const int STRAIN_GAUGE_THRESHOLD_;
00067 
00072     void diagnostics_agg_cb_(const diagnostic_msgs::DiagnosticArray::ConstPtr& msg);
00073   };
00074 }
00075 
00076   /* For the emacs weenies in the crowd.
00077      Local Variables:
00078      c-basic-offset: 2
00079      End:
00080   */
00081 
00082 #endif /* _MOTOR_TEST_H_ */


sr_self_test
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:38