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

PCL Pointcloud type conversion/pointer issue

asked 2016-09-28 08:13:44 -0500

anonymous user

Anonymous

updated 2016-09-29 03:42:52 -0500

As I want to get used to the PCL library, I tried to test switching between PointCloud and PointCloud2 types. The node corresponding to the following callback function compiles, but produces a segmentation error. The problem occurs 100% in the code fragment after // OPTIONAL: Perform voxel filtering provided below. It is likely due to making mistakes when converting the types or confusing pointers (kinda new to C++). Any help is appreciated.

void 
cloud_cb (const sensor_msgs::PointCloud2ConstPtr& input)
{
  // convert sensor_msgs to PointCloud
  pcl::PointCloud<pcl::PointXYZ> cloud;
  pcl::fromROSMsg (*input, cloud);

  // //////////////////////////////////////////////////////////////
  // OPTIONAL: Perform voxel filtering
  pcl::PCLPointCloud2Ptr cloud_unfiltered;
  pcl::toPCLPointCloud2(cloud, *cloud_unfiltered); // LINE 29!!
  pcl::PCLPointCloud2ConstPtr cloudPtr(cloud_unfiltered);
  pcl::PCLPointCloud2 cloud_filtered;

  pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
  sor.setInputCloud (cloudPtr);
  sor.setLeafSize (0.1, 0.1, 0.1);
  sor.filter (cloud_filtered);

  pcl::fromPCLPointCloud2(cloud_filtered, cloud);
  // /////////////////////////////////////////////////////////////

gdb backtrace:

    Program received signal SIGSEGV, Segmentation fault.
    0x0000000000413a36 in pcl::toPCLPointCloud2<pcl::PointXYZ> (cloud=..., msg=...)
        at /usr/include/pcl-1.7/pcl/conversions.h:248
    248       msg.height = cloud.height;
    (gdb) bt
    #0  0x0000000000413a36 in pcl::toPCLPointCloud2<pcl::PointXYZ> (cloud=..., 
        msg=...) at /usr/include/pcl-1.7/pcl/conversions.h:248
    #1  0x000000000040d498 in cloud_cb (input=...)
        at /home/mma7rng/catkin_ws/src/pcl_planar_segmentation/src/pcl_planar_segmentation_node.cpp:29
    #2  0x0000000000411b4b in operator() (a0=..., this=<optimized out>)
        at /usr/include/boost/function/function_template.hpp:767
    #3  boost::detail::function::void_function_obj_invoker1<boost::function<void (boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&)>, void, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> >::invoke(boost::detail::function::function_buffer&, boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const>) (function_obj_ptr=..., 
        a0=...) at /usr/include/boost/function/function_template.hpp:153
    #4  0x00000000004168d8 in operator() (a0=..., this=0x6360b8)
        at /usr/include/boost/function/function_template.hpp:767
    #5  ros::SubscriptionCallbackHelperT<boost::shared_ptr<sensor_msgs::PointCloud2_<std::allocator<void> > const> const&, void>::call (this=0x6360b0, params=...)
        at /opt/ros/jade/include/ros/subscription_callback_helper.h:144
    #6  0x00007ffff646a6b5 in ros::SubscriptionQueue::call() ()
       from /opt/ros/jade/lib/libroscpp.so
    #7  0x00007ffff6424107 in ros::CallbackQueue::callOneCB(ros::CallbackQueue::TLS*) () from /opt/ros/jade/lib/libroscpp.so
    #8  0x00007ffff6424c33 in ros::CallbackQueue::callAvailable(ros::WallDuration)
() from /opt/ros/jade/lib/libroscpp.so
#9  0x00007ffff646d1e5 in ros::SingleThreadedSpinner::spin(ros::CallbackQueue*)
    () from /opt/ros/jade/lib/libroscpp.so
#10 0x00007ffff6454e0b in ros::spin() () from /opt/ros/jade/lib/libroscpp.so
#11 0x000000000040cea9 in main (argc=1, argv=0x7fffffffd948)
    at /home/mma7rng/catkin_ws/src/pcl_planar_segmentation/src/pcl_planar_segmentation_node.cpp:107
edit retag flag offensive close merge delete

Comments

Can you copy what the error says?

alienmon gravatar image alienmon  ( 2016-09-29 02:35:14 -0500 )edit

I edited the backtrace error from gdb. The initial program is running well and removes planes from pointclouds. The voxel filtering works well in another node. However, due to these functions needing different inputs (Pointcloud and Pointcloud2 respectively), I had to convert and got the error.

anonymous userAnonymous ( 2016-09-29 03:37:48 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2016-10-04 08:38:32 -0500

mjcarroll gravatar image

I believe that you need to initialize the PCLPointCloud2. Currently, it appears that you are dereferencing an uninitialized pointer.

pcl::PCLPointCloud2Ptr cloud_unfiltered(new pcl::PointCloud2());
pcl::toPCLPointCloud2(cloud, *cloud_unfiltered); // LINE 29!!

Or, skip the pointer.

pcl::PCLPointCloud2 cloud_unfiltered;
pcl::toPCLPointCloud2(cloud, cloud_unfiltered);
edit flag offensive delete link more

Comments

Both versions do not work. The error for the first part:

error: expected type-specifier
   pcl::PCLPointCloud2Ptr cloud_unfiltered(new pcl::PointCloud2());
anonymous userAnonymous ( 2016-10-05 06:39:40 -0500 )edit
1

Ah, sorry, that should be

pcl::PCLPointCloud2Ptr cloud_unfiltered(new pcl::PCLPointCloud2());
mjcarroll gravatar image mjcarroll  ( 2016-10-06 12:10:11 -0500 )edit

well, I could have noticed that :D Thanks, that was it! It works now. So I guess the problem was that pcl::PCLPointCloud2Ptr needs a pcl::PCLPointCloud2 object as an input for the constructor in order to point to it.

anonymous userAnonymous ( 2016-10-07 03:52:45 -0500 )edit

Yes, the pcl::PCLPointCloud2Ptr type should just be a boost::shared_ptr, you you either need to give a raw pointer to the constructor or use boost::make_shared.

mjcarroll gravatar image mjcarroll  ( 2016-10-17 20:24:41 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-09-28 08:13:44 -0500

Seen: 7,480 times

Last updated: Oct 04 '16