ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
The wiki page on the cache wasn't really helpful, but I figured out a few problems in your code.
There needs to be an implementation of message_traits::TimeStamp. Have a look here. I guess the reason is that the cache needs to ensure the messages to be ordered. All stamped data types, e.g. geometry_msgs/PoseStamped already implement the time stamp. Either implement the traits for the message type you want to use or use a stamped type.
For some reason, the compiler refused to resolve the types correctly in the registerCallback method call. By explicitly constructing a boost::function, 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 &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::function<void(const geometry_msgs::PoseStamped &)>(&some_function));
return ros::spin();
}
2 | No.2 Revision |
The wiki page on the cache wasn't really helpful, but I figured out a few problems in your code.
There needs to be an implementation of message_traits::TimeStamp. Have a look here. I guess the reason is that the cache needs to ensure the messages to be ordered. order the messages. All stamped data types, e.g. geometry_msgs/PoseStamped already implement the time stamp. stamp trait. Either implement the traits for the message type you want to use or use a stamped type.
For some reason, the compiler refused to resolve the types correctly in the registerCallback method call. By explicitly constructing a boost::function, 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 &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::function<void(const geometry_msgs::PoseStamped &)>(&some_function));
return ros::spin();
}
3 | No.3 Revision |
The wiki page on the cache wasn't really helpful, but I figured out a few problems in your code.
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.
For some reason, the compiler refused refuses to resolve the types correctly in the registerCallback method call. By explicitly constructing a boost::function, 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 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::function<void(const geometry_msgs::PoseStamped &)>(&some_function));
cache.registerCallback(boost::bind(&some_function, _1));
ros::spin();
return ros::spin();
0;
}