Go to the documentation of this file.
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(); } \
70 namespace message_traits
89 static const bool value =
false;
120 return M::__s_getMD5Sum().c_str();
123 static const char*
value(
const M& m)
125 return m.__getMD5Sum().c_str();
137 return M::__s_getDataType().c_str();
140 static const char*
value(
const M& m)
142 return m.__getDataType().c_str();
154 return M::__s_getMessageDefinition().c_str();
157 static const char*
value(
const M& m)
159 return m.__getMessageDefinition().c_str();
167 template<
typename M,
typename Enable =
void>
170 static std_msgs::Header*
pointer(M& m) { (void)m;
return 0; }
171 static std_msgs::Header
const*
pointer(
const M& m) { (void)m;
return 0; }
177 static std_msgs::Header*
pointer(M& m) {
return &m.header; }
178 static std_msgs::Header
const*
pointer(
const M& m) {
return &m.header; }
186 template<
typename M,
typename Enable =
void>
189 static std::string*
pointer(M& m) { (void)m;
return 0; }
190 static std::string
const*
pointer(
const M& m) { (void)m;
return 0; }
196 static std::string*
pointer(M& m) {
return &m.header.frame_id; }
197 static std::string
const*
pointer(
const M& m) {
return &m.header.frame_id; }
198 static std::string
value(
const M& m) {
return m.header.frame_id; }
206 template<
typename M,
typename Enable =
void>
216 static ros::Time*
pointer(
typename boost::remove_const<M>::type &m) {
return &m.header.stamp; }
288 inline std_msgs::Header
const*
header(
const M& m)
359 #endif // ROSLIB_MESSAGE_TRAITS_H
TimeStamp trait. In the default implementation pointer() returns &m.header.stamp if HasHeader<M>::val...
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static const char * value(const M &m)
std::string * frameId(M &m)
returns FrameId<M>::pointer(m);
const char * md5sum()
returns MD5Sum<M>::value();
static std::string const * pointer(const M &m)
static const char * value(const M &m)
const char * definition()
returns Definition<M>::value();
A simple datatype is one that can be memcpy'd directly in array form, i.e. it's a POD,...
static const char * value(const M &m)
Specialize to provide the datatype for a message.
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static ros::Time const * pointer(const M &m)
bool isFixedSize()
returns IsFixedSize<M>::value;
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
static ros::Time * pointer(M &m)
static const char * value()
#define ROS_DECLARE_MESSAGE(msg)
Forward-declare a message, including Ptr and ConstPtr types, using std::allocator.
static const char * value()
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
Specialize to provide the md5sum for a message.
FrameId trait. In the default implementation pointer() returns &m.header.frame_id if HasHeader<M>::va...
const char * datatype()
returns DataType<M>::value();
static const char * value()
static std::string * pointer(M &m)
Specialize to provide the definition for a message.
bool hasHeader()
returns HasHeader<M>::value;
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
bool isSimple()
returns IsSimple<M>::value;
roscpp_traits
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Jun 17 2023 02:32:39