importance_sampling.cpp
Go to the documentation of this file.
2 #include <boost/random/normal_distribution.hpp>
3 #include <boost/thread/thread.hpp>
4 #include <ctype.h>
6 #include "Eigen/Dense"
7 #include "Eigen/Core"
8 #include "handle_detector/CylinderArrayMsg.h"
9 #include "handle_detector/CylinderMsg.h"
10 #include "handle_detector/HandleListMsg.h"
14 #include <iostream>
16 #include <pcl/point_cloud.h>
17 #include <pcl/point_types.h>
18 #include <pcl/io/pcd_io.h>
19 #include <pcl/visualization/pcl_visualizer.h>
20 #include <ros/ros.h>
21 #include <sensor_msgs/PointCloud2.h>
22 #include <sstream>
23 #include <stdlib.h>
24 #include <stdio.h>
25 #include <string.h>
26 #include <vector>
27 #define EIGEN_DONT_PARALLELIZE
28 
29 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
30 
31 const std::string RANGE_SENSOR_FRAME = "/camera_rgb_optical_frame";
32 const std::string RANGE_SENSOR_TOPIC = "/camera/depth_registered/points";
33 //~ const std::string RANGE_SENSOR_TOPIC = "/head_camera/depth/points"; // simulated Kinect
34 
35 // input and output ROS topic data
36 PointCloud::Ptr g_cloud(new PointCloud);
39 std::vector<CylindricalShell> g_cylindrical_shells;
40 std::vector<std::vector<CylindricalShell> > g_handles;
41 
42 // synchronization
43 double g_prev_time;
45 bool g_has_read = false;
46 
47 void chatterCallback(const sensor_msgs::PointCloud2ConstPtr& input)
48 {
49  if (omp_get_wtime() - g_prev_time < g_update_interval)
50  return;
51 
52  // check whether input frame is equivalent to range sensor frame constant
53  std::string input_frame = input->header.frame_id;
54  if (input_frame.compare(RANGE_SENSOR_FRAME) != 0)
55  {
56  printf("Input frame %s is not equivalent to output frame %s ! Exiting ...\n", input_frame.c_str(),
57  RANGE_SENSOR_FRAME.c_str());
58  std::exit (EXIT_FAILURE);
59  }
60  printf("input frame: %s, output frame: %s\n", input_frame.c_str(), RANGE_SENSOR_FRAME.c_str());
61 
62  // convert ROS sensor message to PCL point cloud
63  PointCloud::Ptr cloud(new PointCloud);
64  pcl::fromROSMsg(*input, *cloud);
65  g_has_read = true;
66 
67  // organize point cloud for Organized Nearest Neighbors Search
68  g_cloud->width = 640;
69  g_cloud->height = 480;
70  g_cloud->points.resize(g_cloud->width * g_cloud->height);
71  for (int i = 0; i < g_cloud->height; i++)
72  {
73  for (int j = 0; j < g_cloud->width; j++)
74  {
75  g_cloud->points[i * g_cloud->width + j] = cloud->points[i * g_cloud->width + j];
76  }
77  }
78 
79  // store data to file
80  //~ pcl::PointCloud<pcl::PointXYZRGB>::Ptr stored_cloud;
81  //~ pcl::fromROSMsg(*input, *stored_cloud);
82  //~ pcl::io::savePCDFileASCII("/home/andreas/test_pcd.pcd", *stored_cloud);
83 
84  // search grasp affordances
85  g_cylindrical_shells = g_sampling.searchAffordances(g_cloud, g_affordances.getTargetRadius());
86 
87  // search handles
89 
90  // store current time
91  g_prev_time = omp_get_wtime();
92 }
93 
94 int main(int argc, char** argv)
95 {
96  // constants
97  const int PCD_FILE = 0;
98  const int SENSOR = 1;
99 
100  // initialize random seed
101  srand (time(NULL));
102 
103  // initialize ROS
104  ros::init(argc, argv, "localization");
105  ros::NodeHandle node("~");
106 
107  // set point cloud source from launch file
108  int point_cloud_source;
109  node.param("point_cloud_source", point_cloud_source, SENSOR);
110  printf("point cloud source: %i\n", point_cloud_source);
111 
112  // set point cloud update interval from launch file
113  node.param("update_interval", g_update_interval, 10.0);
114 
115  // read parameters
116  g_affordances.initParams(node);
117 
118  g_sampling.initParams(node);
119  g_sampling.setAffordances(g_affordances);
120  std::string range_sensor_frame;
121  ros::Subscriber sub;
122 
123  // read point cloud from file
124  if (point_cloud_source == PCD_FILE)
125  {
126  double start_time_file = omp_get_wtime();
127  range_sensor_frame = "/map";
128  std::string file = g_affordances.getPCDFile();
129 
130  if (pcl::io::loadPCDFile<pcl::PointXYZRGBA>(file, *g_cloud) == -1)
131  {
132  std::cerr << "Couldn't read pcd file" << std::endl;
133  return (-1);
134  }
135 
136  // search grasp affordances
137  double start_time = omp_get_wtime();
138  g_cylindrical_shells = g_sampling.searchAffordances(g_cloud, g_affordances.getTargetRadius());
139 
140  // search handles
141  double start_time_handles = omp_get_wtime();
143  printf("Handle search done in %.3f sec.\n", omp_get_wtime() - start_time_handles);
144 
145  // set boolean variable so that visualization topics get updated
146  g_has_read = true;
147 
148  // measure runtime
149  printf("Affordance and handle search done in %.3f sec.\n", omp_get_wtime() - start_time);
150  }
151  // point cloud read from sensor
152  else if (point_cloud_source == SENSOR)
153  {
154  printf("Reading point cloud data from sensor topic: %s\n", RANGE_SENSOR_TOPIC.c_str());
155  range_sensor_frame = RANGE_SENSOR_FRAME;
157  }
158 
159  // visualization of point cloud, grasp affordances, and handles
160  Visualizer visualizer(g_update_interval);
161  ros::Publisher cylinder_pub = node.advertise<handle_detector::CylinderArrayMsg>("cylinder_list", 10);
162  ros::Publisher handles_pub = node.advertise<handle_detector::HandleListMsg>("handle_list", 10);
163  ros::Publisher pcl_pub = node.advertise<sensor_msgs::PointCloud2>("point_cloud", 10);
164  sensor_msgs::PointCloud2 pc2msg;
165  PointCloud::Ptr cloud_vis(new PointCloud);
166  std::vector<visualization_msgs::MarkerArray> marker_arrays;
167  visualization_msgs::MarkerArray marker_array_msg;
168  visualization_msgs::MarkerArray marker_array_msg_handles;
169 
170  // publication of grasp affordances and handles as ROS topics
171  Messages messages;
172  ros::Publisher marker_array_pub = node.advertise<visualization_msgs::MarkerArray>("visualization_all_affordances",
173  10);
174  ros::Publisher marker_array_pub_handles = node.advertise<visualization_msgs::MarkerArray>("visualization_all_handles",
175  10);
176  std::vector<ros::Publisher> handle_pubs;
177  handle_detector::CylinderArrayMsg cylinder_list_msg;
178  handle_detector::HandleListMsg handle_list_msg;
179 
180  // how often things are published
181  ros::Rate rate(10);
182 
183  double prev_time = omp_get_wtime();
184 
185  while (ros::ok())
186  {
187  if (g_has_read)
188  {
189  // create visual point cloud
190  cloud_vis = g_affordances.workspaceFilter(g_cloud);
191  ROS_INFO("update cloud");
192 
193  // create cylinder messages for visualization and ROS topic
194  marker_array_msg = visualizer.createCylinders(g_cylindrical_shells, range_sensor_frame);
195  cylinder_list_msg = messages.createCylinderArray(g_cylindrical_shells, range_sensor_frame);
196  ROS_INFO("update visualization");
197 
198  // create handle messages for visualization and ROS topic
199  handle_list_msg = messages.createHandleList(g_handles, range_sensor_frame);
200  visualizer.createHandles(g_handles, range_sensor_frame, marker_arrays, marker_array_msg_handles);
201  handle_pubs.resize(g_handles.size());
202  for (std::size_t i = 0; i < handle_pubs.size(); i++)
203  handle_pubs[i] = node.advertise<visualization_msgs::MarkerArray>(
204  "visualization_handle_" + boost::lexical_cast < std::string > (i), 10);
205  ROS_INFO("update messages");
206 
207  g_has_read = false;
208  }
209 
210  // publish point cloud
211  pcl::toROSMsg(*cloud_vis, pc2msg);
212  pc2msg.header.stamp = ros::Time::now();
213  pc2msg.header.frame_id = range_sensor_frame;
214  pcl_pub.publish(pc2msg);
215 
216  // publish cylinders for visualization
217  marker_array_pub.publish(marker_array_msg);
218 
219  // publish handles for visualization
220  for (std::size_t i = 0; i < handle_pubs.size(); i++)
221  handle_pubs[i].publish(marker_arrays[i]);
222 
223  // publish handles for visualization
224  marker_array_pub_handles.publish(marker_array_msg_handles);
225 
226  // publish cylinders as ROS topic
227  cylinder_pub.publish(cylinder_list_msg);
228 
229  // publish handles as ROS topic
230  handles_pub.publish(handle_list_msg);
231 
232  ros::spinOnce();
233  rate.sleep();
234  }
235 
236  return 0;
237 }
bool g_has_read
void initParams(ros::NodeHandle node)
Read the parameters from a ROS launch file.
Definition: affordances.cpp:30
void publish(const boost::shared_ptr< M > &message) const
Sampling localizes grasp affordances using importance sampling.
Definition: sampling.h:47
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< CylindricalShell > g_cylindrical_shells
MarkerArray createCylinders(const std::vector< CylindricalShell > &list, const std::string &frame)
Create a MarkerArray message from a list of cylindrical shells.
Definition: visualizer.cpp:9
Affordances g_affordances
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
double getTargetRadius()
Return the target radius.
Definition: affordances.h:150
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
handle_detector::CylinderArrayMsg createCylinderArray(const std::vector< CylindricalShell > &list, std::string frame)
Create a CylinderArray message from a list of cylindrical shells.
Definition: messages.cpp:3
visualization_msgs::MarkerArray MarkerArray
Definition: visualizer.h:42
PointCloud::Ptr workspaceFilter(const PointCloud::Ptr &cloud_in, tf::StampedTransform *transform=NULL)
Filter out all points from a given cloud that are outside of a cube defined by the workspace limits o...
handle_detector::HandleListMsg createHandleList(const std::vector< std::vector< CylindricalShell > > &handles, std::string frame)
Create a HandleList message from a list of cylindrical shells.
Definition: messages.cpp:55
std::string getPCDFile()
Return the *.pcd file given by the corresponding parameter in the ROS launch file.
Definition: affordances.h:142
#define ROS_INFO(...)
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
Definition: affordances.h:53
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
double g_prev_time
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::vector< std::vector< CylindricalShell > > searchHandles(const PointCloud::Ptr &cloud, std::vector< CylindricalShell > shells)
Search handles in a set of cylindrical shells. If occlusion filtering is turned on (using the corresp...
Affordances localizes grasp affordances and handles in a point cloud. It also provides helper methods...
Definition: affordances.h:73
void createHandles(const std::vector< std::vector< CylindricalShell > > &handles, const std::string &frame, std::vector< MarkerArray > &marker_arrays, MarkerArray &all_handle_markers)
Create a list of MarkerArray messages and a MarkerArray from a list of handles. The former represents...
Definition: visualizer.cpp:134
void setAffordances(Affordances &affordances)
Definition: sampling.h:50
void chatterCallback(const sensor_msgs::PointCloud2ConstPtr &input)
bool sleep()
std::vector< std::vector< CylindricalShell > > g_handles
const std::string RANGE_SENSOR_TOPIC
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
double g_update_interval
Messages creates custom ROS messages to publish the results of the localization. The messages that ca...
Definition: messages.h:50
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
static Time now()
void initParams(const ros::NodeHandle &node)
Definition: sampling.cpp:242
const std::string RANGE_SENSOR_FRAME
ROSCPP_DECL void spinOnce()
PointCloud::Ptr g_cloud(new PointCloud)
std::vector< CylindricalShell > searchAffordances(const PointCloud::Ptr &cloud, double target_radius)
Definition: sampling.cpp:102
Sampling g_sampling
Visualizer creates ROS messages to visualize the results of the localization in RViz. The possible objects that can be visualized are: neighborhoods, cylindrical shells, and handles.
Definition: visualizer.h:49


handle_detector
Author(s):
autogenerated on Mon Jun 10 2019 13:29:00