Classes | Functions | Variables
detector.cpp File Reference
#include <ros/ros.h>
#include <sensor_msgs/CameraInfo.h>
#include <sensor_msgs/Image.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <tf/transform_datatypes.h>
#include <articulation_msgs/TrackMsg.h>
Include dependency graph for detector.cpp:

Go to the source code of this file.

Classes

struct  Observation
struct  Track

Functions

void addToTrack (Observation &percept)
bool checkPercept (Observation &percept, int plane)
void CountConvexPoly (cv::Mat &img, const cv::Point *v, int npts, int &pixel_value, int &pixel_size, int &pixel_occ)
float evalPercept (Observation &percept, int plane, bool draw=false)
bool extractPlanes ()
void imageCallback (const sensor_msgs::Image::ConstPtr &msg)
void infoCallback (const sensor_msgs::CameraInfo::ConstPtr &msg)
int main (int argc, char **argv)
int openChannel (articulation_msgs::TrackMsg &track, std::string name, bool autocreate)
float optimizePercept (Observation &percept, int plane)
bool sameObject (Observation &a, Observation &b)
cv::Point samplePoint (int step)
void sendTracks (std_msgs::Header header)
cv::Point to2D (cv::Point3f pt)
cv::Point3f to3D (cv::Point a)

Variables

sensor_msgs::CameraInfo::ConstPtr cameraInfo_
int CLIP_BOTTOM = 16
int CLIP_LEFT = 16
int CLIP_RIGHT = 16
int CLIP_TOP = 40
int COST_FREE = 255
int COST_INPLANE = 0
int COST_OCCLUDED = 20
int COST_UNKNOWN = 20
cv_bridge::CvImagePtr cv_ptr
cv::Mat debugImage_
double FILTER_Z = 2
double MAX_DIFF_ROT = M_PI/180*20
double MAX_DIFF_SIZE = 0.05
double MAX_DIFF_TRANS = 0.10
const int MAX_PLANES = 10
cv::Vec3f planeCenter [MAX_PLANES]
cv::Mat planeImage [MAX_PLANES]
cv::Vec3f planeNormal [MAX_PLANES]
int PLANES = 1
int planeSize [MAX_PLANES]
double PRIOR_HEIGHT = 0.1
double PRIOR_WIDTH = 0.1
double RANSAC_DISTANCE = 0.01
int RANSAC_DOWNSAMPLE = 15
int RANSAC_FITTING_ITERATIONS = 200
int RANSAC_ITERATIONS = 200
bool SHOW_IMAGES = true
int STEP_FACTOR [] = {8,4,2,1}
double STEP_ROT = M_PI/180*0.5
double STEP_TRANS = 0.005
double THRESHOLD_PRECISION = 0.7
double THRESHOLD_RECALL = 0.7
cv::Mat tmpImage_
ros::Publisher track_pub_
std::vector< Tracktracks
ros::Publisher visualization_array_pub_
ros::Publisher visualization_pub_

Function Documentation

void addToTrack ( Observation percept)

Definition at line 568 of file detector.cpp.

bool checkPercept ( Observation percept,
int  plane 
)

Definition at line 458 of file detector.cpp.

void CountConvexPoly ( cv::Mat &  img,
const cv::Point v,
int  npts,
int &  pixel_value,
int &  pixel_size,
int &  pixel_occ 
)

Definition at line 84 of file detector.cpp.

float evalPercept ( Observation percept,
int  plane,
bool  draw = false 
)

Definition at line 405 of file detector.cpp.

Definition at line 268 of file detector.cpp.

void imageCallback ( const sensor_msgs::Image::ConstPtr &  msg)

Definition at line 647 of file detector.cpp.

void infoCallback ( const sensor_msgs::CameraInfo::ConstPtr &  msg)

Definition at line 642 of file detector.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 716 of file detector.cpp.

int openChannel ( articulation_msgs::TrackMsg track,
std::string  name,
bool  autocreate 
)

Definition at line 592 of file detector.cpp.

float optimizePercept ( Observation percept,
int  plane 
)

Definition at line 480 of file detector.cpp.

bool sameObject ( Observation a,
Observation b 
)

Definition at line 556 of file detector.cpp.

cv::Point samplePoint ( int  step)

Definition at line 240 of file detector.cpp.

void sendTracks ( std_msgs::Header  header)

Definition at line 613 of file detector.cpp.

cv::Point to2D ( cv::Point3f  pt) [inline]

Definition at line 261 of file detector.cpp.

cv::Point3f to3D ( cv::Point  a) [inline]

Definition at line 249 of file detector.cpp.


Variable Documentation

sensor_msgs::CameraInfo::ConstPtr cameraInfo_

Definition at line 69 of file detector.cpp.

int CLIP_BOTTOM = 16

Definition at line 50 of file detector.cpp.

int CLIP_LEFT = 16

Definition at line 47 of file detector.cpp.

int CLIP_RIGHT = 16

Definition at line 48 of file detector.cpp.

int CLIP_TOP = 40

Definition at line 49 of file detector.cpp.

int COST_FREE = 255

Definition at line 33 of file detector.cpp.

int COST_INPLANE = 0

Definition at line 32 of file detector.cpp.

int COST_OCCLUDED = 20

Definition at line 34 of file detector.cpp.

int COST_UNKNOWN = 20

Definition at line 35 of file detector.cpp.

cv_bridge::CvImagePtr cv_ptr

Definition at line 70 of file detector.cpp.

cv::Mat debugImage_

Definition at line 71 of file detector.cpp.

double FILTER_Z = 2

Definition at line 30 of file detector.cpp.

double MAX_DIFF_ROT = M_PI/180*20

Definition at line 53 of file detector.cpp.

double MAX_DIFF_SIZE = 0.05

Definition at line 54 of file detector.cpp.

double MAX_DIFF_TRANS = 0.10

Definition at line 52 of file detector.cpp.

const int MAX_PLANES = 10

Definition at line 20 of file detector.cpp.

cv::Vec3f planeCenter[MAX_PLANES]

Definition at line 75 of file detector.cpp.

Definition at line 73 of file detector.cpp.

cv::Vec3f planeNormal[MAX_PLANES]

Definition at line 76 of file detector.cpp.

int PLANES = 1

Definition at line 22 of file detector.cpp.

Definition at line 74 of file detector.cpp.

double PRIOR_HEIGHT = 0.1

Definition at line 38 of file detector.cpp.

double PRIOR_WIDTH = 0.1

Definition at line 37 of file detector.cpp.

double RANSAC_DISTANCE = 0.01

Definition at line 26 of file detector.cpp.

Definition at line 27 of file detector.cpp.

Definition at line 28 of file detector.cpp.

int RANSAC_ITERATIONS = 200

Definition at line 25 of file detector.cpp.

bool SHOW_IMAGES = true

Definition at line 23 of file detector.cpp.

int STEP_FACTOR[] = {8,4,2,1}

Definition at line 42 of file detector.cpp.

double STEP_ROT = M_PI/180*0.5

Definition at line 41 of file detector.cpp.

double STEP_TRANS = 0.005

Definition at line 40 of file detector.cpp.

double THRESHOLD_PRECISION = 0.7

Definition at line 44 of file detector.cpp.

double THRESHOLD_RECALL = 0.7

Definition at line 45 of file detector.cpp.

cv::Mat tmpImage_

Definition at line 72 of file detector.cpp.

Definition at line 80 of file detector.cpp.

Definition at line 82 of file detector.cpp.

Definition at line 79 of file detector.cpp.

Definition at line 78 of file detector.cpp.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


articulation_perception
Author(s):
autogenerated on Wed Dec 26 2012 16:41:22