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

How to use waitForMessage properly ?

asked 2018-06-12 04:18:12 -0500

antonin_haulot gravatar image

updated 2018-06-19 04:30:29 -0500

Hello everyone !

I am trying to use the function ros:topic::waitForMessage in order to get one time a nav_msgs::Path message. As waitForMessage is overloaded, I am using the following definition :

boost::shared_ptr<M const> ros::topic::waitForMessage (const std::string &topic, ros::NodeHandle &nh )

Here is the extract of my main where is located the function :

int main(int argc, char *argv[]){
  ros::init(argc, argv, "create_path");
  ros::NodeHandle create_path;
  nav_msgs::Path path = ros::topic::waitForMessage("/path_planned/edge", create_path);
  ros::Rate loop_rate(1);
  while (ros::ok()){
    loop_rate.sleep();
  }
  return 0;
}

My problem is that I don't get how to use properly this function. When I catkin_make this code, I get these errors :

/home/stagiaire019/astek_ws/src/coverage_path_planning/src/create_path.cpp: In function ‘int main(int, char**)’:
/home/stagiaire019/astek_ws/src/coverage_path_planning/src/create_path.cpp:63:86: error: no matching function for call to ‘waitForMessage(const char [19], ros::NodeHandle&)’
   nav_msgs::Path &path = ros::topic::waitForMessage("/path_planned/edge", create_path);
                                                                                      ^
In file included from /opt/ros/kinetic/include/ros/ros.h:55:0,
                 from /home/stagiaire019/astek_ws/src/coverage_path_planning/src/create_path.cpp:1:
/opt/ros/kinetic/include/ros/topic.h:135:28: note: candidate: template<class M> boost::shared_ptr<const M> ros::topic::waitForMessage(const string&, ros::NodeHandle&)
 boost::shared_ptr<M const> waitForMessage(const std::string& topic, ros::NodeHandle& nh)
                            ^
/opt/ros/kinetic/include/ros/topic.h:135:28: note:   template argument deduction/substitution failed:
/home/stagiaire019/astek_ws/src/coverage_path_planning/src/create_path.cpp:63:86: note:   couldn’t deduce template parameter ‘M’
   nav_msgs::Path &path = ros::topic::waitForMessage("/path_planned/edge", create_path);
                                                                                      ^
coverage_path_planning/CMakeFiles/create_path.dir/build.make:62: recipe for target 'coverage_path_planning/CMakeFiles/create_path.dir/src/create_path.cpp.o' failed
make[2]: *** [coverage_path_planning/CMakeFiles/create_path.dir/src/create_path.cpp.o] Error 1
CMakeFiles/Makefile2:1371: recipe for target 'coverage_path_planning/CMakeFiles/create_path.dir/all' failed
make[1]: *** [coverage_path_planning/CMakeFiles/create_path.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

After this error, I changed the line of waitForMessage in my program. There is the new line :

nav_msgs::Path path = ros::topic::waitForMessage<nav_msgs::Path>("/path_planned/edge", create_path);

I tried to catkin_make again and I got this new error :

/home/stagiaire019/astek_ws/src/coverage_path_planning/src/create_path.cpp: In function ‘int main(int, char**)’:
/home/stagiaire019/astek_ws/src/coverage_path_planning/src/create_path.cpp:63:67: error: conversion from ‘boost::shared_ptr<const nav_msgs::Path_<std::allocator<void> > >’ to non-scalar type ‘nav_msgs::Path {aka nav_msgs::Path_<std::allocator<void> >}’ requested
   nav_msgs::Path path = ros::topic::waitForMessage<nav_msgs::Path>("/path_planned/edge", create_path);
                                                                   ^
coverage_path_planning/CMakeFiles/create_path.dir/build.make:62: recipe for target 'coverage_path_planning/CMakeFiles/create_path.dir/src/create_path.cpp.o' failed
make[2]: *** [coverage_path_planning/CMakeFiles/create_path.dir/src/create_path.cpp.o] Error 1
CMakeFiles/Makefile2:1371: recipe for target 'coverage_path_planning/CMakeFiles/create_path.dir/all' failed
make[1]: *** [coverage_path_planning/CMakeFiles/create_path.dir/all] Error 2
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

I don't understand how ... (more)

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
5

answered 2018-06-12 14:40:47 -0500

knxa gravatar image

You need to understand shared pointers. Here is another question that shows a similar solution.

edit flag offensive delete link more

Comments

It worked ! Thank you !

I've edited my question to show the solution at the end.

antonin_haulot gravatar image antonin_haulot  ( 2018-06-13 04:19:47 -0500 )edit
1

@antonin_haulot can you please create an answer containing your solution rather than putting it in your question?

jayess gravatar image jayess  ( 2018-06-13 04:33:32 -0500 )edit
1

@jayess done !

antonin_haulot gravatar image antonin_haulot  ( 2018-06-19 04:31:29 -0500 )edit
11

answered 2018-06-19 04:30:51 -0500

antonin_haulot gravatar image

Here is my solution :

  boost::shared_ptr<nav_msgs::Path const> sharedEdge;
  nav_msgs::Path edge;
  sharedEdge = ros::topic::waitForMessage<nav_msgs::Path>("/path_planned/edge",create_path);
  if(sharedEdge != NULL){
    edge = *sharedEdge;
  }
edit flag offensive delete link more

Comments

This worked for me perfectly! Thank you

NagaDinesh1194 gravatar image NagaDinesh1194  ( 2019-03-06 21:13:54 -0500 )edit
4

All ROS messages define typedefs to make it easier to use the shared pointer version. For example, instead of boost::shared_ptr<nav_msgs::Path>, you can write nav_msgs::PathPtr or nav_msgs::Path::Ptr. Likewise, instead of boost::shared_ptr<nav_msgs::Path const>, you can write nav_msgs::PathConstPtr or nav_msgs::Path::ConstPtr.

cyberguy42 gravatar image cyberguy42  ( 2019-06-25 17:04:13 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-06-12 04:18:12 -0500

Seen: 13,840 times

Last updated: Jun 19 '18