importance_sampling.cpp
Go to the documentation of this file.
00001 #include "handle_detector/affordances.h"
00002 #include <boost/random/normal_distribution.hpp>
00003 #include <boost/thread/thread.hpp>
00004 #include <ctype.h>
00005 #include "handle_detector/cylindrical_shell.h"
00006 #include "Eigen/Dense"
00007 #include "Eigen/Core"
00008 #include "handle_detector/CylinderArrayMsg.h"
00009 #include "handle_detector/CylinderMsg.h"
00010 #include "handle_detector/HandleListMsg.h"
00011 #include "handle_detector/messages.h"
00012 #include "handle_detector/sampling.h"
00013 #include "handle_detector/visualizer.h"
00014 #include <iostream>
00015 #include <pcl_conversions/pcl_conversions.h>
00016 #include <pcl/point_cloud.h>
00017 #include <pcl/point_types.h>
00018 #include <pcl/io/pcd_io.h>
00019 #include <pcl/visualization/pcl_visualizer.h>
00020 #include <ros/ros.h>
00021 #include <sensor_msgs/PointCloud2.h>
00022 #include <sstream>
00023 #include <stdlib.h> 
00024 #include <stdio.h>
00025 #include <string.h>
00026 #include <vector>
00027 #define EIGEN_DONT_PARALLELIZE
00028 
00029 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
00030 
00031 const std::string RANGE_SENSOR_FRAME = "/camera_rgb_optical_frame";
00032 const std::string RANGE_SENSOR_TOPIC = "/camera/depth_registered/points";
00033 //~ const std::string RANGE_SENSOR_TOPIC = "/head_camera/depth/points"; // simulated Kinect
00034 
00035 // input and output ROS topic data
00036 PointCloud::Ptr g_cloud(new PointCloud);
00037 Affordances g_affordances;
00038 Sampling g_sampling;
00039 std::vector<CylindricalShell> g_cylindrical_shells;
00040 std::vector<std::vector<CylindricalShell> > g_handles;
00041 
00042 // synchronization
00043 double g_prev_time;
00044 double g_update_interval;
00045 bool g_has_read = false;
00046 
00047 void chatterCallback(const sensor_msgs::PointCloud2ConstPtr& input)
00048 {
00049   if (omp_get_wtime() - g_prev_time < g_update_interval)
00050     return;
00051 
00052   // check whether input frame is equivalent to range sensor frame constant
00053   std::string input_frame = input->header.frame_id;
00054   if (input_frame.compare(RANGE_SENSOR_FRAME) != 0)
00055   {
00056     printf("Input frame %s is not equivalent to output frame %s ! Exiting ...\n", input_frame.c_str(),
00057            RANGE_SENSOR_FRAME.c_str());
00058     std::exit (EXIT_FAILURE);
00059   }
00060   printf("input frame: %s, output frame: %s\n", input_frame.c_str(), RANGE_SENSOR_FRAME.c_str());
00061 
00062   // convert ROS sensor message to PCL point cloud
00063   PointCloud::Ptr cloud(new PointCloud);
00064   pcl::fromROSMsg(*input, *cloud);
00065   g_has_read = true;
00066 
00067   // organize point cloud for Organized Nearest Neighbors Search
00068   g_cloud->width = 640;
00069   g_cloud->height = 480;
00070   g_cloud->points.resize(g_cloud->width * g_cloud->height);
00071   for (int i = 0; i < g_cloud->height; i++)
00072   {
00073     for (int j = 0; j < g_cloud->width; j++)
00074     {
00075       g_cloud->points[i * g_cloud->width + j] = cloud->points[i * g_cloud->width + j];
00076     }
00077   }
00078 
00079   // store data to file
00080   //~ pcl::PointCloud<pcl::PointXYZRGB>::Ptr stored_cloud;
00081   //~ pcl::fromROSMsg(*input, *stored_cloud);
00082   //~ pcl::io::savePCDFileASCII("/home/andreas/test_pcd.pcd", *stored_cloud);
00083 
00084   // search grasp affordances
00085   g_cylindrical_shells = g_sampling.searchAffordances(g_cloud, g_affordances.getTargetRadius());
00086 
00087   // search handles
00088   g_handles = g_affordances.searchHandles(g_cloud, g_cylindrical_shells);
00089 
00090   // store current time
00091   g_prev_time = omp_get_wtime();
00092 }
00093 
00094 int main(int argc, char** argv)
00095 {
00096   // constants
00097   const int PCD_FILE = 0;
00098   const int SENSOR = 1;
00099 
00100   // initialize random seed
00101   srand (time(NULL));
00102 
00103   // initialize ROS
00104   ros::init(argc, argv, "localization");
00105   ros::NodeHandle node("~");
00106 
00107   // set point cloud source from launch file
00108   int point_cloud_source;
00109   node.param("point_cloud_source", point_cloud_source, SENSOR);
00110   printf("point cloud source: %i\n", point_cloud_source);
00111 
00112   // set point cloud update interval from launch file
00113   node.param("update_interval", g_update_interval, 10.0);
00114 
00115   // read parameters
00116   g_affordances.initParams(node);
00117 
00118   g_sampling.initParams(node);
00119   g_sampling.setAffordances(g_affordances);
00120   std::string range_sensor_frame;
00121   ros::Subscriber sub;
00122 
00123   // read point cloud from file
00124   if (point_cloud_source == PCD_FILE)
00125   {
00126     double start_time_file = omp_get_wtime();
00127     range_sensor_frame = "/map";
00128     std::string file = g_affordances.getPCDFile();
00129 
00130     if (pcl::io::loadPCDFile<pcl::PointXYZRGBA>(file, *g_cloud) == -1)
00131     {
00132       std::cerr << "Couldn't read pcd file" << std::endl;
00133       return (-1);
00134     }
00135 
00136     // search grasp affordances
00137     double start_time = omp_get_wtime();
00138     g_cylindrical_shells = g_sampling.searchAffordances(g_cloud, g_affordances.getTargetRadius());
00139 
00140     // search handles
00141     double start_time_handles = omp_get_wtime();
00142     g_handles = g_affordances.searchHandles(g_cloud, g_cylindrical_shells);
00143     printf("Handle search done in %.3f sec.\n", omp_get_wtime() - start_time_handles);
00144 
00145     // set boolean variable so that visualization topics get updated
00146     g_has_read = true;
00147 
00148     // measure runtime
00149     printf("Affordance and handle search done in %.3f sec.\n", omp_get_wtime() - start_time);
00150   }
00151   // point cloud read from sensor
00152   else if (point_cloud_source == SENSOR)
00153   {
00154     printf("Reading point cloud data from sensor topic: %s\n", RANGE_SENSOR_TOPIC.c_str());
00155     range_sensor_frame = RANGE_SENSOR_FRAME;
00156     sub = node.subscribe(RANGE_SENSOR_TOPIC, 10, chatterCallback);
00157   }
00158 
00159   // visualization of point cloud, grasp affordances, and handles
00160   Visualizer visualizer(g_update_interval);
00161   ros::Publisher cylinder_pub = node.advertise<handle_detector::CylinderArrayMsg>("cylinder_list", 10);
00162   ros::Publisher handles_pub = node.advertise<handle_detector::HandleListMsg>("handle_list", 10);
00163   ros::Publisher pcl_pub = node.advertise<sensor_msgs::PointCloud2>("point_cloud", 10);
00164   sensor_msgs::PointCloud2 pc2msg;
00165   PointCloud::Ptr cloud_vis(new PointCloud);
00166   std::vector<visualization_msgs::MarkerArray> marker_arrays;
00167   visualization_msgs::MarkerArray marker_array_msg;
00168   visualization_msgs::MarkerArray marker_array_msg_handles;
00169 
00170   // publication of grasp affordances and handles as ROS topics
00171   Messages messages;
00172   ros::Publisher marker_array_pub = node.advertise<visualization_msgs::MarkerArray>("visualization_all_affordances",
00173                                                                                     10);
00174   ros::Publisher marker_array_pub_handles = node.advertise<visualization_msgs::MarkerArray>("visualization_all_handles",
00175                                                                                             10);
00176   std::vector<ros::Publisher> handle_pubs;
00177   handle_detector::CylinderArrayMsg cylinder_list_msg;
00178   handle_detector::HandleListMsg handle_list_msg;
00179 
00180   // how often things are published
00181   ros::Rate rate(10);
00182 
00183   double prev_time = omp_get_wtime();
00184 
00185   while (ros::ok())
00186   {
00187     if (g_has_read)
00188     {
00189       // create visual point cloud
00190       cloud_vis = g_affordances.workspaceFilter(g_cloud);
00191       ROS_INFO("update cloud");
00192 
00193       // create cylinder messages for visualization and ROS topic
00194       marker_array_msg = visualizer.createCylinders(g_cylindrical_shells, range_sensor_frame);
00195       cylinder_list_msg = messages.createCylinderArray(g_cylindrical_shells, range_sensor_frame);
00196       ROS_INFO("update visualization");
00197 
00198       // create handle messages for visualization and ROS topic
00199       handle_list_msg = messages.createHandleList(g_handles, range_sensor_frame);
00200       visualizer.createHandles(g_handles, range_sensor_frame, marker_arrays, marker_array_msg_handles);
00201       handle_pubs.resize(g_handles.size());
00202       for (std::size_t i = 0; i < handle_pubs.size(); i++)
00203         handle_pubs[i] = node.advertise<visualization_msgs::MarkerArray>(
00204             "visualization_handle_" + boost::lexical_cast < std::string > (i), 10);
00205       ROS_INFO("update messages");
00206 
00207       g_has_read = false;
00208     }
00209 
00210     // publish point cloud
00211     pcl::toROSMsg(*cloud_vis, pc2msg);
00212     pc2msg.header.stamp = ros::Time::now();
00213     pc2msg.header.frame_id = range_sensor_frame;
00214     pcl_pub.publish(pc2msg);
00215 
00216     // publish cylinders for visualization
00217     marker_array_pub.publish(marker_array_msg);
00218 
00219     // publish handles for visualization
00220     for (std::size_t i = 0; i < handle_pubs.size(); i++)
00221       handle_pubs[i].publish(marker_arrays[i]);
00222 
00223     // publish handles for visualization
00224     marker_array_pub_handles.publish(marker_array_msg_handles);
00225 
00226     // publish cylinders as ROS topic
00227     cylinder_pub.publish(cylinder_list_msg);
00228 
00229     // publish handles as ROS topic
00230     handles_pub.publish(handle_list_msg);
00231 
00232     ros::spinOnce();
00233     rate.sleep();
00234   }
00235 
00236   return 0;
00237 }


handle_detector
Author(s):
autogenerated on Thu Jun 6 2019 17:36:23