int main(){ FaceRec fr; fr.train("/home/kevin/workspace/opencv/csv.ext"); vector<int> labels, predictLabels; predictLabels = fr.predict("/home/kevin/workspace/opencv/test.ext", labels); for(int i = 0; i < labels.size(); i++){ cout << "Actual result: " << labels[i] << endl; cout << "Predict result: " << predictLabels[i] << endl; } return 0; }
void executeCB(const corobot_face_recognition::FaceRecognitionGoalConstPtr &goal) { if (_as.isPreemptRequested() || !ros::ok()) { ROS_INFO("%s: Preempted", _action_name.c_str()); // set the action state to preempted _as.setPreempted(); // success = false; // break; } // helper variables ros::Rate r(60); bool success = true; _goal_id = goal->order_id; _goal_argument = goal->order_argument; _feedback.order_id = _goal_id; _feedback.names.clear(); _feedback.confidence.clear(); _result.order_id = _goal_id; _result.names.clear(); _result.confidence.clear(); // publish info to the console for the user ROS_INFO("%s: Executing. order_id: %i, order_argument: %s ", _action_name.c_str(), _goal_id, _goal_argument.c_str()); switch (_goal_id) { // RECOGNIZE ONCE case 0: // cout << "case 0" << endl; // _fr = new FaceRec(true); _image_sub = _it.subscribe("/usb_cam/image_raw", 1, &FaceRecognition::recognizeCb, this); while( _as.isActive() && !_as.isPreemptRequested() && !ros::isShuttingDown() ) r.sleep(); break; // RECOGNIZE CONTINUOUSLY case 1: //cout << "case 1" << endl; // _fr = new FaceRec(true); _image_sub = _it.subscribe("/usb_cam/image_raw", 1, &FaceRecognition::recognizeCb, this); while( _as.isActive() && !_as.isPreemptRequested() && !ros::isShuttingDown() ) r.sleep(); break; // ADD TRAINING IMAGES case 2: // cout << "case 2" << endl; _fc = new FaceImgCapturer(_goal_argument); _image_sub = _it.subscribe("/usb_cam/image_raw", 1, &FaceRecognition::addTrainingImagesCb, this); while( _as.isActive() && !_as.isPreemptRequested() && !ros::isShuttingDown() ) r.sleep(); break; // TRAIN DATABASE case 3: // call training function and check if successful // bool trainingSuccessful = true; // cout << "case 3" << endl; _fr->train(_preprocessing); if (true) _as.setSucceeded(_result); else _as.setAborted(_result); break; // STOP case 4: if (_as.isActive()) { _as.setPreempted(); // _image_sub.shutdown(); } break; // EXIT case 5: // cout << "case 4" << endl; ROS_INFO("%s: Exit request.", _action_name.c_str()); _as.setSucceeded(_result); r.sleep(); ros::shutdown(); break; } }