#include <motor_test.hpp>
| Public Member Functions | |
| MotorTest (self_test::TestRunner *test_runner, std::string joint_name, shadowrobot::HandCommander *hand_commander) | |
| void | run_test (diagnostic_updater::DiagnosticStatusWrapper &status) | 
| virtual | ~MotorTest () | 
| Protected Member Functions | |
| void | diagnostics_agg_cb_ (const diagnostic_msgs::DiagnosticArray::ConstPtr &msg) | 
| Protected Attributes | |
| ros::Subscriber | diagnostic_sub_ | 
| ros::Publisher | effort_pub_ | 
| shadowrobot::HandCommander * | hand_commander_ | 
| std::string | joint_name_ | 
| ros::NodeHandle | nh_ | 
| double | PWM_target_ | 
| short | record_data_ | 
| 0 if not recording, 1 if going +, -1 if going - | |
| bool | test_current_moving_ | 
| bool | test_current_zero_ | 
| self_test::TestRunner * | test_runner_ | 
| bool | test_strain_gauge_left_ | 
| bool | test_strain_gauge_right_ | 
| Static Protected Attributes | |
| static const double | STANDARD_PWM_TARGET_ = 150.0 | 
| static const int | STRAIN_GAUGE_THRESHOLD_ = 40 | 
| static const double | WRJ1_PWM_TARGET_ = 250.0 | 
| static const double | WRJ2_PWM_TARGET_ = 190.0 | 
Definition at line 37 of file motor_test.hpp.
| shadow_robot::MotorTest::MotorTest | ( | self_test::TestRunner * | test_runner, | 
| std::string | joint_name, | ||
| shadowrobot::HandCommander * | hand_commander | ||
| ) | 
Definition at line 45 of file motor_test.cpp.
| virtual shadow_robot::MotorTest::~MotorTest | ( | ) |  [inline, virtual] | 
Definition at line 43 of file motor_test.hpp.
| void shadow_robot::MotorTest::diagnostics_agg_cb_ | ( | const diagnostic_msgs::DiagnosticArray::ConstPtr & | msg | ) |  [protected] | 
Susbscribed to the diagnostics_agg topic.
| msg | new incoming msg | 
Definition at line 232 of file motor_test.cpp.
Definition at line 64 of file motor_test.cpp.
Definition at line 53 of file motor_test.hpp.
| ros::Publisher shadow_robot::MotorTest::effort_pub_  [protected] | 
Definition at line 52 of file motor_test.hpp.
Definition at line 51 of file motor_test.hpp.
| std::string shadow_robot::MotorTest::joint_name_  [protected] | 
Definition at line 50 of file motor_test.hpp.
| ros::NodeHandle shadow_robot::MotorTest::nh_  [protected] | 
Definition at line 48 of file motor_test.hpp.
| double shadow_robot::MotorTest::PWM_target_  [protected] | 
Definition at line 54 of file motor_test.hpp.
| short shadow_robot::MotorTest::record_data_  [protected] | 
0 if not recording, 1 if going +, -1 if going -
Definition at line 56 of file motor_test.hpp.
| const double shadow_robot::MotorTest::STANDARD_PWM_TARGET_ = 150.0  [static, protected] | 
Definition at line 63 of file motor_test.hpp.
| const int shadow_robot::MotorTest::STRAIN_GAUGE_THRESHOLD_ = 40  [static, protected] | 
Definition at line 66 of file motor_test.hpp.
| bool shadow_robot::MotorTest::test_current_moving_  [protected] | 
Definition at line 59 of file motor_test.hpp.
| bool shadow_robot::MotorTest::test_current_zero_  [protected] | 
Definition at line 58 of file motor_test.hpp.
Definition at line 49 of file motor_test.hpp.
| bool shadow_robot::MotorTest::test_strain_gauge_left_  [protected] | 
Definition at line 61 of file motor_test.hpp.
| bool shadow_robot::MotorTest::test_strain_gauge_right_  [protected] | 
Definition at line 60 of file motor_test.hpp.
| const double shadow_robot::MotorTest::WRJ1_PWM_TARGET_ = 250.0  [static, protected] | 
Definition at line 64 of file motor_test.hpp.
| const double shadow_robot::MotorTest::WRJ2_PWM_TARGET_ = 190.0  [static, protected] | 
Definition at line 65 of file motor_test.hpp.