Public Member Functions | Private Member Functions | Private Attributes
cba_learner Class Reference

Object used to handle communication between other ROS nodes and CBA. More...

#include <cba.h>

List of all members.

Public Member Functions

 cba_learner ()
 Creates a cba_learner using optional ROS parameters.
void step ()
 Iterates once trough the CBA algorithm.
virtual ~cba_learner ()
 cba_learner destructor.

Private Member Functions

bool a_complete_callback (lfd_common::action_complete::Request &req, lfd_common::action_complete::Response &resp)
 a_complete service callback function
predictionclassify_state ()
 Used to classify the current state.
double conf_thresh (int l, int db)
 Retrieve the confidence threshold for the given label and decision boundary pair.
double nearest_neighbor ()
 Used to calculate the nearest neighbor to the current state.
void state_listener_callback (const lfd_common::state::ConstPtr &msg)
 state_listener topic callback function
void update_thresholds ()
 Update the distance and confidence thresholds.

Private Attributes

int a
ros::ServiceServer a_complete
bool action_complete
ros::Publisher add_point
ANNpointArray ann_data
bool autonomous_action
ros::Publisher change_point
ros::ServiceClient classify
std::vector< conf * > conf_thresholds
ros::ServiceClient correction
ros::ServiceClient demonstration
double dist_mult
double dist_thresh
ros::Publisher execute
int32_t * labels
int max_pts
ros::NodeHandle node
int pts
float * s
int s_size
float * sc
ros::Subscriber state_listener

Detailed Description

Object used to handle communication between other ROS nodes and CBA.

The cba_learner handles communication between the agent, human, and CBA via ROS. ROS nodes and services are created and maintained within this object.

Definition at line 75 of file cba.h.


Constructor & Destructor Documentation

Creates a cba_learner using optional ROS parameters.

Creates a cba_learner object that will allocate most of the necessary resources needed and initialize all ROS topics/services. Optional parameters can be supplied via ROS parameters to set the data set size and distance threshold multiplier.

Definition at line 25 of file cba.cpp.

cba_learner destructor.

Frees the resources used by the CBA learner.

Definition at line 56 of file cba.cpp.


Member Function Documentation

a_complete service callback function

Set the action complete flag to true and autonomous action flag to false. Furthermore, if the action completed was autonomous and a correction was given by the user, the model is updated appropriately.

Parameters:
reqthe request for the a_complete service
respthe response for the a_complete service; this does not contain any information for this service
Returns:
returns true once completed

Definition at line 364 of file cba.cpp.

Used to classify the current state.

Query the classifier for the label of the current state. If the communication to the classifier cannot be made, a label of -1 is given with negative infinity confidence.

Returns:
the prediction information for the current state

Definition at line 190 of file cba.cpp.

double cba_learner::conf_thresh ( int  l,
int  db 
) [private]

Retrieve the confidence threshold for the given label and decision boundary pair.

Find the confidence threshold for the given label and decision boundary pair. If no threshold value has been set for this pair yet, infinity is returned (the initial threshold).

Parameters:
lthe label value
dbthe decision boundary label value
Returns:
the confidence threshold for the given label and decision boundary pair

Definition at line 255 of file cba.cpp.

double cba_learner::nearest_neighbor ( ) [private]

Used to calculate the nearest neighbor to the current state.

Calculate and return the nearest neighbor distance to the current state using ANN. If no data points exist in the data set, infinity is returned.

Returns:
the nearest neighbor distance to the current state

Definition at line 223 of file cba.cpp.

state_listener topic callback function

Copies the given state vector into a global buffer. If this is the first call to this function, several buffer resources are allocated based on the size of the state vector.

Parameters:
msgthe current state vector of the agent

Definition at line 341 of file cba.cpp.

Iterates once trough the CBA algorithm.

Used to iterate once through the CBA algorithm. This loop will update the learner and handle any ROS messages/service requests that must be made.

Definition at line 72 of file cba.cpp.

void cba_learner::update_thresholds ( ) [private]

Update the distance and confidence thresholds.

Update the distance and confidence thresholds as defined by the CBA algorithm.

Definition at line 266 of file cba.cpp.


Member Data Documentation

int cba_learner::a [private]

the length of the state vector, maximum number of data points to allocate, current number of data points, and current action for the agent to execute

Definition at line 164 of file cba.h.

the a_complete service

Definition at line 161 of file cba.h.

Definition at line 165 of file cba.h.

Definition at line 158 of file cba.h.

ANNpointArray cba_learner::ann_data [private]

data points for ANN

Definition at line 169 of file cba.h.

if the action has been reported by the agent as finished and if the current action was executed autonomously

Definition at line 165 of file cba.h.

the execute, add_point, and change_point topics

Definition at line 158 of file cba.h.

Definition at line 160 of file cba.h.

std::vector<conf*> cba_learner::conf_thresholds [private]

confidence threshold values for action label and decision boundary pairs

Definition at line 167 of file cba.h.

Definition at line 160 of file cba.h.

the classify, correction, and demonstration services

Definition at line 160 of file cba.h.

double cba_learner::dist_mult [private]

the distance threshold value and distance threshold multiplier

Definition at line 166 of file cba.h.

double cba_learner::dist_thresh [private]

Definition at line 166 of file cba.h.

Definition at line 158 of file cba.h.

int32_t* cba_learner::labels [private]

labels for each entry in the data set

Definition at line 170 of file cba.h.

int cba_learner::max_pts [private]

Definition at line 164 of file cba.h.

a handle for this ROS node

Definition at line 156 of file cba.h.

int cba_learner::pts [private]

Definition at line 164 of file cba.h.

float* cba_learner::s [private]

Definition at line 163 of file cba.h.

int cba_learner::s_size [private]

Definition at line 164 of file cba.h.

float * cba_learner::sc [private]

the current state of CBA and the last confidence state

Definition at line 163 of file cba.h.

the state_listener topic

Definition at line 159 of file cba.h.


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


cba
Author(s): Russell Toris
autogenerated on Thu Jan 2 2014 11:23:56