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. More... | |
bool | done () |
HysteresisController () | |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
Functional way to initialize. More... | |
bool | sendData () |
Sends data, returns true if sent. More... | |
void | starting () |
Called when controller is started. More... | |
void | update () |
Issues commands to the joint to perform hysteresis test. More... | |
~HysteresisController () | |
Public Member Functions inherited from pr2_controller_interface::Controller | |
Controller () | |
bool | getController (const std::string &name, int sched, ControllerType *&c) |
bool | initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
bool | isRunning () |
void | starting (const ros::Time &time) |
bool | startRequest () |
void | stopping (const ros::Time &time) |
virtual void | stopping () |
bool | stopRequest () |
void | update (const ros::Time &time, const ros::Duration &period) |
void | updateRequest () |
virtual | ~Controller () |
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_ |
Additional Inherited Members | |
Public Attributes inherited from pr2_controller_interface::Controller | |
std::vector< std::string > | after_list_ |
AFTER_ME | |
std::vector< std::string > | before_list_ |
BEFORE_ME | |
CONSTRUCTED | |
INITIALIZED | |
RUNNING | |
enum pr2_controller_interface::Controller:: { ... } | state_ |
Hystersis Controller.
This tests the hysteresis of a joint using a velocity controller.
Definition at line 60 of file hysteresis_controller.h.
anonymous enum |
Enumerator | |
---|---|
STOPPED | |
MOVING_HOME | |
MOVING_UP | |
MOVING_DOWN | |
ANALYZING | |
DONE |
Definition at line 64 of file hysteresis_controller.h.
HysteresisController::HysteresisController | ( | ) |
Definition at line 47 of file hysteresis_controller.cpp.
HysteresisController::~HysteresisController | ( | ) |
Definition at line 91 of file hysteresis_controller.cpp.
void HysteresisController::analysis | ( | ) |
Perform the test analysis.
Definition at line 317 of file hysteresis_controller.cpp.
|
inline |
Definition at line 96 of file hysteresis_controller.h.
|
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 96 of file hysteresis_controller.cpp.
bool HysteresisController::sendData | ( | ) |
Sends data, returns true if sent.
Definition at line 338 of file hysteresis_controller.cpp.
|
virtual |
Called when controller is started.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 211 of file hysteresis_controller.cpp.
|
private |
Definition at line 300 of file hysteresis_controller.cpp.
|
virtual |
Issues commands to the joint to perform hysteresis test.
Implements pr2_controller_interface::Controller.
Definition at line 219 of file hysteresis_controller.cpp.
|
private |
Definition at line 110 of file hysteresis_controller.h.
|
private |
Definition at line 117 of file hysteresis_controller.h.
|
private |
Definition at line 109 of file hysteresis_controller.h.
|
private |
Definition at line 122 of file hysteresis_controller.h.
|
private |
Definition at line 108 of file hysteresis_controller.h.
|
private |
Start time of the test.
Definition at line 107 of file hysteresis_controller.h.
|
private |
Joint we're controlling.
Definition at line 102 of file hysteresis_controller.h.
|
private |
Definition at line 119 of file hysteresis_controller.h.
|
private |
Maximum allowable effort.
Definition at line 106 of file hysteresis_controller.h.
|
private |
Pointer to robot structure.
Definition at line 103 of file hysteresis_controller.h.
|
private |
Definition at line 115 of file hysteresis_controller.h.
|
private |
Definition at line 114 of file hysteresis_controller.h.
|
private |
Definition at line 100 of file hysteresis_controller.h.
|
private |
Definition at line 112 of file hysteresis_controller.h.
|
private |
Definition at line 109 of file hysteresis_controller.h.
|
private |
Velocity during the test.
Definition at line 105 of file hysteresis_controller.h.
|
private |
The velocity controller for the hysteresis test.
Definition at line 104 of file hysteresis_controller.h.