Object used to handle communication between other ROS nodes and CBA. More...
#include <cba.h>
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 | |
prediction * | classify_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 |
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.
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.
cba_learner::~cba_learner | ( | ) | [virtual] |
cba_learner destructor.
Frees the resources used by the CBA learner.
bool cba_learner::a_complete_callback | ( | lfd_common::action_complete::Request & | req, |
lfd_common::action_complete::Response & | resp | ||
) | [private] |
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.
req | the request for the a_complete service |
resp | the response for the a_complete service; this does not contain any information for this service |
prediction * cba_learner::classify_state | ( | ) | [private] |
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.
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).
l | the label value |
db | the decision boundary label value |
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.
void cba_learner::state_listener_callback | ( | const lfd_common::state::ConstPtr & | msg | ) | [private] |
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.
msg | the current state vector of the agent |
void cba_learner::step | ( | ) |
void cba_learner::update_thresholds | ( | ) | [private] |
int cba_learner::a [private] |
ros::ServiceServer cba_learner::a_complete [private] |
bool cba_learner::action_complete [private] |
ros::Publisher cba_learner::add_point [private] |
ANNpointArray cba_learner::ann_data [private] |
bool cba_learner::autonomous_action [private] |
ros::Publisher cba_learner::change_point [private] |
ros::ServiceClient cba_learner::classify [private] |
std::vector<conf*> cba_learner::conf_thresholds [private] |
ros::ServiceClient cba_learner::correction [private] |
ros::ServiceClient cba_learner::demonstration [private] |
double cba_learner::dist_mult [private] |
double cba_learner::dist_thresh [private] |
ros::Publisher cba_learner::execute [private] |
int32_t* cba_learner::labels [private] |
int cba_learner::max_pts [private] |
ros::NodeHandle cba_learner::node [private] |
int cba_learner::pts [private] |
float* cba_learner::s [private] |
int cba_learner::s_size [private] |
float * cba_learner::sc [private] |
ros::Subscriber cba_learner::state_listener [private] |