#include <counterbalance_test_controller.h>
Public Types | |
enum | { STARTING, SETTLING, DITHERING, NEXT, DONE } |
Public Member Functions | |
CounterbalanceTestController () | |
bool | done () |
bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
Functional way to initialize. More... | |
bool | sendData () |
void | starting () |
void | update () |
Issues commands to the joint. Should be called at regular intervals. More... | |
~CounterbalanceTestController () | |
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 () |
Public Attributes | |
joint_qualification_controllers::CounterbalanceTestData | cb_test_data_ |
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_ |
Private Attributes | |
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::CounterbalanceTestData > > | cb_data_pub_ |
bool | data_sent_ |
int | dither_count_ |
int | dither_points_ |
controller::JointPositionController * | flex_controller_ |
control_toolbox::Dither * | flex_dither_ |
uint | flex_index_ |
pr2_mechanism_model::JointState * | flex_state_ |
ros::Time | initial_time_ |
controller::JointPositionController * | lift_controller_ |
control_toolbox::Dither * | lift_dither_ |
uint | lift_index_ |
pr2_mechanism_model::JointState * | lift_state_ |
pr2_mechanism_model::RobotState * | robot_ |
double | settle_time_ |
ros::Time | start_time_ |
int | starting_count_ |
int | state_ |
double | timeout_ |
Definition at line 63 of file counterbalance_test_controller.h.
anonymous enum |
Enumerator | |
---|---|
STARTING | |
SETTLING | |
DITHERING | |
NEXT | |
DONE |
Definition at line 67 of file counterbalance_test_controller.h.
CounterbalanceTestController::CounterbalanceTestController | ( | ) |
Definition at line 47 of file counterbalance_test_controller.cpp.
CounterbalanceTestController::~CounterbalanceTestController | ( | ) |
Definition at line 108 of file counterbalance_test_controller.cpp.
|
inline |
Definition at line 88 of file counterbalance_test_controller.h.
|
virtual |
Functional way to initialize.
*robot | The robot that is being controlled. |
&n | Node handle for parameters and services |
Implements pr2_controller_interface::Controller.
Definition at line 116 of file counterbalance_test_controller.cpp.
bool CounterbalanceTestController::sendData | ( | ) |
Definition at line 553 of file counterbalance_test_controller.cpp.
|
virtual |
Reimplemented from pr2_controller_interface::Controller.
Definition at line 435 of file counterbalance_test_controller.cpp.
|
virtual |
Issues commands to the joint. Should be called at regular intervals.
Implements pr2_controller_interface::Controller.
Definition at line 440 of file counterbalance_test_controller.cpp.
|
private |
Definition at line 122 of file counterbalance_test_controller.h.
joint_qualification_controllers::CounterbalanceTestData joint_qualification_controllers::CounterbalanceTestController::cb_test_data_ |
Definition at line 90 of file counterbalance_test_controller.h.
|
private |
Definition at line 120 of file counterbalance_test_controller.h.
|
private |
Definition at line 115 of file counterbalance_test_controller.h.
|
private |
Definition at line 112 of file counterbalance_test_controller.h.
|
private |
Definition at line 97 of file counterbalance_test_controller.h.
|
private |
Definition at line 94 of file counterbalance_test_controller.h.
|
private |
Definition at line 118 of file counterbalance_test_controller.h.
|
private |
Definition at line 99 of file counterbalance_test_controller.h.
|
private |
Definition at line 108 of file counterbalance_test_controller.h.
|
private |
Definition at line 96 of file counterbalance_test_controller.h.
|
private |
Definition at line 93 of file counterbalance_test_controller.h.
|
private |
Definition at line 117 of file counterbalance_test_controller.h.
|
private |
Definition at line 100 of file counterbalance_test_controller.h.
|
private |
Definition at line 102 of file counterbalance_test_controller.h.
|
private |
Definition at line 110 of file counterbalance_test_controller.h.
|
private |
Definition at line 111 of file counterbalance_test_controller.h.
|
private |
Definition at line 104 of file counterbalance_test_controller.h.
|
private |
Definition at line 106 of file counterbalance_test_controller.h.
|
private |
Definition at line 113 of file counterbalance_test_controller.h.