joint_qualification_controllers::CheckoutController Class Reference

Checkout Controller checks state of PR2 mechanism. More...

#include <checkout_controller.h>

List of all members.

Public Types

enum  { STARTING, LISTENING, ANALYZING, DONE }

Public Member Functions

void analysis (double time, bool timeout=false)
 Perform the test analysis.
 CheckoutController ()
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 or restarted.
void update ()
 Checks joint, actuator status for calibrated and enabled.
 ~CheckoutController ()

Private Member Functions

bool done ()

Private Attributes

int actuator_count_
bool data_sent_
ros::Time initial_time_
int joint_count_
double last_publish_time_
pr2_mechanism_model::RobotState * robot_
joint_qualification_controllers::RobotData robot_data_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< joint_qualification_controllers::RobotData > > 
robot_data_pub_
int state_
double timeout_

Detailed Description

Checkout Controller checks state of PR2 mechanism.

Verifies that all robot joints are calibrated. Publishes state of actuators and joints.

Definition at line 70 of file checkout_controller.h.


Member Enumeration Documentation

anonymous enum
Enumerator:
STARTING 
LISTENING 
ANALYZING 
DONE 

Definition at line 74 of file checkout_controller.h.


Constructor & Destructor Documentation

CheckoutController::CheckoutController (  ) 

Definition at line 45 of file checkout_controller.cpp.

joint_qualification_controllers::CheckoutController::~CheckoutController (  )  [inline]

Definition at line 77 of file checkout_controller.h.


Member Function Documentation

void CheckoutController::analysis ( double  time,
bool  timeout = false 
)

Perform the test analysis.

Definition at line 267 of file checkout_controller.cpp.

bool joint_qualification_controllers::CheckoutController::done (  )  [inline, private]

Definition at line 120 of file checkout_controller.h.

bool CheckoutController::init ( pr2_mechanism_model::RobotState *  robot,
ros::NodeHandle &  n 
)

Functional way to initialize.

Parameters:
*robot The robot that is being controlled.
&n NodeHandle of mechanism control

Definition at line 61 of file checkout_controller.cpp.

bool CheckoutController::sendData (  ) 

Sends data, returns true if sent.

Definition at line 232 of file checkout_controller.cpp.

void CheckoutController::starting (  ) 

Called when controller is started or restarted.

Definition at line 132 of file checkout_controller.cpp.

void CheckoutController::update (  ) 

Checks joint, actuator status for calibrated and enabled.

Definition at line 139 of file checkout_controller.cpp.


Member Data Documentation

Definition at line 118 of file checkout_controller.h.

Definition at line 122 of file checkout_controller.h.

Start time of the test.

Definition at line 109 of file checkout_controller.h.

Definition at line 117 of file checkout_controller.h.

Definition at line 124 of file checkout_controller.h.

pr2_mechanism_model::RobotState* joint_qualification_controllers::CheckoutController::robot_ [private]

Definition at line 108 of file checkout_controller.h.

Definition at line 113 of file checkout_controller.h.

Definition at line 128 of file checkout_controller.h.

Definition at line 115 of file checkout_controller.h.

Definition at line 111 of file checkout_controller.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Defines


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Fri Jan 11 09:54:10 2013