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

RGBDSLAM Problem compilation (fuerte and cv 2.4.0)( solved)

asked 2012-05-08 01:57:50 -0500

updated 2014-01-28 17:12:15 -0500

ngrennan gravatar image

Hello I'm compiling the rgbdslam (like http://www.ros.org/wiki/rgbdslam). And i get problems:

(Ubuntu 12.04; ROS Fuert; PCL 1.5.1; OpenCv 2.3.1(in OS) and opencv 2.4.0 (in ros))

UPDATE RESOLUTION

In rgbdslam/src/openni_listener.cpp:

//#include "pcl/common/transform.h" (i think this not exist yet! is now transforms.h)
...
//#include "pcl/ros/for_each_type.h" (libpcl1.5, don't have this?!)

in rgbdslam/src/glviewer.cpp (add):

#include "GL/glut.h"
...
#include "boost/foreach.hpp"
#include "pcl/point_types.h"
...
template <typename PointType>
inline bool hasValidXYZ(const PointType& p){
      return std::isfinite(p.x) && std::isfinite(p.y) && std::isfinite(p.z);
};

in rgbdslam/src/misc.cpp (add):

#include "opencv2/core/core.hpp"
#include "opencv2/features2d/features2d.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "opencv2/nonfree/nonfree.hpp"

...

// based on http://answers.ros.org/question/30249/minimal-topics-for-rgbdslam

  sensor_msgs::ImagePtr rgb_msg(new sensor_msgs::Image);
  rgb_msg->header = rgb_msg1->header;
  rgb_msg->height = rgb_msg1->height;
  rgb_msg->width = rgb_msg1->width;
  rgb_msg->encoding = rgb_msg1->encoding;
  rgb_msg->is_bigendian = rgb_msg1->is_bigendian;
  rgb_msg->step = rgb_msg1->step;
  rgb_msg->data = rgb_msg1->data;

  if (rgb_msg->encoding.compare("bgr8") == 0) {
    rgb_msg->encoding = "rgb8";
    for (int i=0; i<rgb_msg->data.size(); i+=3) {
      char temp_red = rgb_msg->data[i];
      rgb_msg->data[i] = rgb_msg->data[i+2];
      rgb_msg->data[i+2] = temp_red;
    }
  }



....
in line 287
   fd = new SiftFeatureDetector(); //SIFT::DetectorParams::GET_DEFAULT_THRESHOLD(),
                                     //SIFT::DetectorParams::GET_DEFAULT_EDGE_THRESHOLD());
        ROS_INFO("Default SIFT threshold:"); /*%f, Default SIFT Edge Threshold: %f",
                 SIFT::DetectorParams::GET_DEFAULT_THRESHOLD(),
                 SIFT::DetectorParams::GET_DEFAULT_EDGE_THRESHOLD());*/

...
in line 310:
  fd = new OrbFeatureDetector();//params->get<int>("max_keypoints"),
                //ORB::CommonParams(1.2, ORB::CommonParams::DEFAULT_N_LEVELS, 31, ORB::CommonParams::DEFAULT_FIRST_LEVEL));
    }

in CMAKEFILE

SET(LIBS_LINK GL GLU -lgl2ps ${G2O_LIBS} ${QT_LIBRARIES} ${QT_QTOPENGL_LIBRARY} ${GLUT_LIBRARY} ${OPENGL_LIBRARY} ${OpenCV_LIBS} -lboost_signals)

And now appears to work :) :D ;)

edit retag flag offensive close merge delete

Comments

What ROS, PCL and OpenCV version do you use?

Felix Endres gravatar image Felix Endres  ( 2012-05-08 06:20:55 -0500 )edit

Ubuntu 12.04; ROS Fuert; PCL 1.5.1; OpenCv 2.4.0 (update not 2.3.1)

Filipe Santos gravatar image Filipe Santos  ( 2012-05-08 06:24:12 -0500 )edit

4 Answers

Sort by ยป oldest newest most voted
1

answered 2012-05-08 02:28:06 -0500

munhoney gravatar image

you should change function name (hasValidXYZ -> isFinite) :-)

Because of version change, I change lots of things.

However, it doesn't work well. (Now I'm searching the problems)

edit flag offensive delete link more

Comments

Yeh, I'm facing another troubles :)

Filipe Santos gravatar image Filipe Santos  ( 2012-05-08 04:21:15 -0500 )edit
1

answered 2012-05-31 15:23:09 -0500

Toaster gravatar image

Hey,

Your work here really helped me out, thanks!

One thing I found was that the hasValidXYZ function needed to be altered such that it becomes:

template <typename PointType>
inline bool hasValidXYZ(const PointType& p){
      return std::isfinite(p.x) && std::isfinite(p.y) && std::isfinite(p.z);
};

I have no idea why (I'm a ROS novice), but changing

template "typename PointType"

to

template <typename PointType>

and adding the trailing semi-colon sorted out the majority of my problems, and things compiled cleanly.

Thanks again,

Cameron

edit flag offensive delete link more

Comments

Same here (on electric emys though)

Felix Endres gravatar image Felix Endres  ( 2012-06-03 10:18:57 -0500 )edit

Sorry that was my mistake (here in this forum), because i don't know what correct tags should i use in this forum to put code.

Filipe Santos gravatar image Filipe Santos  ( 2012-06-03 21:57:51 -0500 )edit
0

answered 2012-05-31 15:18:28 -0500

Toaster gravatar image

Hey,

Your guide saved me days (weeks?) of fooling around getting rgbdslam to compile, thanks!

One small note, I was getting grief from rosmake until I changed hasValidXYZ to be:

template <typename PointType>
inline bool hasValidXYZ(const PointType& p){
      return std::isfinite(p.x) && std::isfinite(p.y) && std::isfinite(p.z);
};

After that, all was well. Now I have to test it!

Thanks again,

Cameron

edit flag offensive delete link more
0

answered 2012-06-06 04:56:03 -0500

I have included most of the changes (those that do not break rgbdslam for electric) in the latest svn version. The color issue should be solved without the above change, please tell me if that is not the case.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2012-05-08 01:57:50 -0500

Seen: 990 times

Last updated: Jun 06 '12