Hystersis Controller. More...
#include <hysteresis_controller2.h>

| Public Types | |
| enum | { STOPPED, MOVING_HOME, MOVING_UP, MOVING_DOWN, ANALYZING, DONE } | 
| Public Member Functions | |
| void | analysis () | 
| Perform the test analysis. | |
| bool | done () | 
| HysteresisController2 () | |
| bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) | 
| Functional way to initialize. | |
| bool | sendData () | 
| Sends data, returns true if sent. | |
| void | starting () | 
| Called when controller is started. | |
| void | update () | 
| Issues commands to the joint to perform hysteresis test. | |
| ~HysteresisController2 () | |
| Private Member Functions | |
| bool | turn () | 
| Private Attributes | |
| bool | complete | 
| bool | data_sent_ | 
| int | down_count_ | 
| boost::scoped_ptr < realtime_tools::RealtimePublisher < joint_qualification_controllers::HysteresisData2 > > | hyst_pub_ | 
| double | initial_position_ | 
| ros::Time | initial_time_ | 
| pr2_mechanism_model::JointState * | joint_ | 
| double | last_publish_time_ | 
| double | max_effort_ | 
| std::vector< int > | move_count_ | 
| int | repeat_ | 
| int | repeat_count_ | 
| pr2_mechanism_model::RobotState * | robot_ | 
| int | starting_count_ | 
| int | state_ | 
| joint_qualification_controllers::HysteresisData2 | test_data_ | 
| double | timeout_ | 
| int | up_count_ | 
| double | velocity_ | 
| controller::JointVelocityController * | velocity_controller_ | 
Hystersis Controller.
This tests the hysteresis of a joint using a velocity controller.
Definition at line 60 of file hysteresis_controller2.h.
| anonymous enum | 
Definition at line 64 of file hysteresis_controller2.h.
Definition at line 47 of file hysteresis_controller2.cpp.
Definition at line 97 of file hysteresis_controller2.cpp.
| void HysteresisController2::analysis | ( | ) | 
Perform the test analysis.
Definition at line 358 of file hysteresis_controller2.cpp.
| bool joint_qualification_controllers::HysteresisController2::done | ( | ) |  [inline] | 
Definition at line 96 of file hysteresis_controller2.h.
| bool HysteresisController2::init | ( | pr2_mechanism_model::RobotState * | robot, | 
| ros::NodeHandle & | n | ||
| ) |  [virtual] | 
Functional way to initialize.
| *robot | The robot that is being controlled. | 
| &n | NodeHandle of mechanism control | 
Implements pr2_controller_interface::Controller.
Definition at line 102 of file hysteresis_controller2.cpp.
| bool HysteresisController2::sendData | ( | ) | 
Sends data, returns true if sent.
Definition at line 373 of file hysteresis_controller2.cpp.
| void HysteresisController2::starting | ( | ) |  [virtual] | 
Called when controller is started.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 239 of file hysteresis_controller2.cpp.
| bool HysteresisController2::turn | ( | ) |  [private] | 
Definition at line 341 of file hysteresis_controller2.cpp.
| void HysteresisController2::update | ( | void | ) |  [virtual] | 
Issues commands to the joint to perform hysteresis test.
Implements pr2_controller_interface::Controller.
Definition at line 247 of file hysteresis_controller2.cpp.
Definition at line 113 of file hysteresis_controller2.h.
Definition at line 120 of file hysteresis_controller2.h.
Definition at line 109 of file hysteresis_controller2.h.
| boost::scoped_ptr<realtime_tools::RealtimePublisher<joint_qualification_controllers::HysteresisData2> > joint_qualification_controllers::HysteresisController2::hyst_pub_  [private] | 
Definition at line 125 of file hysteresis_controller2.h.
Definition at line 108 of file hysteresis_controller2.h.
Start time of the test.
Definition at line 107 of file hysteresis_controller2.h.
| pr2_mechanism_model::JointState* joint_qualification_controllers::HysteresisController2::joint_  [private] | 
Joint we're controlling.
Definition at line 102 of file hysteresis_controller2.h.
Definition at line 122 of file hysteresis_controller2.h.
| double joint_qualification_controllers::HysteresisController2::max_effort_  [private] | 
Maximum allowable effort.
Definition at line 106 of file hysteresis_controller2.h.
Definition at line 110 of file hysteresis_controller2.h.
Definition at line 112 of file hysteresis_controller2.h.
Definition at line 111 of file hysteresis_controller2.h.
| pr2_mechanism_model::RobotState* joint_qualification_controllers::HysteresisController2::robot_  [private] | 
Pointer to robot structure.
Definition at line 103 of file hysteresis_controller2.h.
Definition at line 118 of file hysteresis_controller2.h.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 117 of file hysteresis_controller2.h.
| joint_qualification_controllers::HysteresisData2 joint_qualification_controllers::HysteresisController2::test_data_  [private] | 
Definition at line 100 of file hysteresis_controller2.h.
| double joint_qualification_controllers::HysteresisController2::timeout_  [private] | 
Definition at line 115 of file hysteresis_controller2.h.
Definition at line 109 of file hysteresis_controller2.h.
| double joint_qualification_controllers::HysteresisController2::velocity_  [private] | 
Velocity during the test.
Definition at line 105 of file hysteresis_controller2.h.
| controller::JointVelocityController* joint_qualification_controllers::HysteresisController2::velocity_controller_  [private] | 
The velocity controller for the hysteresis test.
Definition at line 104 of file hysteresis_controller2.h.