Public Member Functions | |
double | computeFacePositionDistance (const cob_perception_msgs::Detection &previous_detection, const cob_perception_msgs::Detection ¤t_detection) |
void | eval () |
void | print_result () |
void | recognitionCallback (const cob_perception_msgs::DetectionArray::ConstPtr &face_position_msg_in) |
checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive | |
void | trackingCallback (const cob_perception_msgs::DetectionArray::ConstPtr &face_position_msg_in) |
checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive | |
TrackingEvalNode (ros::NodeHandle nh) | |
~TrackingEvalNode () | |
Public Attributes | |
int | correct_recognitions_ |
int | correct_trackings_ |
int | error_out_ |
EvalObj | eval_rec_ |
EvalObj | eval_track_ |
std::string | gt_name_ |
ros::NodeHandle | node_handle_ |
bool | rec_rec |
bool | rec_track |
ros::Subscriber | recognition_subscriber_ |
int | total_comparisons_ |
int | tracking_decline_ |
int | tracking_improvement_ |
ros::Subscriber | tracking_subscriber_ |
Definition at line 200 of file tracking_eval_node.cpp.
TrackingEvalNode::TrackingEvalNode | ( | ros::NodeHandle | nh | ) | [inline] |
Definition at line 221 of file tracking_eval_node.cpp.
TrackingEvalNode::~TrackingEvalNode | ( | ) | [inline] |
Definition at line 237 of file tracking_eval_node.cpp.
double TrackingEvalNode::computeFacePositionDistance | ( | const cob_perception_msgs::Detection & | previous_detection, |
const cob_perception_msgs::Detection & | current_detection | ||
) | [inline] |
Definition at line 241 of file tracking_eval_node.cpp.
void TrackingEvalNode::eval | ( | ) | [inline] |
Definition at line 298 of file tracking_eval_node.cpp.
void TrackingEvalNode::print_result | ( | ) | [inline] |
Definition at line 329 of file tracking_eval_node.cpp.
void TrackingEvalNode::recognitionCallback | ( | const cob_perception_msgs::DetectionArray::ConstPtr & | face_position_msg_in | ) | [inline] |
checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive
Definition at line 276 of file tracking_eval_node.cpp.
void TrackingEvalNode::trackingCallback | ( | const cob_perception_msgs::DetectionArray::ConstPtr & | face_position_msg_in | ) | [inline] |
checks the detected faces from the input topic against the people segmentation and outputs faces if both are positive
Definition at line 254 of file tracking_eval_node.cpp.
Definition at line 211 of file tracking_eval_node.cpp.
Definition at line 210 of file tracking_eval_node.cpp.
Definition at line 215 of file tracking_eval_node.cpp.
Definition at line 204 of file tracking_eval_node.cpp.
Definition at line 205 of file tracking_eval_node.cpp.
std::string TrackingEvalNode::gt_name_ |
Definition at line 208 of file tracking_eval_node.cpp.
Definition at line 219 of file tracking_eval_node.cpp.
Definition at line 207 of file tracking_eval_node.cpp.
Definition at line 206 of file tracking_eval_node.cpp.
Definition at line 217 of file tracking_eval_node.cpp.
Definition at line 212 of file tracking_eval_node.cpp.
Definition at line 214 of file tracking_eval_node.cpp.
Definition at line 213 of file tracking_eval_node.cpp.
Definition at line 218 of file tracking_eval_node.cpp.