Main vision processing object. More...
#include <processor.h>
Public Member Functions | |
processor () | |
~processor () | |
Private Member Functions | |
void | accuracy () |
void | cloud_cback (const sensor_msgs::PointCloud2::ConstPtr &pc) |
void | feed_cback (const sensor_msgs::Image::ConstPtr &img) |
std::vector< float > | get_feature_vector (cv::Mat const src) |
std::vector< cv::RotatedRect > | segment (cv::Mat const src) |
void | smooth (cv::RotatedRect r) |
std::vector< cv::Mat > | split_image (cv::Mat const src, std::vector< cv::RotatedRect > rectangles) |
void | train () |
Private Attributes | |
CvNormalBayesClassifier * | bayes |
bool | capture |
int | capture_count |
ros::Subscriber | cloud |
cv::Mat | dilate_element |
cv::Mat | erode_element |
ros::Subscriber | feed |
int | last_x |
int | last_y |
pcl::PointCloud< pcl::PointXYZ > | latest_cloud |
ros::NodeHandle | node |
std::vector< int > | non_matches |
cv::RNG | random |
std::vector< cv::Point > | ref_contour |
std::vector< smoothing_point > | smoothing_points |
tf::TransformBroadcaster | tfb |
Main vision processing object.
The processor reading from the PR2's cameras and looking for objects.
Definition at line 268 of file processor.h.
Creates a processor. This will subscribe to the necessary image streams and initialize their callback functions.
Definition at line 27 of file processor.cpp.
Cleans up any resources from the processor.
Definition at line 81 of file processor.cpp.
void processor::accuracy | ( | ) | [private] |
Runs the classifier accuracy test on the set of training images.
Definition at line 171 of file processor.cpp.
void processor::cloud_cback | ( | const sensor_msgs::PointCloud2::ConstPtr & | pc | ) | [private] |
The main callback for the point cloud.
pc | the ROS point cloud from the PR2 |
Definition at line 689 of file processor.cpp.
void processor::feed_cback | ( | const sensor_msgs::Image::ConstPtr & | img | ) | [private] |
The main callback for the image feed. This will call the necessary processing functions.
img | the ROS image from the PR2 |
Definition at line 284 of file processor.cpp.
vector< float > processor::get_feature_vector | ( | cv::Mat const | src | ) | [private] |
Gets the feature vector for the given image.
src | the image to process |
Definition at line 612 of file processor.cpp.
vector< RotatedRect > processor::segment | ( | cv::Mat const | src | ) | [private] |
Performs a Canny edge operator and probabilistic Hough transform on the given image.
src | the image to perform the operations on |
Definition at line 488 of file processor.cpp.
void processor::smooth | ( | cv::RotatedRect | r | ) | [private] |
Uses the given bounding box of a possible computer location to smooth out the location.
r | the bounding box |
Definition at line 450 of file processor.cpp.
vector< Mat > processor::split_image | ( | cv::Mat const | src, |
std::vector< cv::RotatedRect > | rectangles | ||
) | [private] |
Creates a vector of subsections of the original image based a set of bounding boxes
src | the image to create subsections of |
rectangles | the bounding boxes to subsection by |
Definition at line 581 of file processor.cpp.
void processor::train | ( | ) | [private] |
Trains the classifier based on the set of training images.
Definition at line 86 of file processor.cpp.
CvNormalBayesClassifier* processor::bayes [private] |
Definition at line 353 of file processor.h.
bool processor::capture [private] |
used to see if the user wants to capture training data first
Definition at line 355 of file processor.h.
int processor::capture_count [private] |
used when saving captured images
Definition at line 356 of file processor.h.
ros::Subscriber processor::cloud [private] |
PR2's image and point cloud streams
Definition at line 345 of file processor.h.
cv::Mat processor::dilate_element [private] |
element to use to erode and dilate
Definition at line 347 of file processor.h.
cv::Mat processor::erode_element [private] |
Definition at line 347 of file processor.h.
ros::Subscriber processor::feed [private] |
Definition at line 345 of file processor.h.
int processor::last_x [private] |
Definition at line 361 of file processor.h.
int processor::last_y [private] |
last known location of the object
Definition at line 361 of file processor.h.
pcl::PointCloud<pcl::PointXYZ> processor::latest_cloud [private] |
robots latest point cloud
Definition at line 363 of file processor.h.
ros::NodeHandle processor::node [private] |
main ROS node handle
Definition at line 343 of file processor.h.
std::vector<int> processor::non_matches [private] |
used to remove unlikely objects during smoothing
Definition at line 359 of file processor.h.
cv::RNG processor::random [private] |
used to generate random colors
Definition at line 351 of file processor.h.
std::vector<cv::Point> processor::ref_contour [private] |
used for rectangle matching in the feature vector
Definition at line 349 of file processor.h.
used to smooth the object location
Definition at line 358 of file processor.h.
tf::TransformBroadcaster processor::tfb [private] |
used to find the object in 3D space
Definition at line 362 of file processor.h.