[Documentation] [TitleIndex] [WordIndex

object_recognition: barcode_from_picture | bigg_detector | dpm_detector | fast_template_detector | fiducial | rein | shape_detection | stereo_object_recognition | textured_object_detection | tod | tod_converter | tod_detecting | tod_stub | tod_test | tod_training | vfh_cluster_classifier

Package Summary

The Recognition Infrastructure (ReIn) is a software library that facilitates rapid development for 2D/3D object and scene recognition. ReIn can create different computational graphs from its various modules by combining them together in parallel or in a cascade fashion. Examples include: object detectors, pose estimators, attention operators, etc. The backbone of ReIn is supported by OpenCV (http://opencv.willowgarage.com/) and PCL (http://pcl.ros.org).

Overview

The rein (REcognition INfrastructure) package contains a framework that is supposed to make the addition of new vision algorithms that work on the PR2 much simpler. The recognition infrastructure contains the following main components:

Framework design

The framework is split in two main components, a ROS-independent one containing the vision algorithms doing the actual work and one that contains ROS wrappers around those algorithms and exposes them as nodelets. Using nodelets allows the algorithms to be dynamically (un)loadable and offers optimizations for zero-copy cost of Boost shared_ptr messages between different nodelets that are part of the same process.

Algorithms API

This part of the package contains the ROS-independent algorithms. The framework has base classes for attention operators, detectors and pose estimators that are wrapped by the ROS nodelets. Each new algorithm that is added to the pipeline will have to inherit from one of these classes.

AttentionOperator

The rein::AttentionOperator represents the base class for attention operators. An attention operator takes as input an image and/or point cloud to compute interesting regions in the image. The output of an attention operator is a list of regions of interest (ROI) and masks. The rein::AttentionOperator has the following pure virtual methods which have to be implemented by a subclass.

   1 virtual void run() = 0; // runs the attention operator
   2 virtual std::string getName() = 0; // returns the (unique) name of the attention operator
   3 

An attention operator also has the following getter/setter methods.

   1 void setImage(const cv::Mat& image);  // input image
   2 void setPointCloud(const sensor_msgs::PointCloud2ConstPtr point_cloud); // input point cloud
   3 MaskArray getMasks() const; // output masks
   4 

The ROS nodelet will automatically call these getter/setter methods to set the input image/point cloud and to get the resulting masks after the attention operator has run.

Detector

The rein::Detector represents the base class for detectors. A detector takes as input an image and/or point cloud and/or some regions of interest and detects the objects present in the image/point cloud. The output of a detector is a list of detections (rein/Detection).The rein::Detector has the following pure virtual methods which have to be implemented by a subclass.

   1 virtual void detect() = 0; // runs the detector
   2 virtual std::string getName() = 0; // returns the (unique) name of the detector
   3 virtual void loadModels(const std::vector<std::string>& models) = 0; // loads the list of pre-trained models that will be detected in the input image
   4 

A detector also has the following getter/setter methods. These are automatically called by the ROS wrapper.

   1 void setImage(const cv::Mat& image);  // input image
   2 void setMasks(const MaskArrayConstPtr& masks); // masks (rois)
   3 void setPointCloud(const sensor_msgs::PointCloud2ConstPtr point_cloud); // input point cloud
   4 DetectionArray getDetections() const; // output detections
   5 

PoseEstimator

The rein::PoseEstimator represents the base class for pose estimator algorithms. A pose estimator takes as input an image and/or point cloud and/or a list of detections and computes/refines the poses of the objects in the image/point cloud. The output of a pose estimator is a list of poses. The rein::PoseEstimator has the following pure virtual methods which have to be implemented by a subclass.

   1 virtual void run() = 0; // runs the attention operator
   2 virtual std::string getName() = 0; // returns the (unique) name of the pose estimator
   3 

A pose estimator also has the following getter/setter methods. These are automatically called by the ROS wrapper.

   1 void setImage(const cv::Mat& image);  // input image
   2 void setDetections(const DetectionArrayConstPtr& detections) // input detections
   3 void setPointCloud(const sensor_msgs::PointCloud2ConstPtr point_cloud); // input point cloud
   4 geometry_msgs::PoseArray getPoses() const; // output poses
   5 

Trainable

The rein::Trainable is an interface that must be implemented by all the algorithms (usually detectors) that support online training. The interface contains the following pure virtual methods:

   1 void startTraining(const std::string& name) = 0; // called when training of a new object model starts
   2 void trainInstance(const std::string& name, const TrainingData& data) = 0; // called for each training instance
   3 void endTraining(const std::string& name) = 0; // called when training is finished, usually to save the model
   4 

ModelStorage

The rein::ModelStorage is an interface that different algorithms can use to persist models. It may have several implementations, one of them being rein::ModelDatabase, that uses a database (postgresql and sqlite3 are currently supported) for persistence. The interface has the following methods:

   1 virtual void saveModel(const std::string& name, const std::string& detector, const std::string& model_blob) = 0;
   2 virtual bool loadModel(const std::string& name, const std::string& detector, std::string& model_blob) = 0;
   3 virtual bool getModelList(const std::string& detector, std::vector<std::string>& model_list) = 0;
   4 

ROS Nodelets

The ROS nodelets wrap the ROS-independent algorithms and take care of subscribing to topics, synchronizing the messages on the input topics, publishing the results and setting the algorithm parameters using the dynamic reconfigure framework. Each algorithm will have a nodelet wrapper. Several base nodelet classes are provided for each type of algorithm presented above, which simplifies the process of writing new nodelets.

AttentionOperatorNodelet

Subscribed Topics

~/image (sensor_msgs/Image)

~/point_cloud (sensor_msgs/PointCloud2)

Published Topics

~/masks (rein/MaskArray)

~/rois (rein/RectArray)

Parameters

~/use_image (bool, default: True)

~/use_point_cloud (bool, default: False) ~/approximate_sync (bool, default: False) ~/queue_size (int, default: 10)

DetectorNodelet

Subscribed Topics

~/image (sensor_msgs/Image)

~/masks (rein/MaskArray) ~/point_cloud (sensor_msgs/PointCloud2)

Published Topics

~/detections (rein/DetectionArray)

~/masks (rein/MaskArray) ~/poses (geometry_msgs/PoseArray)

Parameters

~/use_image (bool, default: True)

~/use_point_cloud (bool, default: False) ~/use_masks (bool, default: False) ~/queue_size (int, default: 10)

PoseEstimatorNodelet

Subscribed Topics

~/image (sensor_msgs/Image)

~/point_cloud (sensor_msgs/PointCloud2) ~/detections (rein/DetectionArray)

Published Topics

~/poses (geometry_msgs/PoseArray)

Parameters

~/use_image (bool, default: True)

~/use_point_cloud (bool, default: False) ~/use_detection (bool, default: False) ~/queue_size (int, default: 10)

TrainerServer

The rein::TrainerServer class is a 'server' class that when instantiated by a node/nodelet advertises three services which can be used to train a new detector. The detector to be trained must implement the rein::Trainable interface and is passed as a parameter to the constructor of TrainerServer.

   1 boost::shared_ptr<Trainable> trainabale_ptr = boost::static_pointer_cast<Trainable>(detector);
   2 boost::shared_ptr<TrainerServer> trainer_server = boost::make_shared<TrainerServer>(boost::ref(nh), boost::ref(trainabale_ptr));
   3 

Services advertised

~/start_training (rein/StartTraining)

~/train_instance (rein/TrainInstance) ~/end_training (rein/EndTraining)


2011-11-19 12:32