2 #include <boost/random/normal_distribution.hpp> 3 #include <boost/thread/thread.hpp> 8 #include "handle_detector/CylinderArrayMsg.h" 9 #include "handle_detector/CylinderMsg.h" 10 #include "handle_detector/HandleListMsg.h" 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> 21 #include <sensor_msgs/PointCloud2.h> 27 #define EIGEN_DONT_PARALLELIZE 40 std::vector<std::vector<CylindricalShell> >
g_handles;
53 std::string input_frame = input->header.frame_id;
56 printf(
"Input frame %s is not equivalent to output frame %s ! Exiting ...\n", input_frame.c_str(),
58 std::exit (EXIT_FAILURE);
60 printf(
"input frame: %s, output frame: %s\n", input_frame.c_str(),
RANGE_SENSOR_FRAME.c_str());
71 for (
int i = 0; i <
g_cloud->height; i++)
73 for (
int j = 0; j <
g_cloud->width; j++)
94 int main(
int argc,
char** argv)
97 const int PCD_FILE = 0;
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);
120 std::string range_sensor_frame;
124 if (point_cloud_source == PCD_FILE)
126 double start_time_file = omp_get_wtime();
127 range_sensor_frame =
"/map";
128 std::string file = g_affordances.
getPCDFile();
130 if (pcl::io::loadPCDFile<pcl::PointXYZRGBA>(file, *
g_cloud) == -1)
132 std::cerr <<
"Couldn't read pcd file" << std::endl;
137 double start_time = omp_get_wtime();
141 double start_time_handles = omp_get_wtime();
143 printf(
"Handle search done in %.3f sec.\n", omp_get_wtime() - start_time_handles);
149 printf(
"Affordance and handle search done in %.3f sec.\n", omp_get_wtime() - start_time);
152 else if (point_cloud_source == SENSOR)
154 printf(
"Reading point cloud data from sensor topic: %s\n",
RANGE_SENSOR_TOPIC.c_str());
164 sensor_msgs::PointCloud2 pc2msg;
166 std::vector<visualization_msgs::MarkerArray> marker_arrays;
176 std::vector<ros::Publisher> handle_pubs;
177 handle_detector::CylinderArrayMsg cylinder_list_msg;
178 handle_detector::HandleListMsg handle_list_msg;
183 double prev_time = omp_get_wtime();
202 for (std::size_t i = 0; i < handle_pubs.size(); i++)
204 "visualization_handle_" + boost::lexical_cast < std::string > (i), 10);
213 pc2msg.header.frame_id = range_sensor_frame;
214 pcl_pub.publish(pc2msg);
217 marker_array_pub.
publish(marker_array_msg);
220 for (std::size_t i = 0; i < handle_pubs.size(); i++)
221 handle_pubs[i].publish(marker_arrays[i]);
224 marker_array_pub_handles.publish(marker_array_msg_handles);
227 cylinder_pub.
publish(cylinder_list_msg);
230 handles_pub.publish(handle_list_msg);
void initParams(ros::NodeHandle node)
Read the parameters from a ROS launch file.
void publish(const boost::shared_ptr< M > &message) const
Sampling localizes grasp affordances using importance sampling.
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.
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.
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.
visualization_msgs::MarkerArray MarkerArray
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.
std::string getPCDFile()
Return the *.pcd file given by the corresponding parameter in the ROS launch file.
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
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...
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...
void setAffordances(Affordances &affordances)
void chatterCallback(const sensor_msgs::PointCloud2ConstPtr &input)
std::vector< std::vector< CylindricalShell > > g_handles
const std::string RANGE_SENSOR_TOPIC
pcl::PointCloud< pcl::PointXYZRGBA > PointCloud
Messages creates custom ROS messages to publish the results of the localization. The messages that ca...
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
void initParams(const ros::NodeHandle &node)
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)
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.