#include <ros/ros.h>#include <ros/package.h>#include <std_msgs/Header.h>#include <geometry_msgs/PointStamped.h>#include <geometry_msgs/Pose2D.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 <sensor_msgs/image_encodings.h>#include <actionlib/server/simple_action_server.h>#include <pr2_manipulation_controllers/JTTaskControllerState.h>#include <pr2_manipulation_controllers/JinvTeleopControllerState.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/io/pcd_io.h>#include <pcl16_ros/transforms.h>#include <pcl16/ros/conversions.h>#include <pcl16/ModelCoefficients.h>#include <pcl16/registration/transformation_estimation_svd.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/comp_geometry.h>#include <cpl_visual_features/features/shape_context.h>#include <tabletop_pushing/LearnPush.h>#include <tabletop_pushing/LocateTable.h>#include <tabletop_pushing/VisFeedbackPushTrackingAction.h>#include <tabletop_pushing/point_cloud_segmentation.h>#include <tabletop_pushing/shape_features.h>#include <tabletop_pushing/object_tracker_25d.h>#include <tabletop_pushing/push_primitives.h>#include <tabletop_pushing/arm_obj_segmentation.h>#include <tabletop_pushing/extern/Timer.hpp>#include <libsvm/svm.h>#include <vector>#include <queue>#include <set>#include <string>#include <sstream>#include <iostream>#include <utility>#include <float.h>#include <math.h>#include <cmath>#include <time.h>#include <cstdlib>Go to the source code of this file.
Classes | |
| struct | ScoredIdx | 
| class | ScoredIdxComparison | 
| class | TabletopPushingPerceptionNode | 
Defines | |
| #define | DISPLAY_WAIT 1 | 
| #define | FOOTPRINT_XY_RES 0.001 | 
Typedefs | |
| typedef  message_filters::sync_policies::ApproximateTime < sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::PointCloud2 >  | MySyncPolicy | 
| typedef  tabletop_pushing::VisFeedbackPushTrackingAction  | PushTrackerAction | 
| typedef  tabletop_pushing::VisFeedbackPushTrackingGoal  | PushTrackerGoal | 
| typedef  tabletop_pushing::VisFeedbackPushTrackingResult  | PushTrackerResult | 
| typedef  tabletop_pushing::VisFeedbackPushTrackingFeedback  | PushTrackerState | 
| typedef pcl16::PointCloud < pcl16::PointXYZ >  | XYZPointCloud | 
Functions | |
| int | main (int argc, char **argv) | 
| int | objLocToIdx (double val, double min_val, double max_val) | 
| #define DISPLAY_WAIT 1 | 
Definition at line 120 of file tabletop_pushing_perception_node.cpp.
| #define FOOTPRINT_XY_RES 0.001 | 
Definition at line 158 of file tabletop_pushing_perception_node.cpp.
| typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::PointCloud2> MySyncPolicy | 
Definition at line 145 of file tabletop_pushing_perception_node.cpp.
| typedef tabletop_pushing::VisFeedbackPushTrackingAction PushTrackerAction | 
Definition at line 156 of file tabletop_pushing_perception_node.cpp.
| typedef tabletop_pushing::VisFeedbackPushTrackingGoal PushTrackerGoal | 
Definition at line 154 of file tabletop_pushing_perception_node.cpp.
| typedef tabletop_pushing::VisFeedbackPushTrackingResult PushTrackerResult | 
Definition at line 155 of file tabletop_pushing_perception_node.cpp.
| typedef tabletop_pushing::VisFeedbackPushTrackingFeedback PushTrackerState | 
Definition at line 153 of file tabletop_pushing_perception_node.cpp.
| typedef pcl16::PointCloud<pcl16::PointXYZ> XYZPointCloud | 
Definition at line 141 of file tabletop_pushing_perception_node.cpp.
| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Definition at line 2330 of file tabletop_pushing_perception_node.cpp.
| int objLocToIdx | ( | double | val, | 
| double | min_val, | ||
| double | max_val | ||
| ) |  [inline] | 
        
Definition at line 160 of file tabletop_pushing_perception_node.cpp.