#include <wrist_difference_controller.h>

Public Types | |
| enum | { STARTING, LEFT, RIGHT, ANALYZING, DONE } |
Public Member Functions | |
| void | analysis () |
| Perform the test analysis. More... | |
| bool | done () |
| 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... | |
| WristDifferenceController () | |
| ~WristDifferenceController () | |
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 Attributes | |
| bool | data_sent_ |
| controller::JointPositionController * | flex_controller_ |
| pr2_mechanism_model::JointState * | flex_joint_ |
| double | flex_position_ |
| double | initial_position_ |
| ros::Time | initial_time_ |
| int | left_count_ |
| int | right_count_ |
| pr2_mechanism_model::RobotState * | robot_ |
| controller::JointVelocityController * | roll_controller_ |
| pr2_mechanism_model::JointState * | roll_joint_ |
| double | roll_velocity_ |
| double | sd_max_ |
| int | start_count_ |
| int | starting_count |
| int | state_ |
| double | timeout_ |
| double | tolerance_ |
| boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::WristDiffData > > | wrist_data_pub_ |
| joint_qualification_controllers::WristDiffData | wrist_test_data_ |
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_ |
Definition at line 62 of file wrist_difference_controller.h.
| anonymous enum |
| Enumerator | |
|---|---|
| STARTING | |
| LEFT | |
| RIGHT | |
| ANALYZING | |
| DONE | |
Definition at line 66 of file wrist_difference_controller.h.
| WristDifferenceController::WristDifferenceController | ( | ) |
Definition at line 46 of file wrist_difference_controller.cpp.
| WristDifferenceController::~WristDifferenceController | ( | ) |
Definition at line 101 of file wrist_difference_controller.cpp.
| void WristDifferenceController::analysis | ( | ) |
Perform the test analysis.
Definition at line 346 of file wrist_difference_controller.cpp.
|
inline |
Definition at line 98 of file wrist_difference_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 107 of file wrist_difference_controller.cpp.
| bool WristDifferenceController::sendData | ( | ) |
Sends data, returns true if sent.
Definition at line 376 of file wrist_difference_controller.cpp.
|
virtual |
Called when controller is started.
Reimplemented from pr2_controller_interface::Controller.
Definition at line 248 of file wrist_difference_controller.cpp.
|
virtual |
Issues commands to the joint to perform hysteresis test.
Implements pr2_controller_interface::Controller.
Definition at line 256 of file wrist_difference_controller.cpp.
|
private |
Definition at line 123 of file wrist_difference_controller.h.
|
private |
Definition at line 107 of file wrist_difference_controller.h.
|
private |
Definition at line 104 of file wrist_difference_controller.h.
|
private |
Definition at line 110 of file wrist_difference_controller.h.
|
private |
Definition at line 113 of file wrist_difference_controller.h.
|
private |
Start time of the test.
Definition at line 112 of file wrist_difference_controller.h.
|
private |
Definition at line 114 of file wrist_difference_controller.h.
|
private |
Definition at line 114 of file wrist_difference_controller.h.
|
private |
Definition at line 106 of file wrist_difference_controller.h.
|
private |
Definition at line 108 of file wrist_difference_controller.h.
|
private |
Definition at line 105 of file wrist_difference_controller.h.
|
private |
Velocity during the test.
Definition at line 111 of file wrist_difference_controller.h.
|
private |
Definition at line 118 of file wrist_difference_controller.h.
|
private |
Definition at line 114 of file wrist_difference_controller.h.
|
private |
Definition at line 121 of file wrist_difference_controller.h.
|
private |
Definition at line 120 of file wrist_difference_controller.h.
|
private |
Definition at line 116 of file wrist_difference_controller.h.
|
private |
Definition at line 117 of file wrist_difference_controller.h.
|
private |
Definition at line 126 of file wrist_difference_controller.h.
|
private |
Definition at line 102 of file wrist_difference_controller.h.