00001 00027 #ifndef SR_SELF_TEST_HPP_ 00028 #define SR_SELF_TEST_HPP_ 00029 00030 #include <diagnostic_msgs/SelfTest.h> 00031 00032 #include "sr_self_test/sr_test_runner.hpp" 00033 #include "sr_self_test/motor_test.hpp" 00034 00035 #include <boost/thread.hpp> 00036 #include <boost/ptr_container/ptr_vector.hpp> 00037 #include <sr_robot_msgs/joint.h> 00038 #include <sr_hand/hand_commander.hpp> 00039 #include <ros/ros.h> 00040 00041 #include "sr_self_test/test_joint_movement.hpp" 00042 00043 namespace shadow_robot 00044 { 00045 class SrSelfTest { 00046 public: 00047 SrSelfTest(bool simulated); 00048 ~SrSelfTest() {}; 00049 00050 void checkTest() 00051 { 00052 test_runner_.checkTest(); 00053 } 00054 00055 void checkTestAsync() 00056 { 00057 test_thread_.reset(new boost::thread(boost::bind(&SrSelfTest::checkTest, this))); 00058 } 00059 00060 private: 00061 ros::NodeHandle nh_tilde_; 00062 // self_test::TestRunner is the handles sequencing driver self-tests. 00063 shadow_robot::SrTestRunner test_runner_; 00065 boost::shared_ptr<shadowrobot::HandCommander> hand_commander_; 00067 bool simulated_; 00069 void test_services_(); 00071 std::vector<std::string> joints_to_test_; 00072 00074 boost::ptr_vector<MotorTest> motor_tests_; 00075 00077 // TESTING MOVEMENTS 00078 00080 size_t index_joints_to_test_; 00086 void add_all_movements_tests_(const ros::TimerEvent& event); 00088 ros::Timer test_movement_timer_; 00093 void test_movement_(diagnostic_updater::DiagnosticStatusWrapper& status); 00099 void send_safe_target_(std::string joint_name); 00101 boost::shared_ptr<std::map<std::string, sr_robot_msgs::joint> > safe_targets_; 00103 void init_safe_targets_(); 00110 void update_safe_targets_(std::string joint_name); 00112 std::map<std::string, boost::shared_ptr<TestJointMovement> > test_mvts_; 00114 static const double MAX_MSE_CONST_; 00116 std::string path_to_plots_; 00117 00119 boost::shared_ptr<boost::thread> test_thread_; 00120 }; 00121 } 00122 00123 /* For the emacs weenies in the crowd. 00124 Local Variables: 00125 c-basic-offset: 2 00126 End: 00127 */ 00128 00129 #endif /* SR_SELF_TEST_HPP_ */