Hello,
I recently started using the message_filters::Cache and it seems that
only messages, containing a Header element, can be used out of the box.
For what I found out, if I place a Header element in the message
definition file (Something.msg) the generated C++ header file
automatically contains the required function:
static ros::Time ros::message_traits::TimeStamp<M>::value( const M& m );
If I don't include the Header element, this function does not exist and
the Cache cannot be used.
For my personal needs I don't require all the information in the Header
element. A simple time element would suffice. Also, I don't see why the
cache would need more than a simple timestamp. But, from what I found
out, if I replace the Header element with a simple time element, the
required message traits are not generated, thus the Cache doesn't work
(or even compile).
As a workaround I found out, that I can define the required message
traits myself like so:
Assuming my message definition file (Something.msg) starts with:
time stamp
...
If I put the following code fragment somewhere in my code before I start
using the Cache, it's working:
namespace ros
{
namespace message_traits
{
template<>
struct TimeStamp<Something>
{
static ros::Time* pointer( Something& m )
{
return &m.stamp;
}
static ros::Time const* pointer( const Something& m )
{
return &m.stamp;
}
static ros::Time value( const Something& m )
{
return m.stamp;
}
};
} // namespace message_traits
} // namespace ros
Finally, my question: Is there a way to let the shown code fragment be
generated automatically as it will be if I used the Header element? Or
to put it differently: Can I somehow mark a time element in the message
definition file, such that the code fragment is automatically appended
to the generated c++ header?
Thanks,
Sebastian