ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Without adding a class (which would be best) or globals, you can pass easily an extra parameter to your callback, something like this:
void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
message_filters::Cache<capygroovy::Ticks> &ticks_cache)
{
......
ticks = ticks_cache.getInterval(last,msg3->header.stamp);
......
}
int main(int argc, char** argv)
{
......
sync.registerCallback(boost::bind(&callback, _1, _2, _3, ticks_cache));
......
return 0;
}
It really is as simple as that!
2 | No.2 Revision |
Without adding a class (which would be best) or globals, you can pass easily an extra parameter to your callback, something like this:
void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
message_filters::Cache<capygroovy::Ticks> &ticks_cache)
{
......
ticks = ticks_cache.getInterval(last,msg3->header.stamp);
......
}
int main(int argc, char** argv)
{
......
sync.registerCallback(boost::bind(&callback, _1, _2, _3, ticks_cache));
......
return 0;
}
It really is as simple as that!
BTW, to make classes easier to create, we use a template like this:
template <typename T>
int NodeMain(int argc, char **argv, std::string const &nodeName)
{
ros::init(argc, argv, nodeName);
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
T a(nh, pnh);
ros::spin();
return EXIT_SUCCESS;
}
Now you just need:
class MyNode
{
private:
void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
message_filters::Cache<capygroovy::Ticks> &ticks_cache)
{ ... }
public:
MyNode(ros::NodeHandle publicNodeHandle, ros::NodeHandle privateNodeHandle)
{
....
sync.registerCallback(boost::bind(&callback, this, _1, _2, _3, ticks_cache));
....
}
}
int main(int argc, char **argv) { NodeMain<mynode>(argc, argv, "MyNode"); }
We also have a slightly more complicated template for a nodelet
, and it means we can use class MyNode
as either a stand-alone node or a nodelet without any code changes.
3 | No.3 Revision |
Without adding a class (which would be best) or globals, you can pass easily an extra parameter to your callback, something like this:
void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
message_filters::Cache<capygroovy::Ticks> &ticks_cache)
{
......
ticks = ticks_cache.getInterval(last,msg3->header.stamp);
......
}
int main(int argc, char** argv)
{
......
sync.registerCallback(boost::bind(&callback, _1, _2, _3, ticks_cache));
......
return 0;
}
It really is as simple as that!
BTW, to make classes easier to create, we use a template like this:
template <typename T>
int NodeMain(int argc, char **argv, std::string const &nodeName)
{
ros::init(argc, argv, nodeName);
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
T a(nh, pnh);
ros::spin();
return EXIT_SUCCESS;
}
Now you just need:
class MyNode
{
private:
void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
message_filters::Cache<capygroovy::Ticks> &ticks_cache)
{ ... }
public:
MyNode(ros::NodeHandle publicNodeHandle, ros::NodeHandle privateNodeHandle)
{
....
sync.registerCallback(boost::bind(&callback, this, _1, _2, _3, ticks_cache));
....
}
}
int main(int argc, char **argv)
{
NodeMain<mynode>(argc, {
NodeMain<MyNode>(argc, argv, "MyNode");
}
We also have a slightly more complicated template for a nodelet
, and it means we can use class MyNode
as either a stand-alone node or a nodelet without any code changes.