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

ROS Fuerte and PCL from source on ARM / Hard-float support

asked 2012-06-25 06:20:49 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

Hi guys,

Unfortunately, I can't use the apt-get install ros-fuerte-pcl command and need an installation from source. (I'm using an ARM board and Ubuntu 12.04) I'm asking because it seems that in the new ROS Fuerte setup the PCL Library is not included and is seen as an external system dependency.

When i use $roslocate info pcl I get the following output:

But this website doesn't exist. But there seems to be a special PCL version for ROS (see the Willow Garage repository [https://github.com/wg-debs/pcl-release] ) saw that at answers.ros.org (link)

So i tried to compile the code from WG with the USE_ROS option on ON and it fails to compile with the following failure.

[  1%] Built target gtest 
[  1%] Built target gtest_main 
[  8%] Built target pcl_common 
[  9%] Built target pcl_kdtree 
[ 10%] Built target pcl_octree 
[ 12%] Built target pcl_search 
[ 23%] Built target pcl_sample_consensus 
[ 23%] Built target pcl_geometry 
[ 26%] Built target pcl_segmentation 
[ 26%] Building CXX object io/CMakeFiles/pcl_io_ply.dir/src/ply/ply_parser.cpp.o 
In file included from /home/panda/ros/pcl-release/io/include/pcl/io/ply/ply.h:45:0, 
                 from /home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h:61, 
                 from /home/panda/ros/pcl-release/io/src/ply/ply_parser.cpp:41: 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/byte_order.h:65:4: error: #error 
In file included from /home/panda/ros/pcl-release/io/include/pcl/io/ply/ply.h:45:0, 
                 from /home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h:61, 
                 from /home/panda/ros/pcl-release/io/src/ply/ply_parser.cpp:41: 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/byte_order.h:77:4: error: #error 
In file included from /home/panda/ros/pcl-release/io/src/ply/ply_parser.cpp:41:0: 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h: In member function ‘bool pcl::io::ply::ply_parser::parse_scalar_property(pcl::io::ply::format_type, std::istream&, const typename pcl::io::ply::ply_parser::scalar_property_callback_type<ScalarType>::type&)’: 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h:577:51: error: ‘host_byte_order’ was not declared in this scope 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h: In member function ‘bool pcl::io::ply::ply_parser::parse_list_property(pcl::io::ply::format_type, std::istream&, const typename pcl::io::ply::ply_parser::list_property_begin_callback_type<SizeType, ScalarType>::type&, const typename pcl::io::ply::ply_parser::list_property_element_callback_type<SizeType, ScalarType>::type&, const typename pcl::io::ply::ply_parser::list_property_end_callback_type<SizeType, ScalarType>::type&)’: 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h:648:51: error: ‘host_byte_order’ was not declared in this scope 
/home/panda/ros/pcl-release/io/include/pcl/io/ply/ply_parser.h:674:53: error: ‘host_byte_order’ was not declared in this scope 
make[2]: *** [io/CMakeFiles/pcl_io_ply.dir/src/ply/ply_parser.cpp.o] Error 1 
make[1]: *** [io/CMakeFiles/pcl_io_ply.dir/all] Error 2 
make: *** [all] Error 2

Would be great to get your thoughts about ... (more)

edit retag flag offensive close merge delete

Comments

Is this ROS Fuerte or Electric?

Eric Perko gravatar image Eric Perko  ( 2012-06-25 13:06:37 -0500 )edit

2 Answers

Sort by » oldest newest most voted
1

answered 2012-09-04 04:24:56 -0500

this post is marked as community wiki

This post is a wiki. Anyone with karma >75 is welcome to improve it.

The PCL-developers did a great job over the weekend and pushed things further . Its now possible to use pcl 1.7 beside an existing pcl installation for ROS respectively as working pcl source for an ARM-board (Thumps up)

To use this 1.7 trunk version as source for your ROS there are some tricks to do. ( My objective was it to run openni_launch -> which depends on depth_image_proc -> which needs pcl )

Here's what you need to do:

1) $ svn co http://svn.pointclouds.org/ros/trunk/perception_pcl_fuerte_unstable/

2) $ roscd pcl17_ros && make

3) check out https://code.ros.org/svn/ros-pkg/stacks/image_pipeline/trunk/depth_image_proc/ (URL taken from here: http://ros.org/wiki/depth_image_proc), add it to your ROS_PACKAGE_PATH in front of all the rest.

4) go to depth_image_proc and apply the patch (which is basically changing includes and namespaces from pcl to pcl17) attached to this post and make, i.e.:

$ roscd depth_image_proc 
$ patch -p0 < pcl17_trunk.patch 
$ make

I hope I saved someones time :)

patch:

Because I can't upload a patch file. Just copy this into a new createt file named pcl17_trunk.patch

Index: manifest.xml
===================================================================
--- manifest.xml    (revision 40052)
+++ manifest.xml    (working copy)
@@ -24,8 +24,8 @@
   <depend package="image_transport"/>
   <depend package="message_filters"/>
   <depend package="nodelet"/>
-  <depend package="pcl"/>
-  <depend package="pcl_ros"/>
+  <depend package="pcl17"/>
+  <depend package="pcl17_ros"/>
   <depend package="roscpp"/>
   <depend package="sensor_msgs"/>
   <depend package="stereo_msgs"/>
Index: src/nodelets/point_cloud_xyz.cpp
===================================================================
--- src/nodelets/point_cloud_xyz.cpp    (revision 40052)
+++ src/nodelets/point_cloud_xyz.cpp    (working copy)
@@ -1,8 +1,8 @@
 #include <ros/ros.h>
 #include <nodelet/nodelet.h>
 #include <image_transport/image_transport.h>
-#include <pcl_ros/point_cloud.h>
-#include <pcl/point_types.h>
+#include <pcl17_ros/point_cloud.h>
+#include <pcl17/point_types.h>
 #include <sensor_msgs/image_encodings.h>
 #include <image_geometry/pinhole_camera_model.h>
 #include <boost/thread.hpp>
@@ -21,7 +21,7 @@

   // Publications
   boost::mutex connect_mutex_;
-  typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
+  typedef pcl17::PointCloud<pcl17::PointXYZ> PointCloud;
   ros::Publisher pub_point_cloud_;

   image_geometry::PinholeCameraModel model_;
@@ -119,7 +119,7 @@
   {
     for (int u = 0; u < (int)cloud_msg->width; ++u)
     {
-      pcl::PointXYZ& pt = *pt_iter++;
+      pcl17::PointXYZ& pt = *pt_iter++;
       T depth = depth_row[u];

       // Missing points denoted by NaNs
Index: src/nodelets/point_cloud_xyzrgb.cpp
===================================================================
--- src/nodelets/point_cloud_xyzrgb.cpp (revision 40052)
+++ src/nodelets/point_cloud_xyzrgb.cpp (working copy)
@@ -5,8 +5,8 @@
 #include <message_filters/subscriber.h>
 #include <message_filters/synchronizer.h>
 #include <message_filters/sync_policies/approximate_time.h>
-#include <pcl_ros/point_cloud.h>
-#include <pcl/point_types.h>
+#include <pcl17_ros/point_cloud.h>
+#include <pcl17/point_types.h>
 #include <sensor_msgs/image_encodings.h>
 #include <image_geometry/pinhole_camera_model.h>
 #include "depth_traits.h"
@@ -45,7 +45,7 @@

   // Publications
   boost::mutex connect_mutex_;
-  typedef pcl::PointCloud<pcl::PointXYZRGB> PointCloud;
+  typedef pcl17::PointCloud<pcl17::PointXYZRGB> PointCloud;
   ros::Publisher pub_point_cloud_;

   image_geometry::PinholeCameraModel model_;
@@ -243,7 +243,7 @@
   {
     for (int u = 0; u < (int)cloud_msg->width; ++u, rgb += color_step)
     {
-      pcl::PointXYZRGB& pt = *pt_iter++;
+      pcl17::PointXYZRGB& pt = *pt_iter++;
       T depth = depth_row[u];

       // Check for invalid measurements
edit flag offensive delete link more

Comments

Be aware that this patch only fixes depth_image_proc. You will need to make similar changes to every other package you build that uses pcl.

joq gravatar image joq  ( 2012-09-04 05:57:10 -0500 )edit
0

answered 2012-09-01 10:21:12 -0500

joq gravatar image

updated 2012-09-03 13:33:41 -0500

In PCL 2.0, these ROS integration problems should finally be solved.

There is an interim PCL 1.7 solution in perception_pcl_fuerte_unstable. Follow the recently-updated "Integration with ROS" directions in the PCL Downloads page.

UPDATE: Apparently, the PCL 1.7 package lives in the pcl17 namespace. You can use that to experiment with new PCL features, but it does not provide the pcl namespace objects needed by openni_launch.

Please open a high-priority defect ticket, to get this problem fixed. Link back to this question for the details.

edit flag offensive delete link more

Comments

Hi! I can't even try PCL 1.7, my projects can't find the Eigen include files, even though they're installed in the system, and with PCL 1.5 (the one which comes installed by default with ROS) I have no problem with that.

Pedro gravatar image Pedro  ( 2012-09-06 05:10:31 -0500 )edit

@dinamex@joq it seems that you have a pandaboard with a running openni_launch? for me it still doesn't work after a LOT of hours of work... so i am going to ask if you could maybe upload an image of your system, please. i would be very thankful for this and i know it could be some gigabyte...

RodBelaFarin gravatar image RodBelaFarin  ( 2012-12-04 05:56:32 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2012-06-25 06:20:49 -0500

Seen: 1,974 times

Last updated: Sep 04 '12