Classes | Defines | Typedefs | Functions
object_singulation_node.cpp File Reference
#include <ros/ros.h>
#include <std_msgs/Header.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/PoseStamped.h>
#include <sensor_msgs/Image.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/CameraInfo.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <cv_bridge/cv_bridge.h>
#include <tf/transform_listener.h>
#include <pcl16/point_cloud.h>
#include <pcl16/point_types.h>
#include <pcl16/common/common.h>
#include <pcl16/common/eigen.h>
#include <pcl16/common/centroid.h>
#include <pcl16/io/io.h>
#include <pcl16_ros/transforms.h>
#include <pcl16/ros/conversions.h>
#include <pcl16/ModelCoefficients.h>
#include <pcl16/sample_consensus/method_types.h>
#include <pcl16/sample_consensus/model_types.h>
#include <pcl16/segmentation/sac_segmentation.h>
#include <pcl16/filters/extract_indices.h>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <boost/shared_ptr.hpp>
#include <cpl_visual_features/helpers.h>
#include <cpl_visual_features/features/edges.h>
#include <tabletop_pushing/SingulationPush.h>
#include <tabletop_pushing/LocateTable.h>
#include <tabletop_pushing/point_cloud_segmentation.h>
#include <vector>
#include <set>
#include <string>
#include <sstream>
#include <iostream>
#include <utility>
#include <float.h>
#include <math.h>
#include <time.h>
#include <cstdlib>
Include dependency graph for object_singulation_node.cpp:

Go to the source code of this file.

Classes

struct  Boundary
class  ObjectSingulation
class  ObjectSingulationNode
struct  PushOpt

Defines

#define DEBUG_PUSH_HISTORY   1
#define DISPLAY_3D_BOUNDARIES   1
#define DISPLAY_CHOSEN_BOUNDARY   1
#define DISPLAY_INPUT_COLOR   1
#define DISPLAY_PROJECTED_OBJECTS   1
#define DISPLAY_PUSH_VECTOR   1
#define DISPLAY_WAIT   1
#define randf()   static_cast<float>(rand())/RAND_MAX

Typedefs

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::PointCloud2 > 
MySyncPolicy
typedef std::vector< PushOptPushOpts
typedef SingulationPush::Response PushVector
typedef pcl16::PointCloud
< pcl16::PointXYZ > 
XYZPointCloud

Functions

int main (int argc, char **argv)

Define Documentation

#define DEBUG_PUSH_HISTORY   1

Definition at line 106 of file object_singulation_node.cpp.

#define DISPLAY_3D_BOUNDARIES   1

Definition at line 103 of file object_singulation_node.cpp.

#define DISPLAY_CHOSEN_BOUNDARY   1

Definition at line 102 of file object_singulation_node.cpp.

#define DISPLAY_INPUT_COLOR   1

Definition at line 97 of file object_singulation_node.cpp.

#define DISPLAY_PROJECTED_OBJECTS   1

Definition at line 100 of file object_singulation_node.cpp.

#define DISPLAY_PUSH_VECTOR   1

Definition at line 104 of file object_singulation_node.cpp.

#define DISPLAY_WAIT   1

Definition at line 105 of file object_singulation_node.cpp.

#define randf ( )    static_cast<float>(rand())/RAND_MAX

Definition at line 107 of file object_singulation_node.cpp.


Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::PointCloud2> MySyncPolicy

Definition at line 117 of file object_singulation_node.cpp.

Definition at line 291 of file object_singulation_node.cpp.

typedef SingulationPush::Response PushVector

Definition at line 118 of file object_singulation_node.cpp.

typedef pcl16::PointCloud<pcl16::PointXYZ> XYZPointCloud

Definition at line 114 of file object_singulation_node.cpp.


Function Documentation

int main ( int  argc,
char **  argv 
)

Definition at line 3062 of file object_singulation_node.cpp.



tabletop_pushing
Author(s): Tucker Hermans
autogenerated on Wed Nov 27 2013 11:59:44