How to use waitForMessage properly ?
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 ...