Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
joint_qualification_controllers::HysteresisController Class Reference

Hystersis Controller. More...

#include <hysteresis_controller.h>

Inheritance diagram for joint_qualification_controllers::HysteresisController:
Inheritance graph
[legend]

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::JointStatejoint_
 
double last_publish_time_
 
double max_effort_
 
pr2_mechanism_model::RobotStaterobot_
 
int starting_count_
 
int state_
 
joint_qualification_controllers::HysteresisData test_data_
 
double timeout_
 
int up_count_
 
double velocity_
 
controller::JointVelocityControllervelocity_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_
 

Detailed Description

Hystersis Controller.

This tests the hysteresis of a joint using a velocity controller.

Definition at line 60 of file hysteresis_controller.h.

Member Enumeration Documentation

anonymous enum
Enumerator
STOPPED 
MOVING_HOME 
MOVING_UP 
MOVING_DOWN 
ANALYZING 
DONE 

Definition at line 64 of file hysteresis_controller.h.

Constructor & Destructor Documentation

HysteresisController::HysteresisController ( )

Definition at line 47 of file hysteresis_controller.cpp.

HysteresisController::~HysteresisController ( )

Definition at line 91 of file hysteresis_controller.cpp.

Member Function Documentation

void HysteresisController::analysis ( )

Perform the test analysis.

Definition at line 317 of file hysteresis_controller.cpp.

bool joint_qualification_controllers::HysteresisController::done ( )
inline

Definition at line 96 of file hysteresis_controller.h.

bool HysteresisController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
virtual

Functional way to initialize.

Parameters
*robotThe robot that is being controlled.
&nNodeHandle 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.

void HysteresisController::starting ( )
virtual

Called when controller is started.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 211 of file hysteresis_controller.cpp.

bool HysteresisController::turn ( )
private

Definition at line 300 of file hysteresis_controller.cpp.

void HysteresisController::update ( void  )
virtual

Issues commands to the joint to perform hysteresis test.

Implements pr2_controller_interface::Controller.

Definition at line 219 of file hysteresis_controller.cpp.

Member Data Documentation

bool joint_qualification_controllers::HysteresisController::complete
private

Definition at line 110 of file hysteresis_controller.h.

bool joint_qualification_controllers::HysteresisController::data_sent_
private

Definition at line 117 of file hysteresis_controller.h.

int joint_qualification_controllers::HysteresisController::down_count_
private

Definition at line 109 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 122 of file hysteresis_controller.h.

double joint_qualification_controllers::HysteresisController::initial_position_
private

Definition at line 108 of file hysteresis_controller.h.

ros::Time joint_qualification_controllers::HysteresisController::initial_time_
private

Start time of the test.

Definition at line 107 of file hysteresis_controller.h.

pr2_mechanism_model::JointState* joint_qualification_controllers::HysteresisController::joint_
private

Joint we're controlling.

Definition at line 102 of file hysteresis_controller.h.

double joint_qualification_controllers::HysteresisController::last_publish_time_
private

Definition at line 119 of file hysteresis_controller.h.

double joint_qualification_controllers::HysteresisController::max_effort_
private

Maximum allowable effort.

Definition at line 106 of file hysteresis_controller.h.

pr2_mechanism_model::RobotState* joint_qualification_controllers::HysteresisController::robot_
private

Pointer to robot structure.

Definition at line 103 of file hysteresis_controller.h.

int joint_qualification_controllers::HysteresisController::starting_count_
private

Definition at line 115 of file hysteresis_controller.h.

int joint_qualification_controllers::HysteresisController::state_
private

Definition at line 114 of file hysteresis_controller.h.

joint_qualification_controllers::HysteresisData joint_qualification_controllers::HysteresisController::test_data_
private

Definition at line 100 of file hysteresis_controller.h.

double joint_qualification_controllers::HysteresisController::timeout_
private

Definition at line 112 of file hysteresis_controller.h.

int joint_qualification_controllers::HysteresisController::up_count_
private

Definition at line 109 of file hysteresis_controller.h.

double joint_qualification_controllers::HysteresisController::velocity_
private

Velocity during the test.

Definition at line 105 of file hysteresis_controller.h.

controller::JointVelocityController* joint_qualification_controllers::HysteresisController::velocity_controller_
private

The velocity controller for the hysteresis test.

Definition at line 104 of file hysteresis_controller.h.


The documentation for this class was generated from the following files:


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Wed Jan 6 2021 03:39:12