message_traits.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSLIB_MESSAGE_TRAITS_H
29 #define ROSLIB_MESSAGE_TRAITS_H
30 
31 #include "message_forward.h"
32 
33 #include <ros/time.h>
34 
35 #include <string>
36 #include <boost/utility/enable_if.hpp>
37 #include <boost/type_traits/remove_const.hpp>
38 #include <boost/type_traits/remove_reference.hpp>
39 
40 namespace std_msgs
41 {
42  ROS_DECLARE_MESSAGE(Header)
43 }
44 
45 #define ROS_IMPLEMENT_SIMPLE_TOPIC_TRAITS(msg, md5sum, datatype, definition) \
46  namespace ros \
47  { \
48  namespace message_traits \
49  { \
50  template<> struct MD5Sum<msg> \
51  { \
52  static const char* value() { return md5sum; } \
53  static const char* value(const msg&) { return value(); } \
54  }; \
55  template<> struct DataType<msg> \
56  { \
57  static const char* value() { return datatype; } \
58  static const char* value(const msg&) { return value(); } \
59  }; \
60  template<> struct Definition<msg> \
61  { \
62  static const char* value() { return definition; } \
63  static const char* value(const msg&) { return value(); } \
64  }; \
65  } \
66  }
67 
68 namespace ros
69 {
70 namespace message_traits
71 {
72 
77 struct TrueType
78 {
79  static const bool value = true;
80  typedef TrueType type;
81 };
82 
87 struct FalseType
88 {
89  static const bool value = false;
90  typedef FalseType type;
91 };
92 
97 template<typename M> struct IsSimple : public FalseType {};
101 template<typename M> struct IsFixedSize : public FalseType {};
105 template<typename M> struct HasHeader : public FalseType {};
106 
110 template<typename M> struct IsMessage : public FalseType {};
111 
115 template<typename M>
116 struct MD5Sum
117 {
118  static const char* value()
119  {
120  return M::__s_getMD5Sum().c_str();
121  }
122 
123  static const char* value(const M& m)
124  {
125  return m.__getMD5Sum().c_str();
126  }
127 };
128 
132 template<typename M>
133 struct DataType
134 {
135  static const char* value()
136  {
137  return M::__s_getDataType().c_str();
138  }
139 
140  static const char* value(const M& m)
141  {
142  return m.__getDataType().c_str();
143  }
144 };
145 
149 template<typename M>
151 {
152  static const char* value()
153  {
154  return M::__s_getMessageDefinition().c_str();
155  }
156 
157  static const char* value(const M& m)
158  {
159  return m.__getMessageDefinition().c_str();
160  }
161 };
162 
167 template<typename M, typename Enable = void>
168 struct Header
169 {
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; }
172 };
173 
174 template<typename M>
175 struct Header<M, typename boost::enable_if<HasHeader<M> >::type >
176 {
177  static std_msgs::Header* pointer(M& m) { return &m.header; }
178  static std_msgs::Header const* pointer(const M& m) { return &m.header; }
179 };
180 
186 template<typename M, typename Enable = void>
187 struct FrameId
188 {
189  static std::string* pointer(M& m) { (void)m; return 0; }
190  static std::string const* pointer(const M& m) { (void)m; return 0; }
191 };
192 
193 template<typename M>
194 struct FrameId<M, typename boost::enable_if<HasHeader<M> >::type >
195 {
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; }
199 };
200 
206 template<typename M, typename Enable = void>
207 struct TimeStamp
208 {
209  static ros::Time* pointer(M& m) { (void)m; return 0; }
210  static ros::Time const* pointer(const M& m) { (void)m; return 0; }
211 };
212 
213 template<typename M>
214 struct TimeStamp<M, typename boost::enable_if<HasHeader<M> >::type >
215 {
216  static ros::Time* pointer(typename boost::remove_const<M>::type &m) { return &m.header.stamp; }
217  static ros::Time const* pointer(const M& m) { return &m.header.stamp; }
218  static ros::Time value(const M& m) { return m.header.stamp; }
219 };
220 
224 template<typename M>
225 inline const char* md5sum()
226 {
228 }
229 
233 template<typename M>
234 inline const char* datatype()
235 {
237 }
238 
242 template<typename M>
243 inline const char* definition()
244 {
246 }
247 
251 template<typename M>
252 inline const char* md5sum(const M& m)
253 {
255 }
256 
260 template<typename M>
261 inline const char* datatype(const M& m)
262 {
264 }
265 
269 template<typename M>
270 inline const char* definition(const M& m)
271 {
273 }
274 
278 template<typename M>
279 inline std_msgs::Header* header(M& m)
280 {
282 }
283 
287 template<typename M>
288 inline std_msgs::Header const* header(const M& m)
289 {
291 }
292 
296 template<typename M>
297 inline std::string* frameId(M& m)
298 {
300 }
301 
305 template<typename M>
306 inline std::string const* frameId(const M& m)
307 {
309 }
310 
314 template<typename M>
315 inline ros::Time* timeStamp(M& m)
316 {
318 }
319 
323 template<typename M>
324 inline ros::Time const* timeStamp(const M& m)
325 {
327 }
328 
332 template<typename M>
333 inline bool isSimple()
334 {
336 }
337 
341 template<typename M>
342 inline bool isFixedSize()
343 {
345 }
346 
350 template<typename M>
351 inline bool hasHeader()
352 {
354 }
355 
356 } // namespace message_traits
357 } // namespace ros
358 
359 #endif // ROSLIB_MESSAGE_TRAITS_H
ros::message_traits::TimeStamp
TimeStamp trait. In the default implementation pointer() returns &m.header.stamp if HasHeader<M>::val...
Definition: message_traits.h:207
ros::message_traits::Header< M, typename boost::enable_if< HasHeader< M > >::type >::pointer
static std_msgs::Header * pointer(M &m)
Definition: message_traits.h:177
ros::message_traits::TrueType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:77
ros::message_traits::MD5Sum::value
static const char * value(const M &m)
Definition: message_traits.h:123
ros::message_traits::frameId
std::string * frameId(M &m)
returns FrameId<M>::pointer(m);
Definition: message_traits.h:297
ros::message_traits::md5sum
const char * md5sum()
returns MD5Sum<M>::value();
Definition: message_traits.h:225
ros::message_traits::FrameId::pointer
static std::string const * pointer(const M &m)
Definition: message_traits.h:190
message_forward.h
ros::message_traits::DataType::value
static const char * value(const M &m)
Definition: message_traits.h:140
ros::message_traits::definition
const char * definition()
returns Definition<M>::value();
Definition: message_traits.h:243
ros
ros::message_traits::IsSimple
A simple datatype is one that can be memcpy'd directly in array form, i.e. it's a POD,...
Definition: message_traits.h:97
ros::message_traits::FrameId< M, typename boost::enable_if< HasHeader< M > >::type >::value
static std::string value(const M &m)
Definition: message_traits.h:198
time.h
ros::message_traits::Definition::value
static const char * value(const M &m)
Definition: message_traits.h:157
ros::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:133
ros::message_traits::FrameId< M, typename boost::enable_if< HasHeader< M > >::type >::pointer
static std::string const * pointer(const M &m)
Definition: message_traits.h:197
ros::message_traits::Header
Header trait. In the default implementation pointer() returns &m.header if HasHeader<M>::value is tru...
Definition: message_traits.h:168
boost
ros::message_traits::HasHeader
HasHeader informs whether or not there is a header that gets serialized as the first thing in the mes...
Definition: message_traits.h:105
ros::message_traits::FalseType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:87
ros::message_traits::TimeStamp::pointer
static ros::Time const * pointer(const M &m)
Definition: message_traits.h:210
ros::message_traits::isFixedSize
bool isFixedSize()
returns IsFixedSize<M>::value;
Definition: message_traits.h:342
ros::message_traits::FalseType::value
static const bool value
Definition: message_traits.h:89
ros::message_traits::TimeStamp< M, typename boost::enable_if< HasHeader< M > >::type >::pointer
static ros::Time * pointer(typename boost::remove_const< M >::type &m)
Definition: message_traits.h:216
ros::message_traits::timeStamp
ros::Time * timeStamp(M &m)
returns TimeStamp<M>::pointer(m);
Definition: message_traits.h:315
ros::message_traits::Header::pointer
static std_msgs::Header const * pointer(const M &m)
Definition: message_traits.h:171
ros::message_traits::TimeStamp::pointer
static ros::Time * pointer(M &m)
Definition: message_traits.h:209
std_msgs
Definition: message_traits.h:40
ros::message_traits::DataType::value
static const char * value()
Definition: message_traits.h:135
ROS_DECLARE_MESSAGE
#define ROS_DECLARE_MESSAGE(msg)
Forward-declare a message, including Ptr and ConstPtr types, using std::allocator.
Definition: message_forward.h:68
ros::message_traits::MD5Sum::value
static const char * value()
Definition: message_traits.h:118
ros::message_traits::header
std_msgs::Header * header(M &m)
returns Header<M>::pointer(m);
Definition: message_traits.h:279
ros::message_traits::TimeStamp< M, typename boost::enable_if< HasHeader< M > >::type >::pointer
static ros::Time const * pointer(const M &m)
Definition: message_traits.h:217
ros::message_traits::MD5Sum
Specialize to provide the md5sum for a message.
Definition: message_traits.h:116
ros::message_traits::Header< M, typename boost::enable_if< HasHeader< M > >::type >::pointer
static std_msgs::Header const * pointer(const M &m)
Definition: message_traits.h:178
ros::message_traits::FalseType::type
FalseType type
Definition: message_traits.h:90
ros::message_traits::Header::pointer
static std_msgs::Header * pointer(M &m)
Definition: message_traits.h:170
ros::message_traits::TrueType::type
TrueType type
Definition: message_traits.h:80
ros::Time
ros::message_traits::FrameId
FrameId trait. In the default implementation pointer() returns &m.header.frame_id if HasHeader<M>::va...
Definition: message_traits.h:187
ros::message_traits::FrameId< M, typename boost::enable_if< HasHeader< M > >::type >::pointer
static std::string * pointer(M &m)
Definition: message_traits.h:196
ros::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:110
ros::message_traits::datatype
const char * datatype()
returns DataType<M>::value();
Definition: message_traits.h:234
ros::message_traits::TrueType::value
static const bool value
Definition: message_traits.h:79
ros::message_traits::TimeStamp< M, typename boost::enable_if< HasHeader< M > >::type >::value
static ros::Time value(const M &m)
Definition: message_traits.h:218
ros::message_traits::Definition::value
static const char * value()
Definition: message_traits.h:152
ros::message_traits::FrameId::pointer
static std::string * pointer(M &m)
Definition: message_traits.h:189
ros::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:150
ros::message_traits::hasHeader
bool hasHeader()
returns HasHeader<M>::value;
Definition: message_traits.h:351
ros::message_traits::IsFixedSize
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
Definition: message_traits.h:101
ros::message_traits::isSimple
bool isSimple()
returns IsSimple<M>::value;
Definition: message_traits.h:333


roscpp_traits
Author(s): Josh Faust, Dirk Thomas
autogenerated on Sat Jun 17 2023 02:32:39