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

Problem with message_filters::cache

asked 2012-09-11 08:41:28 -0500

Blizzard gravatar image

updated 2012-09-11 11:00:16 -0500

Hello,

i am trying to cache messages of a topic. Unfortunately i can't compile it.

I've read these examples yet:

http://www.ros.org/wiki/message_filters#Cache

http://mirror.umd.edu/roswiki/doc/unstable/api/message_filters/html/c++/

Thats a minimal example of my code:

#include "ros/ros.h"
#include "message_filters/subscriber.h"
#include "message_filters/cache.h"
#include "std_msgs/Int16.h"

void some_function (std_msgs::Int16 i)
{
    std::cout << "i = " << i.data << std::endl;
}

int main(int argc, char **argv)
{
    ros::init(argc, argv, "caching_example");
    ros::NodeHandle nh;

    message_filters::Subscriber<std_msgs::Int16> sub(nh, "some_topic", 1);
    message_filters::Cache<std_msgs::Int16> cache(sub, 100);

    cache.registerCallback(some_function);

    ros::spin();
}

The compiler output is:

blizzard@Blizzard-Kubuntu:~$ rosmake caching_example 
[ rosmake ] rosmake starting...
[ rosmake ] Packages requested are: ['caching_example']
[ rosmake ] Logging to directory /home/blizzard/.ros/rosmake/rosmake_output-20120911-224838
[ rosmake ] Expanded args ['caching_example'] to:
['caching_example']
[rosmake-0] Starting >>> roslang [ make]
[rosmake-0] Finished <<< roslang  No Makefile in package roslang
[rosmake-0] Starting >>> roscpp [ make ]
[rosmake-0] Finished <<< roscpp  No Makefile in package roscpp
[rosmake-0] Starting >>> caching_example [ make ]
[ rosmake ] Last 40 linesching_example: 16.8 sec ]
Active 2/3 Complete ]
{-------------------------------------------------------------------------------
  make[1]: Entering directory `/home/blizzard/ROS/caching_example/build'
  make[2]: Entering directory `/home/blizzard/ROS/caching_example/build'
  make[3]: Entering directory `/home/blizzard/ROS/caching_example/build'
  make[3]: Leaving directory `/home/blizzard/ROS/caching_example/build'
  [  0%] Built target rospack_genmsg_libexe
  make[3]: Entering directory `/home/blizzard/ROS/caching_example/build'
  make[3]: Leaving directory `/home/blizzard/ROS/caching_example/build'
  [  0%] Built target rosbuild_precompile
  make[3]: Entering directory `/home/blizzard/ROS/caching_example/build'
  make[3]: Leaving directory `/home/blizzard/ROS/caching_example/build'
  make[3]: Entering directory `/home/blizzard/ROS/caching_example/build'
  [100%] Building CXX object CMakeFiles/someTest.dir/src/test.o
  In file included from /opt/ros/fuerte/include/message_filters/subscriber.h:44:0,
                   from /home/blizzard/ROS/caching_example/src/test.cpp:2:
  /opt/ros/fuerte/include/message_filters/simple_filter.h: In member function ‘message_filters::Connection message_filters::SimpleFilter<M>::registerCallback(void (*)(P)) [with P = std_msgs::Int16_<std::allocator<void> >, M = std_msgs::Int16_<std::allocator<void> >]’:
  /home/blizzard/ROS/caching_example/src/test.cpp:19:41:   instantiated from here
  /opt/ros/fuerte/include/message_filters/simple_filter.h:96:100: error: no matching function for call to ‘message_filters::Signal1<std_msgs::Int16_<std::allocator<void> > >::addCallback(void (*&)(std_msgs::Int16_<std::allocator<void> >))’
  /opt/ros/fuerte/include/message_filters/simple_filter.h:96:100: note: candidate is:
  /opt/ros/fuerte/include/message_filters/signal1.h:91:22: note: template<class P> message_filters::Signal1<M>::CallbackHelper1Ptr message_filters::Signal1::addCallback(const boost::function<void(P)>&) [with P = P, M = std_msgs::Int16_<std::allocator<void> >, message_filters::Signal1<M>::CallbackHelper1Ptr = boost::shared_ptr<message_filters::CallbackHelper1<std_msgs::Int16_<std::allocator<void> > > >]
  In file included from /home/blizzard/ROS/caching_example/src/test.cpp:3:0:
  /opt/ros/fuerte/include/message_filters/cache.h: In member function ‘void message_filters::Cache<M>::add(const EventType&) [with M = std_msgs::Int16_<std::allocator<void> >, message_filters::Cache<M>::EventType = ros::MessageEvent<const std_msgs::Int16_<std::allocator<void> > >]’:
  /opt/ros/fuerte/include/message_filters/cache.h:330:5:   instantiated from ‘void message_filters::Cache<M>::callback(const EventType&) [with ...
(more)
edit retag flag offensive close merge delete

Comments

It would help to see your compiler output.

Lorenz gravatar image Lorenz  ( 2012-09-11 09:14:52 -0500 )edit

There it is :)

Blizzard gravatar image Blizzard  ( 2012-09-11 11:03:27 -0500 )edit

2 Answers

Sort by » oldest newest most voted
3

answered 2012-09-11 22:15:48 -0500

Lorenz gravatar image

updated 2012-09-11 22:19:54 -0500

The wiki page on the cache wasn't really helpful, but I figured out a few problems in your code.

  1. There needs to be an implementation of message_traits::TimeStamp. Have a look here. I guess the reason is that the cache needs to order the messages. All stamped data types, e.g. geometry_msgs/PoseStamped already implement the time stamp trait. Either implement the traits for the message type you want to use or use a stamped type.

  2. For some reason, the compiler refuses to resolve the types correctly in the registerCallback method call. By explicitly constructing a boost::function or by using boost::bind, I could resolve that.

I basically copied your code and changed the message type to PoseStamped. Here the new code:

#include <ros/ros.h>
#include <message_filters/subscriber.h>
#include <message_filters/cache.h>
#include <geometry_msgs/PoseStamped.h>

void some_function (const geometry_msgs::PoseStamped::ConstPtr &i) {
  // do something awesome
}

int main(int argc, char **argv) {
  ros::init(argc, argv, "caching_example");
  ros::NodeHandle nh;

  message_filters::Subscriber<geometry_msgs::PoseStamped> sub(nh, "some_topic", 1);
  message_filters::Cache<geometry_msgs::PoseStamped> cache(sub, 100);

  cache.registerCallback(boost::bind(&some_function, _1));

  ros::spin();
  return 0;
}
edit flag offensive delete link more
1

answered 2012-09-11 23:30:05 -0500

Blizzard gravatar image

updated 2012-09-12 02:10:37 -0500

Thanks a lot for your help. Now it works :)

What's important for everyone who has the same problem:

Don't forget to add these lines to your CMakeLists.txt

rosbuild_add_boost_directories()
rosbuild_link_boost(YOUR_PACKAGE_NAME thread signals system)

You also need to add the following to your manifest.xml

<depend package="message_filters"/>

I also rearranged my code a little bit because i wasn't able to access the cache otherwise. The following now works:

#include <ros/ros.h>
#include <message_filters/subscriber.h>
#include <message_filters/cache.h>
#include <geometry_msgs/PoseStamped.h>

message_filters::Cache<geometry_msgs::PoseStamped> cache;

void some_function (const geometry_msgs::PoseStamped::ConstPtr &msg)
{
    cache.add(msg);

    std::cout << "Oldest time cached is " << cache.getOldestTime() << std::endl;
    std::cout << "Last time received is " << cache.getLatestTime() << std::endl << std::endl;
}

int main(int argc, char **argv) {
  ros::init(argc, argv, "caching_example");
  ros::NodeHandle nh;

  cache.setCacheSize(100);
  ros::Subscriber sub = nh.subscribe("/some_topic", 1, some_function);

  ros::spin();
  return 0;
}
edit flag offensive delete link more

Comments

thanks to Blizzard! Your comments are big helps for me!

superql gravatar image superql  ( 2013-11-08 19:56:31 -0500 )edit

Question Tools

Stats

Asked: 2012-09-11 08:41:28 -0500

Seen: 2,113 times

Last updated: Sep 12 '12