detector.cpp File Reference

#include <ros/ros.h>
#include <iostream>
#include <cmath>
#include <stdexcept>
#include "duration.h"
#include <sys/time.h>
#include "ros/time.h"
#include <cstdio>
#include <sstream>
#include <log4cxx/logger.h>
#include "ros/console.h"
#include <boost/static_assert.hpp>
#include <cassert>
#include <stdint.h>
#include <assert.h>
#include <stddef.h>
#include <string>
#include "ros/assert.h"
#include <vector>
#include <map>
#include <set>
#include <list>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/function.hpp>
#include "exceptions.h"
#include <boost/shared_array.hpp>
#include "ros/types.h"
#include "ros/forwards.h"
#include "ros/common.h"
#include "ros/macros.h"
#include <string.h>
#include <boost/array.hpp>
#include "serialized_message.h"
#include "message_forward.h"
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
#include "message_traits.h"
#include "ros/exception.h"
#include <boost/call_traits.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
#include <boost/bind.hpp>
#include <typeinfo>
#include <ros/message.h>
#include <boost/type_traits/is_void.hpp>
#include <boost/type_traits/is_base_of.hpp>
#include <boost/type_traits/is_const.hpp>
#include <boost/type_traits/add_const.hpp>
#include <boost/make_shared.hpp>
#include <ros/static_assert.h>
#include "ros/message_traits.h"
#include "ros/builtin_message_traits.h"
#include "ros/serialization.h"
#include "ros/message_event.h"
#include "forwards.h"
#include "timer_options.h"
#include "wall_timer_options.h"
#include "ros/service_traits.h"
#include <boost/lexical_cast.hpp>
#include "subscription_callback_helper.h"
#include "ros/spinner.h"
#include <time.h>
#include "ros/publisher.h"
#include <boost/utility.hpp>
#include "ros/service_server.h"
#include "ros/subscriber.h"
#include "ros/node_handle.h"
#include "ros/init.h"
#include "XmlRpcValue.h"
#include "node_handle.h"
#include "ros/names.h"
#include <ostream>
#include "ros/message_operations.h"
#include "std_msgs/Header.h"
#include <sensor_msgs/Image.h>
#include <stdlib.h>
#include <float.h>
#include <math.h>
#include <limits.h>
#include "opencv2/core/core.hpp"
#include "opencv2/core/types_c.h"
#include "opencv2/imgproc/types_c.h"
#include "opencv2/core/core_c.h"
#include "geometry_msgs/Vector3.h"
#include "geometry_msgs/Quaternion.h"
#include "geometry_msgs/Point.h"
#include "btMatrix3x3.h"
#include "geometry_msgs/Pose.h"
This graph shows which files directly or indirectly include this file:

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.

bool extractPlanes (  ) 

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.

ros::Publisher track_pub_

Definition at line 80 of file detector.cpp.

std::vector<Track > tracks

Definition at line 82 of file detector.cpp.

ros::Publisher visualization_array_pub_

Definition at line 79 of file detector.cpp.

ros::Publisher visualization_pub_

Definition at line 78 of file detector.cpp.

 All Classes Files Functions Variables


articulation_perception
Author(s):
autogenerated on Fri Jan 11 09:32:48 2013