#include <opencv2/core/core.hpp>
#include <opencv2/ml/ml.hpp>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <tf/transform_broadcaster.h>
Go to the source code of this file.
Classes | |
class | processor |
Main vision processing object. More... | |
struct | smoothing_point |
Defines | |
#define | BASE_FRAME "/base_link" |
#define | BLUR_KERNEL 5 |
#define | BSG 3 |
#define | CANNY_KERNEL 3 |
#define | CANNY_MAX_THRESH 120 |
#define | CANNY_MIN_THRESH 40 |
#define | CLOUD_FRAME "/head_mount_kinect_rgb_optical_frame" |
#define | COMPUTER 0 |
#define | COVERS 5 |
#define | D 7 |
#define | DILATE_ELEMENT_SIZE 3 |
#define | ERODE_ELEMENT_SIZE 5 |
#define | GOAL_FRAME "/touch_goal" |
#define | HOUGH_MAX_LINE_GAP 3 |
#define | HOUGH_MIN_LINE_LENGTH 8 |
#define | HOUGH_RHO 1 |
#define | HOUGH_THETA CV_PI/180.0 |
#define | HOUGH_THRESH 12 |
#define | MAX_AREA 7000 |
#define | MAX_AVG_LINE_LENGTH 25.0 |
#define | MAX_LINES 150.0 |
#define | MAX_SIFT 20.0 |
#define | MAX_SMOOTHING_COUNT 20 |
#define | MIN_AREA 1000 |
#define | NUM_BSG 19 |
#define | NUM_COMPUTER 36 |
#define | NUM_COVERS 54 |
#define | NUM_OTHER 30 |
#define | NUM_PENS 35 |
#define | NUM_ROBOT 18 |
#define | NUM_TURTLE 39 |
#define | OBJECT_FRAME "/computer_object_link" |
#define | OTHER 6 |
#define | PADDING_X -0.2 |
#define | PADDING_Y -0.1 |
#define | PADDING_Z -0.1 |
#define | PENS 4 |
#define | RATIO_THRESHOLD 0.7 |
#define | REF_HEIGHT 28 |
#define | REF_WIDTH 20 |
#define | ROBOT 2 |
#define | SMOOTH_DIST_THRESH 5 |
#define | TURTLE 1 |
Functions | |
int | main (int argc, char **argv) |
#define BASE_FRAME "/base_link" |
The frame name in the TF tree for the robot base.
Definition at line 234 of file processor.h.
#define BLUR_KERNEL 5 |
Kernel size for blur filter.
Definition at line 65 of file processor.h.
#define BSG 3 |
Integer label for the toy Battlestar Galactica robot.
Definition at line 188 of file processor.h.
#define CANNY_KERNEL 3 |
Kernel size for Canny.
Definition at line 81 of file processor.h.
#define CANNY_MAX_THRESH 120 |
Maximum gradient threshold for Canny.
Definition at line 76 of file processor.h.
#define CANNY_MIN_THRESH 40 |
Minimum gradient threshold for Canny.
Definition at line 71 of file processor.h.
#define CLOUD_FRAME "/head_mount_kinect_rgb_optical_frame" |
The frame name in the TF tree for the point cloud.
Definition at line 239 of file processor.h.
#define COMPUTER 0 |
Integer label for the toy computer.
Definition at line 158 of file processor.h.
#define COVERS 5 |
Integer label for the desk covers.
Definition at line 208 of file processor.h.
#define D 7 |
Dimensionality of the feature vector.
Definition at line 152 of file processor.h.
#define DILATE_ELEMENT_SIZE 3 |
Element size used when we dilate the image.
Definition at line 92 of file processor.h.
#define ERODE_ELEMENT_SIZE 5 |
Element size used when we erode the image.
Definition at line 87 of file processor.h.
#define GOAL_FRAME "/touch_goal" |
The frame name in the TF tree for the arm movement goal.
Definition at line 244 of file processor.h.
#define HOUGH_MAX_LINE_GAP 3 |
Maximum gap between two lines to allow for merging lines.
Definition at line 118 of file processor.h.
#define HOUGH_MIN_LINE_LENGTH 8 |
Minimum length of a line that will be counted as a line.
Definition at line 113 of file processor.h.
#define HOUGH_RHO 1 |
Distance resolution of the Hough transforms accumulator.
Definition at line 98 of file processor.h.
#define HOUGH_THETA CV_PI/180.0 |
Angle resolution of the Hough transforms accumulator.
Definition at line 103 of file processor.h.
#define HOUGH_THRESH 12 |
Only lines with enough votes will be counted as a line using this as the threshold.
Definition at line 108 of file processor.h.
#define MAX_AREA 7000 |
Maximum area cutoff of the bounding box length and width used when filtering contours.
Definition at line 48 of file processor.h.
#define MAX_AVG_LINE_LENGTH 25.0 |
Maximum average line length to bound by in an image for the feature vector.
Definition at line 146 of file processor.h.
#define MAX_LINES 150.0 |
Maximum number of lines to bound by in an image for the feature vector.
Definition at line 141 of file processor.h.
#define MAX_SIFT 20.0 |
SIFT features cutoff size used for scaling in the feature vector.
Definition at line 135 of file processor.h.
#define MAX_SMOOTHING_COUNT 20 |
Max count used for smoothing.
Definition at line 59 of file processor.h.
#define MIN_AREA 1000 |
Minimum area cutoff of the bounding box length and width used when filtering contours.
Definition at line 43 of file processor.h.
#define NUM_BSG 19 |
Number of toy Battlestar Galactica robot training points for the classifier.
Definition at line 193 of file processor.h.
#define NUM_COMPUTER 36 |
Number of computer training points for the classifier.
Definition at line 163 of file processor.h.
#define NUM_COVERS 54 |
Number of desk cover training points for the classifier.
Definition at line 213 of file processor.h.
#define NUM_OTHER 30 |
Number of other segmented objects training points for the classifier.
Definition at line 223 of file processor.h.
#define NUM_PENS 35 |
Number of pen training points for the classifier.
Definition at line 203 of file processor.h.
#define NUM_ROBOT 18 |
Number of robot training points for the classifier.
Definition at line 183 of file processor.h.
#define NUM_TURTLE 39 |
Number of turtle training points for the classifier.
Definition at line 173 of file processor.h.
#define OBJECT_FRAME "/computer_object_link" |
The frame name in the TF tree for the object.
Definition at line 229 of file processor.h.
#define OTHER 6 |
Integer label for other segmented objects.
Definition at line 218 of file processor.h.
#define PADDING_X -0.2 |
Padding in the X director for the arm goal.
Definition at line 250 of file processor.h.
#define PADDING_Y -0.1 |
Padding in the Y director for the arm goal.
Definition at line 255 of file processor.h.
#define PADDING_Z -0.1 |
Padding in the Z director for the arm goal.
Definition at line 260 of file processor.h.
#define PENS 4 |
Integer label for the pens.
Definition at line 198 of file processor.h.
#define RATIO_THRESHOLD 0.7 |
Ratio cutoff of the bounding box length and width used when filtering contours.
Definition at line 38 of file processor.h.
#define REF_HEIGHT 28 |
Reference rectangle height used in rectangle matching in the feature vector.
Definition at line 129 of file processor.h.
#define REF_WIDTH 20 |
Reference rectangle width used in rectangle matching in the feature vector.
Definition at line 124 of file processor.h.
#define ROBOT 2 |
Integer label for the toy robot.
Definition at line 178 of file processor.h.
#define SMOOTH_DIST_THRESH 5 |
Distance threshold used for smoothing.
Definition at line 54 of file processor.h.
#define TURTLE 1 |
Integer label for the toy turtle.
Definition at line 168 of file processor.h.
int main | ( | int | argc, |
char ** | argv | ||
) |
Creates and runs the processor node.
argc | argument count that is passed to ros::init |
argv | arguments that are passed to ros::init |
Definition at line 695 of file processor.cpp.