Hystersis Controller. More...
#include <hysteresis_controller.h>
Public Types | |
| enum | { STOPPED, MOVING_HOME, MOVING_UP, MOVING_DOWN, ANALYZING, DONE } |
Public Member Functions | |
| void | analysis () |
| Perform the test analysis. | |
| bool | done () |
| HysteresisController () | |
| 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. | |
| ~HysteresisController () | |
Private Member Functions | |
| bool | turn () |
Private Attributes | |
| bool | complete |
| bool | data_sent_ |
| int | down_count_ |
| boost::scoped_ptr < realtime_tools::RealtimePublisher < joint_qualification_controllers::HysteresisData > > | hyst_pub_ |
| double | initial_position_ |
| ros::Time | initial_time_ |
| pr2_mechanism_model::JointState * | joint_ |
| double | last_publish_time_ |
| double | max_effort_ |
| pr2_mechanism_model::RobotState * | robot_ |
| int | starting_count_ |
| int | state_ |
| joint_qualification_controllers::HysteresisData | 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 57 of file hysteresis_controller.h.
| anonymous enum |
Definition at line 58 of file hysteresis_controller.h.
| HysteresisController::HysteresisController | ( | ) |
Definition at line 48 of file hysteresis_controller.cpp.
| HysteresisController::~HysteresisController | ( | ) |
Definition at line 92 of file hysteresis_controller.cpp.
| void HysteresisController::analysis | ( | ) |
Perform the test analysis.
Definition at line 318 of file hysteresis_controller.cpp.
| bool joint_qualification_controllers::HysteresisController::done | ( | ) | [inline] |
Definition at line 90 of file hysteresis_controller.h.
| bool HysteresisController::init | ( | pr2_mechanism_model::RobotState * | robot, | |
| ros::NodeHandle & | n | |||
| ) |
Functional way to initialize.
| *robot | The robot that is being controlled. | |
| &n | NodeHandle of mechanism control |
Definition at line 97 of file hysteresis_controller.cpp.
| bool HysteresisController::sendData | ( | ) |
Sends data, returns true if sent.
Definition at line 339 of file hysteresis_controller.cpp.
| void HysteresisController::starting | ( | ) |
Called when controller is started.
Definition at line 212 of file hysteresis_controller.cpp.
| bool HysteresisController::turn | ( | ) | [private] |
Definition at line 301 of file hysteresis_controller.cpp.
| void HysteresisController::update | ( | ) |
Issues commands to the joint to perform hysteresis test.
Definition at line 220 of file hysteresis_controller.cpp.
Definition at line 104 of file hysteresis_controller.h.
Definition at line 111 of file hysteresis_controller.h.
Definition at line 103 of file hysteresis_controller.h.
boost::scoped_ptr<realtime_tools::RealtimePublisher<joint_qualification_controllers::HysteresisData> > joint_qualification_controllers::HysteresisController::hyst_pub_ [private] |
Definition at line 116 of file hysteresis_controller.h.
Definition at line 102 of file hysteresis_controller.h.
ros::Time joint_qualification_controllers::HysteresisController::initial_time_ [private] |
Start time of the test.
Definition at line 101 of file hysteresis_controller.h.
pr2_mechanism_model::JointState* joint_qualification_controllers::HysteresisController::joint_ [private] |
Joint we're controlling.
Definition at line 96 of file hysteresis_controller.h.
Definition at line 113 of file hysteresis_controller.h.
double joint_qualification_controllers::HysteresisController::max_effort_ [private] |
Maximum allowable effort.
Definition at line 100 of file hysteresis_controller.h.
pr2_mechanism_model::RobotState* joint_qualification_controllers::HysteresisController::robot_ [private] |
Pointer to robot structure.
Definition at line 97 of file hysteresis_controller.h.
Definition at line 109 of file hysteresis_controller.h.
Definition at line 108 of file hysteresis_controller.h.
joint_qualification_controllers::HysteresisData joint_qualification_controllers::HysteresisController::test_data_ [private] |
Definition at line 94 of file hysteresis_controller.h.
double joint_qualification_controllers::HysteresisController::timeout_ [private] |
Definition at line 106 of file hysteresis_controller.h.
Definition at line 103 of file hysteresis_controller.h.
double joint_qualification_controllers::HysteresisController::velocity_ [private] |
Velocity during the test.
Definition at line 99 of file hysteresis_controller.h.
controller::JointVelocityController* joint_qualification_controllers::HysteresisController::velocity_controller_ [private] |
The velocity controller for the hysteresis test.
Definition at line 98 of file hysteresis_controller.h.