#include <sr_self_test.hpp>
| Public Member Functions | |
| void | checkTest () | 
| void | checkTestAsync () | 
| SrSelfTest (bool simulated, const std::string &ns="") | |
| ~SrSelfTest () | |
| Private Member Functions | |
| void | add_all_movements_tests_ (const ros::TimerEvent &event) | 
| void | init_safe_targets_ () | 
| Initialises the map safe_targets_. | |
| void | send_safe_target_ (std::string joint_name) | 
| void | test_movement_ (diagnostic_updater::DiagnosticStatusWrapper &status) | 
| void | test_services_ () | 
| Add some services to be checked for existence. | |
| void | update_safe_targets_ (std::string joint_name) | 
| Private Attributes | |
| boost::shared_ptr < shadowrobot::HandCommander > | hand_commander_ | 
| The hand commander is used for getting a list of all controlled joints. | |
| size_t | index_joints_to_test_ | 
| The index of the current joint being tested (movement) | |
| std::vector< std::string > | joints_to_test_ | 
| a vector containing all the joints to be tested | |
| boost::ptr_vector< MotorTest > | motor_tests_ | 
| a vector containing the test to be run on the motors. | |
| ros::NodeHandle | nh_ | 
| ros::NodeHandle | nh_tilde_ | 
| std::string | path_to_plots_ | 
| Where the plots of the movements are stored. | |
| boost::shared_ptr< std::map < std::string, sr_robot_msgs::joint > > | safe_targets_ | 
| A map storing the safe targets for the joints (only those different than min) | |
| bool | simulated_ | 
| True if testing gazebo, false if testing etherCAT hand. | |
| ros::Timer | test_movement_timer_ | 
| Timer used to start add_all_movements_tests_ asynchronously. | |
| std::map< std::string, boost::shared_ptr < TestJointMovement > > | test_mvts_ | 
| mapping the joint name to a TestJointMovement | |
| shadow_robot::SrTestRunner | test_runner_ | 
| boost::shared_ptr< boost::thread > | test_thread_ | 
| Thread for running the tests in parallel when doing the tests on real hand. | |
| Static Private Attributes | |
| static const double | MAX_MSE_CONST_ = 0.18 | 
| The maximum MSE we can accept for the test to succeed. | |
Definition at line 45 of file sr_self_test.hpp.
| shadow_robot::SrSelfTest::SrSelfTest | ( | bool | simulated, | 
| const std::string & | ns = "" | ||
| ) | 
Definition at line 35 of file sr_self_test.cpp.
| shadow_robot::SrSelfTest::~SrSelfTest | ( | ) |  [inline] | 
Definition at line 48 of file sr_self_test.hpp.
| void shadow_robot::SrSelfTest::add_all_movements_tests_ | ( | const ros::TimerEvent & | event | ) |  [private] | 
A method which adds a movement test for each of the fingers.
| event | called from a timer for non-blocking initialisation of the HandCommander. | 
Definition at line 109 of file sr_self_test.cpp.
| void shadow_robot::SrSelfTest::checkTest | ( | ) |  [inline] | 
Definition at line 50 of file sr_self_test.hpp.
| void shadow_robot::SrSelfTest::checkTestAsync | ( | ) |  [inline] | 
Definition at line 55 of file sr_self_test.hpp.
| void shadow_robot::SrSelfTest::init_safe_targets_ | ( | ) |  [private] | 
Initialises the map safe_targets_.
Definition at line 324 of file sr_self_test.cpp.
| void shadow_robot::SrSelfTest::send_safe_target_ | ( | std::string | joint_name | ) |  [private] | 
Sends a "safe target" to all the joints: we want to avoid the collisions when running the movement tests.
| joint_name | the joint we're going to move. | 
Definition at line 231 of file sr_self_test.cpp.
| void shadow_robot::SrSelfTest::test_movement_ | ( | diagnostic_updater::DiagnosticStatusWrapper & | status | ) |  [private] | 
Tests the movement of one finger and update the test result.
| status | contains the test result | 
Definition at line 166 of file sr_self_test.cpp.
| void shadow_robot::SrSelfTest::test_services_ | ( | ) |  [private] | 
Add some services to be checked for existence.
Definition at line 93 of file sr_self_test.cpp.
| void shadow_robot::SrSelfTest::update_safe_targets_ | ( | std::string | joint_name | ) |  [private] | 
Updates the map safe_targets_ based on the joint we're going to move. For example ??J4 safe values are different depending on which joint 4 has been moved already.
| joint_name | The name of the joint we're going to move. | 
Definition at line 262 of file sr_self_test.cpp.
| boost::shared_ptr<shadowrobot::HandCommander> shadow_robot::SrSelfTest::hand_commander_  [private] | 
The hand commander is used for getting a list of all controlled joints.
Definition at line 66 of file sr_self_test.hpp.
| size_t shadow_robot::SrSelfTest::index_joints_to_test_  [private] | 
The index of the current joint being tested (movement)
Definition at line 81 of file sr_self_test.hpp.
| std::vector<std::string> shadow_robot::SrSelfTest::joints_to_test_  [private] | 
a vector containing all the joints to be tested
Definition at line 72 of file sr_self_test.hpp.
| const double shadow_robot::SrSelfTest::MAX_MSE_CONST_ = 0.18  [static, private] | 
The maximum MSE we can accept for the test to succeed.
Definition at line 115 of file sr_self_test.hpp.
| boost::ptr_vector<MotorTest> shadow_robot::SrSelfTest::motor_tests_  [private] | 
a vector containing the test to be run on the motors.
Definition at line 75 of file sr_self_test.hpp.
| ros::NodeHandle shadow_robot::SrSelfTest::nh_  [private] | 
Definition at line 62 of file sr_self_test.hpp.
Definition at line 61 of file sr_self_test.hpp.
| std::string shadow_robot::SrSelfTest::path_to_plots_  [private] | 
Where the plots of the movements are stored.
Definition at line 117 of file sr_self_test.hpp.
| boost::shared_ptr<std::map<std::string, sr_robot_msgs::joint> > shadow_robot::SrSelfTest::safe_targets_  [private] | 
A map storing the safe targets for the joints (only those different than min)
Definition at line 102 of file sr_self_test.hpp.
| bool shadow_robot::SrSelfTest::simulated_  [private] | 
True if testing gazebo, false if testing etherCAT hand.
Definition at line 68 of file sr_self_test.hpp.
Timer used to start add_all_movements_tests_ asynchronously.
Definition at line 89 of file sr_self_test.hpp.
| std::map<std::string, boost::shared_ptr<TestJointMovement> > shadow_robot::SrSelfTest::test_mvts_  [private] | 
mapping the joint name to a TestJointMovement
Definition at line 113 of file sr_self_test.hpp.
Definition at line 64 of file sr_self_test.hpp.
| boost::shared_ptr<boost::thread> shadow_robot::SrSelfTest::test_thread_  [private] | 
Thread for running the tests in parallel when doing the tests on real hand.
Definition at line 120 of file sr_self_test.hpp.