28 #ifndef ROSLIB_MESSAGE_TRAITS_H 29 #define ROSLIB_MESSAGE_TRAITS_H 36 #include <boost/utility/enable_if.hpp> 37 #include <boost/type_traits/remove_const.hpp> 38 #include <boost/type_traits/remove_reference.hpp> 45 #define ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(msg, md5sum, datatype, definition) \ 48 namespace message_traits \ 50 template<> struct MD5Sum<msg> \ 52 static const char* value() { return md5sum; } \ 53 static const char* value(const msg&) { return value(); } \ 55 template<> struct DataType<msg> \ 57 static const char* value() { return datatype; } \ 58 static const char* value(const msg&) { return value(); } \ 60 template<> struct Definition<msg> \ 62 static const char* value() { return definition; } \ 63 static const char* value(const msg&) { return value(); } \ 71 namespace message_traits
80 static const bool value =
true;
90 static const bool value =
false;
121 return M::__s_getMD5Sum().c_str();
124 static const char*
value(
const M& m)
126 return m.__getMD5Sum().c_str();
138 return M::__s_getDataType().c_str();
141 static const char*
value(
const M& m)
143 return m.__getDataType().c_str();
155 return M::__s_getMessageDefinition().c_str();
158 static const char*
value(
const M& m)
160 return m.__getMessageDefinition().c_str();
168 template<
typename M,
typename Enable =
void>
171 static std_msgs::Header*
pointer(M& m) { (void)m;
return 0; }
172 static std_msgs::Header
const*
pointer(
const M& m) { (void)m;
return 0; }
178 static std_msgs::Header*
pointer(M& m) {
return &m.header; }
179 static std_msgs::Header
const*
pointer(
const M& m) {
return &m.header; }
187 template<
typename M,
typename Enable =
void>
190 static std::string*
pointer(M& m) { (void)m;
return 0; }
191 static std::string
const*
pointer(
const M& m) { (void)m;
return 0; }
197 static std::string*
pointer(M& m) {
return &m.header.frame_id; }
198 static std::string
const*
pointer(
const M& m) {
return &m.header.frame_id; }
199 static std::string
value(
const M& m) {
return m.header.frame_id; }
207 template<
typename M,
typename Enable =
void>
217 static ros::Time*
pointer(
typename boost::remove_const<M>::type &m) {
return &m.header.stamp; }
289 inline std_msgs::Header
const*
header(
const M& m)
360 #endif // ROSLIB_MESSAGE_TRAITS_H
static const char * value(const M &m)
static ros::Time const * pointer(const M &m)
static std::string const * pointer(const M &m)
bool hasHeader()
returns HasHeader<M>::value;
#define ROS_DECLARE_MESSAGE(msg)
Forward-declare a message, including Ptr and ConstPtr types, using std::allocator.
static const char * value(const M &m)
TimeStamp trait. In the default implementation pointer() returns &m.header.stamp if HasHeader<M>::val...
static ros::Time * pointer(M &m)
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
std::string const * frameId(const M &m)
returns FrameId<M>::pointer(m);
bool isSimple()
returns IsSimple<M>::value;
Specialize to provide the definition for a message.
std_msgs::Header const * header(const M &m)
returns Header<M>::pointer(m);
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
ros::Time const * timeStamp(const M &m)
returns TimeStamp<M>::pointer(m);
static const char * value()
const char * definition(const M &m)
returns Definition<M>::value(m);
Specialize to provide the md5sum for a message.
bool isFixedSize()
returns IsFixedSize<M>::value;
static const char * value()
static const char * value()
static std::string * pointer(M &m)
FrameId trait. In the default implementation pointer() returns &m.header.frame_id if HasHeader<M>::va...
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
const char * datatype(const M &m)
returns DataType<M>::value(m);
static const char * value(const M &m)
Specialize to provide the datatype for a message.
A simple datatype is one that can be memcpy'd directly in array form, i.e. it's a POD...
const char * md5sum(const M &m)
returns MD5Sum<M>::value(m);