#include <ros/ros.h>#include <nodelet/nodelet.h>#include <ros/package.h>#include <actionlib/server/simple_action_server.h>#include <sensor_msgs/Image.h>#include <sensor_msgs/PointCloud2.h>#include <cob_perception_msgs/DetectionArray.h>#include <message_filters/subscriber.h>#include <message_filters/synchronizer.h>#include <message_filters/sync_policies/approximate_time.h>#include <image_transport/image_transport.h>#include <image_transport/subscriber_filter.h>#include <cob_people_detection/Recognition.h>#include <cob_people_detection/TrainContinuousAction.h>#include <cob_people_detection/TrainCaptureSampleAction.h>#include <cob_people_detection/RecognizeAction.h>#include <cob_people_detection/LoadAction.h>#include <cob_people_detection/SaveAction.h>#include <cob_people_detection/ShowAction.h>#include <opencv2/opencv.hpp>#include <cv_bridge/cv_bridge.h>#include <sensor_msgs/image_encodings.h>#include <pcl/point_types.h>#include <pcl_ros/point_cloud.h>#include "tinyxml.h"#include <boost/bind.hpp>#include <boost/thread/mutex.hpp>#include "boost/filesystem/operations.hpp"#include "boost/filesystem/convenience.hpp"#include "boost/filesystem/path.hpp"#include "cob_vision_ipa_utils/MathUtils.h"#include "cob_sensor_fusion/ColoredPointCloudSequence.h"#include "cob_people_detection/people_detector.h"#include <sstream>#include <string>#include <vector>#include <set>
Go to the source code of this file.
Classes | |
| class | ipa_PeopleDetector::CobFaceDetectionNodelet |
Namespaces | |
| namespace | ipa_PeopleDetector |
Typedefs | |
| typedef actionlib::SimpleActionServer < cob_people_detection::LoadAction > | ipa_PeopleDetector::LoadServer |
| typedef actionlib::SimpleActionServer < cob_people_detection::RecognizeAction > | ipa_PeopleDetector::RecognizeServer |
| typedef actionlib::SimpleActionServer < cob_people_detection::SaveAction > | ipa_PeopleDetector::SaveServer |
| typedef actionlib::SimpleActionServer < cob_people_detection::ShowAction > | ipa_PeopleDetector::ShowServer |
| typedef actionlib::SimpleActionServer < cob_people_detection::TrainCaptureSampleAction > | ipa_PeopleDetector::TrainCaptureSampleServer |
| typedef actionlib::SimpleActionServer < cob_people_detection::TrainContinuousAction > | ipa_PeopleDetector::TrainContinuousServer |