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 
69 namespace ros
70 {
71 namespace message_traits
72 {
73 
78 struct TrueType
79 {
80  static const bool value = true;
81  typedef TrueType type;
82 };
83 
88 struct FalseType
89 {
90  static const bool value = false;
91  typedef FalseType type;
92 };
93 
98 template<typename M> struct IsSimple : public FalseType {};
102 template<typename M> struct IsFixedSize : public FalseType {};
106 template<typename M> struct HasHeader : public FalseType {};
107 
111 template<typename M> struct IsMessage : public FalseType {};
112 
116 template<typename M>
117 struct MD5Sum
118 {
119  static const char* value()
120  {
121  return M::__s_getMD5Sum().c_str();
122  }
123 
124  static const char* value(const M& m)
125  {
126  return m.__getMD5Sum().c_str();
127  }
128 };
129 
133 template<typename M>
134 struct DataType
135 {
136  static const char* value()
137  {
138  return M::__s_getDataType().c_str();
139  }
140 
141  static const char* value(const M& m)
142  {
143  return m.__getDataType().c_str();
144  }
145 };
146 
150 template<typename M>
152 {
153  static const char* value()
154  {
155  return M::__s_getMessageDefinition().c_str();
156  }
157 
158  static const char* value(const M& m)
159  {
160  return m.__getMessageDefinition().c_str();
161  }
162 };
163 
168 template<typename M, typename Enable = void>
169 struct Header
170 {
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; }
173 };
174 
175 template<typename M>
176 struct Header<M, typename boost::enable_if<HasHeader<M> >::type >
177 {
178  static std_msgs::Header* pointer(M& m) { return &m.header; }
179  static std_msgs::Header const* pointer(const M& m) { return &m.header; }
180 };
181 
187 template<typename M, typename Enable = void>
188 struct FrameId
189 {
190  static std::string* pointer(M& m) { (void)m; return 0; }
191  static std::string const* pointer(const M& m) { (void)m; return 0; }
192 };
193 
194 template<typename M>
195 struct FrameId<M, typename boost::enable_if<HasHeader<M> >::type >
196 {
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; }
200 };
201 
207 template<typename M, typename Enable = void>
208 struct TimeStamp
209 {
210  static ros::Time* pointer(M& m) { (void)m; return 0; }
211  static ros::Time const* pointer(const M& m) { (void)m; return 0; }
212 };
213 
214 template<typename M>
215 struct TimeStamp<M, typename boost::enable_if<HasHeader<M> >::type >
216 {
217  static ros::Time* pointer(typename boost::remove_const<M>::type &m) { return &m.header.stamp; }
218  static ros::Time const* pointer(const M& m) { return &m.header.stamp; }
219  static ros::Time value(const M& m) { return m.header.stamp; }
220 };
221 
225 template<typename M>
226 inline const char* md5sum()
227 {
229 }
230 
234 template<typename M>
235 inline const char* datatype()
236 {
238 }
239 
243 template<typename M>
244 inline const char* definition()
245 {
247 }
248 
252 template<typename M>
253 inline const char* md5sum(const M& m)
254 {
256 }
257 
261 template<typename M>
262 inline const char* datatype(const M& m)
263 {
265 }
266 
270 template<typename M>
271 inline const char* definition(const M& m)
272 {
274 }
275 
279 template<typename M>
280 inline std_msgs::Header* header(M& m)
281 {
283 }
284 
288 template<typename M>
289 inline std_msgs::Header const* header(const M& m)
290 {
292 }
293 
297 template<typename M>
298 inline std::string* frameId(M& m)
299 {
301 }
302 
306 template<typename M>
307 inline std::string const* frameId(const M& m)
308 {
310 }
311 
315 template<typename M>
316 inline ros::Time* timeStamp(M& m)
317 {
319 }
320 
324 template<typename M>
325 inline ros::Time const* timeStamp(const M& m)
326 {
328 }
329 
333 template<typename M>
334 inline bool isSimple()
335 {
337 }
338 
342 template<typename M>
343 inline bool isFixedSize()
344 {
346 }
347 
351 template<typename M>
352 inline bool hasHeader()
353 {
355 }
356 
357 } // namespace message_traits
358 } // namespace ros
359 
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;
Header trait. In the default implementation pointer() returns &m.header if HasHeader<M>::value is tru...
#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 ros::Time * pointer(typename boost::remove_const< M >::type &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)
static std_msgs::Header const * pointer(const M &m)
Specialize to provide the datatype for a message.
A simple datatype is one that can be memcpy&#39;d directly in array form, i.e. it&#39;s a POD...
static std_msgs::Header * pointer(M &m)
const char * md5sum(const M &m)
returns MD5Sum<M>::value(m);
HasHeader informs whether or not there is a header that gets serialized as the first thing in the mes...


roscpp_traits
Author(s): Josh Faust
autogenerated on Sat Apr 6 2019 02:52:23