ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Publishing a pointcloud problem

asked 2012-08-17 05:59:22 -0500

David Bravo gravatar image

updated 2016-10-24 08:34:08 -0500

ngrennan gravatar image

Hello, I'm trying to publish a pointcloud that contains the narfkeypoints extracted from a range image with the following code:

#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/CameraInfo.h>

// PCL specific includes
#include <pcl/ros/conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/filters/voxel_grid.h>

#include <pcl/features/narf.h>
#include <pcl/keypoints/narf_keypoint.h>
#include <pcl/range_image/range_image.h>
#include <pcl/features/range_image_border_extractor.h>
#include <pcl/range_image/range_image_planar.h>

typedef pcl::PointCloud<pcl::PointCloud<int> > PointCloud;
typedef pcl::PointXYZ PointType;

ros::Publisher pub;

pcl::PointCloud<int> keypoint_indices;

pcl::PointCloud<pcl::PointXYZ>::Ptr keypoints_ptr (new pcl::PointCloud<pcl::PointXYZ>);
pcl::PointCloud<pcl::PointXYZ>& keypoints = *keypoints_ptr;


float angular_resolution_;
float support_size_ =0.2f;//-0.1f

void depthimage_cb(const sensor_msgs::ImageConstPtr &depth_msg)
{
    const uint16_t* depthImage = reinterpret_cast<const uint16_t*>(&depth_msg->data[0]);

    pcl::RangeImagePlanar range_image_;
    pcl::RangeImageBorderExtractor range_image_border_extractor_;

    // convert the depth-image to a pcl::rangeImage
    angular_resolution_ = (float)(-1);
    range_image_.setDepthImage(depthImage,depth_msg->width, depth_msg->height, (depth_msg->width)/2, (depth_msg->height)/2, 600.0, 600.0, angular_resolution_);

    range_image_.setUnseenToMaxRange();
    pcl::NarfKeypoint keypoint_det;

    // extract the indices of the NARF-Keypoints
    keypoint_det.getParameters ().support_size =  support_size_;
    keypoint_det.setRangeImageBorderExtractor (&range_image_border_extractor_);
    keypoint_det.setRangeImage (&range_image_);
    keypoint_det.compute (keypoint_indices);

    keypoints.points.resize (keypoint_indices.points.size ());
    for (size_t i=0; i<keypoint_indices.points.size (); ++i)
    keypoints.points[i].getVector3fMap () = range_image_.points[keypoint_indices.points[i]].getVector3fMap ();
   // pub.publish (keypoints);
} 

int
main (int argc, char** argv)
{
  // Initialize ROS
  ros::init (argc, argv, "keypointsplanar");
  ros::NodeHandle nh1;
  ros::NodeHandle nh2;

  // Create a ROS subscriber for the input point cloud
  ros::Subscriber sub2 = nh1.subscribe ("/camera/depth/image", 1, depthimage_cb);   

  // Create a ROS publisher for the output point cloud
  //pub = nh2.advertise<pcl::PointCloud<pcl::PointXYZ>& keypoints> ("keypoints", 1);

  // Spin
  ros::spin ();
}

If I comment the pub.publish (keypoints); and the pub = nh2.advertise<pcl::pointcloud<pcl::pointxyz>& keypoints> ("keypoints", 1); lines the code compiles with no problems or warnings, however, if I uncomment them I keep getting these errors:

{-------------------------------------------------------------------------------[ rosmake ] [ make ] [ tesis: 11.3 sec ] [ 1 Active 29/30 Complete ] from /home/jumpei/fuerte_workspace/tesis/src/keypointsplanar.cpp:1: /opt/ros/fuerte/include/ros/message_traits.h: In static member function ‘static const char* ros::message_traits::MD5Sum<m>::value(const M&) [with M = pcl::PointCloud<pcl::pointxyz>]’: /opt/ros/fuerte/include/ros/message_traits.h:255:104: instantiated from ‘const char* ros::message_traits::md5sum(const M&) [with M = pcl::PointCloud<pcl::pointxyz>]’ /opt/ros/fuerte/include/ros/publisher.h:112:7: instantiated from ‘void ros::Publisher::publish(const M&) const [with M = pcl::PointCloud<pcl::pointxyz>]’ /home/jumpei/fuerte_workspace/tesis/src/keypointsplanar.cpp:57:27: instantiated from here /opt/ros/fuerte/include/ros/message_traits.h:126:34: error: ‘const class pcl::PointCloud<pcl::pointxyz>’ has no member named ‘__getMD5Sum’ /opt/ros/fuerte/include/ros/message_traits.h: In static member function ‘static const char* ros::message_traits::DataType<m>::value(const M&) [with M = pcl::PointCloud<pcl::pointxyz>]’: /opt/ros/fuerte/include/ros/message_traits.h:264:106: instantiated from ‘const char* ros::message_traits::datatype(const M&) [with M = pcl::PointCloud<pcl::pointxyz ... (more)

edit retag flag offensive close merge delete

Comments

What versions of ROS and PCL are you using, and what OS are you on?

jbohren gravatar image jbohren  ( 2012-08-18 01:15:31 -0500 )edit

Thank you Allenh, I wasn't including pcl_ros/point_cloud.h. Now I feel stupid. I'm using ROS Fuerte and the ros-fuerte-perception-pcl-fuerte-unstable package because I need the NARF keypoints. Now the topic is published but I can't see it in RVIZ because I get a "No message received" error.

David Bravo gravatar image David Bravo  ( 2012-08-20 06:47:02 -0500 )edit
David Bravo gravatar image David Bravo  ( 2012-08-20 06:51:49 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2012-08-19 06:41:52 -0500

allenh1 gravatar image
edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2012-08-17 05:59:22 -0500

Seen: 9,085 times

Last updated: Aug 19 '12