NAVPoseData.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 // Generated by gencpp from file sick_scan/NAVPoseData.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SICK_SCAN_MESSAGE_NAVPOSEDATA_H
7 #define SICK_SCAN_MESSAGE_NAVPOSEDATA_H
8 
9 
10 #include <string>
11 #include <vector>
12 #include <map>
13 
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
18 
19 #include <std_msgs/Header.h>
20 
21 namespace sick_scan_xd
22 {
23 template <class ContainerAllocator>
25 {
27 
29  : header()
30  , x(0)
31  , y(0)
32  , phi(0)
34  , output_mode(0)
35  , timestamp(0)
36  , mean_dev(0)
37  , nav_mode(0)
38  , info_state(0)
40  , pose_valid(0)
41  , pose_x(0.0)
42  , pose_y(0.0)
43  , pose_yaw(0.0) {
44  }
45  NAVPoseData_(const ContainerAllocator& _alloc)
46  : header(_alloc)
47  , x(0)
48  , y(0)
49  , phi(0)
51  , output_mode(0)
52  , timestamp(0)
53  , mean_dev(0)
54  , nav_mode(0)
55  , info_state(0)
57  , pose_valid(0)
58  , pose_x(0.0)
59  , pose_y(0.0)
60  , pose_yaw(0.0) {
61  (void)_alloc;
62  }
63 
64 
65 
66  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
68 
69  typedef int32_t _x_type;
71 
72  typedef int32_t _y_type;
74 
75  typedef uint32_t _phi_type;
77 
78  typedef uint16_t _opt_pose_data_valid_type;
80 
81  typedef uint8_t _output_mode_type;
83 
84  typedef uint32_t _timestamp_type;
86 
87  typedef int32_t _mean_dev_type;
89 
90  typedef uint8_t _nav_mode_type;
92 
93  typedef uint32_t _info_state_type;
95 
96  typedef uint8_t _quant_used_reflectors_type;
98 
99  typedef int8_t _pose_valid_type;
101 
102  typedef float _pose_x_type;
104 
105  typedef float _pose_y_type;
107 
108  typedef float _pose_yaw_type;
110 
111 
112 
113 
114 
115  typedef std::shared_ptr< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> > Ptr;
116  typedef std::shared_ptr< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> const> ConstPtr;
117 
118 }; // struct NAVPoseData_
119 
120 typedef ::sick_scan_xd::NAVPoseData_<std::allocator<void> > NAVPoseData;
121 
122 typedef std::shared_ptr< ::sick_scan_xd::NAVPoseData > NAVPoseDataPtr;
123 typedef std::shared_ptr< ::sick_scan_xd::NAVPoseData const> NAVPoseDataConstPtr;
124 
125 // constants requiring out of line definition
126 
127 
128 
129 template<typename ContainerAllocator>
130 std::ostream& operator<<(std::ostream& s, const ::sick_scan_xd::NAVPoseData_<ContainerAllocator> & v)
131 {
133 return s;
134 }
135 
136 
137 template<typename ContainerAllocator1, typename ContainerAllocator2>
138 bool operator==(const ::sick_scan_xd::NAVPoseData_<ContainerAllocator1> & lhs, const ::sick_scan_xd::NAVPoseData_<ContainerAllocator2> & rhs)
139 {
140  return lhs.header == rhs.header &&
141  lhs.x == rhs.x &&
142  lhs.y == rhs.y &&
143  lhs.phi == rhs.phi &&
144  lhs.opt_pose_data_valid == rhs.opt_pose_data_valid &&
145  lhs.output_mode == rhs.output_mode &&
146  lhs.timestamp == rhs.timestamp &&
147  lhs.mean_dev == rhs.mean_dev &&
148  lhs.nav_mode == rhs.nav_mode &&
149  lhs.info_state == rhs.info_state &&
150  lhs.quant_used_reflectors == rhs.quant_used_reflectors &&
151  lhs.pose_valid == rhs.pose_valid &&
152  lhs.pose_x == rhs.pose_x &&
153  lhs.pose_y == rhs.pose_y &&
154  lhs.pose_yaw == rhs.pose_yaw;
155 }
156 
157 template<typename ContainerAllocator1, typename ContainerAllocator2>
158 bool operator!=(const ::sick_scan_xd::NAVPoseData_<ContainerAllocator1> & lhs, const ::sick_scan_xd::NAVPoseData_<ContainerAllocator2> & rhs)
159 {
160  return !(lhs == rhs);
161 }
162 
163 
164 } // namespace sick_scan_xd
165 
166 namespace roswrap
167 {
168 namespace message_traits
169 {
170 
171 
172 
173 
174 
175 template <class ContainerAllocator>
176 struct IsMessage< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
177  : TrueType
178  { };
179 
180 template <class ContainerAllocator>
181 struct IsMessage< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> const>
182  : TrueType
183  { };
184 
185 template <class ContainerAllocator>
186 struct IsFixedSize< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
187  : FalseType
188  { };
189 
190 template <class ContainerAllocator>
191 struct IsFixedSize< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> const>
192  : FalseType
193  { };
194 
195 template <class ContainerAllocator>
196 struct HasHeader< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
197  : TrueType
198  { };
199 
200 template <class ContainerAllocator>
201 struct HasHeader< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> const>
202  : TrueType
203  { };
204 
205 
206 template<class ContainerAllocator>
207 struct MD5Sum< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
208 {
209  static const char* value()
210  {
211  return "09a85c46d8eba44e26ad07869c2bbc20";
212  }
213 
214  static const char* value(const ::sick_scan_xd::NAVPoseData_<ContainerAllocator>&) { return value(); }
215  static const uint64_t static_value1 = 0x09a85c46d8eba44eULL;
216  static const uint64_t static_value2 = 0x26ad07869c2bbc20ULL;
217 };
218 
219 template<class ContainerAllocator>
220 struct DataType< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
221 {
222  static const char* value()
223  {
224  return "sick_scan/NAVPoseData";
225  }
226 
227  static const char* value(const ::sick_scan_xd::NAVPoseData_<ContainerAllocator>&) { return value(); }
228 };
229 
230 template<class ContainerAllocator>
231 struct Definition< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
232 {
233  static const char* value()
234  {
235  return "# ROS message of NAV350PoseData, see sick_nav_scandata_parser.h and NAV-350 telegram listing for details.\n"
236 "std_msgs/Header header\n"
237 "\n"
238 "# pose in lidar coordinates in mm and mdeg\n"
239 "int32 x\n"
240 "int32 y\n"
241 "uint32 phi\n"
242 "# optional pose data\n"
243 "uint16 opt_pose_data_valid\n"
244 "uint8 output_mode\n"
245 "uint32 timestamp\n"
246 "int32 mean_dev\n"
247 "uint8 nav_mode\n"
248 "uint32 info_state\n"
249 "uint8 quant_used_reflectors\n"
250 "\n"
251 "# pose in ros coordinates\n"
252 "int8 pose_valid # pose_x, pose_y and pose_yaw are valid if pose_valid > 0\n"
253 "float32 pose_x # x position in ros coordinates in m\n"
254 "float32 pose_y # y position in ros coordinates in m\n"
255 "float32 pose_yaw # yaw angle in radians\n"
256 "\n"
257 "================================================================================\n"
258 "MSG: std_msgs/Header\n"
259 "# Standard metadata for higher-level stamped data types.\n"
260 "# This is generally used to communicate timestamped data \n"
261 "# in a particular coordinate frame.\n"
262 "# \n"
263 "# sequence ID: consecutively increasing ID \n"
264 "uint32 seq\n"
265 "#Two-integer timestamp that is expressed as:\n"
266 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
267 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
268 "# time-handling sugar is provided by the client library\n"
269 "time stamp\n"
270 "#Frame this data is associated with\n"
271 "string frame_id\n"
272 ;
273  }
274 
275  static const char* value(const ::sick_scan_xd::NAVPoseData_<ContainerAllocator>&) { return value(); }
276 };
277 
278 } // namespace message_traits
279 } // namespace roswrap
280 
281 namespace roswrap
282 {
283 namespace serialization
284 {
285 
286  template<class ContainerAllocator> struct Serializer< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
287  {
288  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
289  {
290  stream.next(m.header);
291  stream.next(m.x);
292  stream.next(m.y);
293  stream.next(m.phi);
294  stream.next(m.opt_pose_data_valid);
295  stream.next(m.output_mode);
296  stream.next(m.timestamp);
297  stream.next(m.mean_dev);
298  stream.next(m.nav_mode);
299  stream.next(m.info_state);
300  stream.next(m.quant_used_reflectors);
301  stream.next(m.pose_valid);
302  stream.next(m.pose_x);
303  stream.next(m.pose_y);
304  stream.next(m.pose_yaw);
305  }
306 
308  }; // struct NAVPoseData_
309 
310 } // namespace serialization
311 } // namespace roswrap
312 
313 namespace roswrap
314 {
315 namespace message_operations
316 {
317 
318 template<class ContainerAllocator>
319 struct Printer< ::sick_scan_xd::NAVPoseData_<ContainerAllocator> >
320 {
321  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sick_scan_xd::NAVPoseData_<ContainerAllocator>& v)
322  {
323  s << indent << "header: ";
324  s << std::endl;
326  s << indent << "x: ";
327  Printer<int32_t>::stream(s, indent + " ", v.x);
328  s << indent << "y: ";
329  Printer<int32_t>::stream(s, indent + " ", v.y);
330  s << indent << "phi: ";
331  Printer<uint32_t>::stream(s, indent + " ", v.phi);
332  s << indent << "opt_pose_data_valid: ";
333  Printer<uint16_t>::stream(s, indent + " ", v.opt_pose_data_valid);
334  s << indent << "output_mode: ";
335  Printer<uint8_t>::stream(s, indent + " ", v.output_mode);
336  s << indent << "timestamp: ";
337  Printer<uint32_t>::stream(s, indent + " ", v.timestamp);
338  s << indent << "mean_dev: ";
339  Printer<int32_t>::stream(s, indent + " ", v.mean_dev);
340  s << indent << "nav_mode: ";
341  Printer<uint8_t>::stream(s, indent + " ", v.nav_mode);
342  s << indent << "info_state: ";
343  Printer<uint32_t>::stream(s, indent + " ", v.info_state);
344  s << indent << "quant_used_reflectors: ";
345  Printer<uint8_t>::stream(s, indent + " ", v.quant_used_reflectors);
346  s << indent << "pose_valid: ";
347  Printer<int8_t>::stream(s, indent + " ", v.pose_valid);
348  s << indent << "pose_x: ";
349  Printer<float>::stream(s, indent + " ", v.pose_x);
350  s << indent << "pose_y: ";
351  Printer<float>::stream(s, indent + " ", v.pose_y);
352  s << indent << "pose_yaw: ";
353  Printer<float>::stream(s, indent + " ", v.pose_yaw);
354  }
355 };
356 
357 } // namespace message_operations
358 } // namespace roswrap
359 
360 #endif // SICK_SCAN_MESSAGE_NAVPOSEDATA_H
roswrap::message_traits::FalseType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:89
sick_scan_xd::operator<<
std::ostream & operator<<(std::ostream &s, const ::sick_scan_xd::ColaMsgSrvRequest_< ContainerAllocator > &v)
Definition: ColaMsgSrvRequest.h:59
sick_scan_xd::NAVPoseData_::_y_type
int32_t _y_type
Definition: NAVPoseData.h:72
multiscan_pcap_player.indent
indent
Definition: multiscan_pcap_player.py:252
sick_scan_xd::operator!=
bool operator!=(const ::sick_scan_xd::ColaMsgSrvRequest_< ContainerAllocator1 > &lhs, const ::sick_scan_xd::ColaMsgSrvRequest_< ContainerAllocator2 > &rhs)
Definition: ColaMsgSrvRequest.h:73
roswrap::serialization::Serializer
Templated serialization class. Default implementation provides backwards compatibility with old messa...
Definition: serialization.h:120
sick_scan_xd::NAVPoseData_::Type
NAVPoseData_< ContainerAllocator > Type
Definition: NAVPoseData.h:26
sick_scan_xd::NAVPoseDataPtr
std::shared_ptr< ::sick_scan_xd::NAVPoseData > NAVPoseDataPtr
Definition: NAVPoseData.h:122
roswrap::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:107
sick_scan_xd::NAVPoseData_::_x_type
int32_t _x_type
Definition: NAVPoseData.h:69
const
#define const
Definition: getopt.c:38
sick_scan_xd::NAVPoseData_::header
_header_type header
Definition: NAVPoseData.h:67
sick_scan_xd::NAVPoseData_::NAVPoseData_
NAVPoseData_(const ContainerAllocator &_alloc)
Definition: NAVPoseData.h:45
s
XmlRpcServer s
sick_scan_xd::NAVPoseData_::_output_mode_type
uint8_t _output_mode_type
Definition: NAVPoseData.h:81
sick_scan_xd::NAVPoseData_::phi
_phi_type phi
Definition: NAVPoseData.h:76
sick_scan_xd::NAVPoseData_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: NAVPoseData.h:66
roswrap::serialization::Serializer< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: NAVPoseData.h:288
sick_scan_xd::NAVPoseData_::opt_pose_data_valid
_opt_pose_data_valid_type opt_pose_data_valid
Definition: NAVPoseData.h:79
sick_scan_xd::NAVPoseData
::sick_scan_xd::NAVPoseData_< std::allocator< void > > NAVPoseData
Definition: NAVPoseData.h:120
sick_scan_xd::NAVPoseData_::_quant_used_reflectors_type
uint8_t _quant_used_reflectors_type
Definition: NAVPoseData.h:96
roswrap::message_operations::Printer::stream
static void stream(Stream &s, const std::string &indent, const M &value)
Definition: message_operations.h:43
roswrap::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:103
sick_scan_xd::NAVPoseData_::_opt_pose_data_valid_type
uint16_t _opt_pose_data_valid_type
Definition: NAVPoseData.h:78
sick_scan_xd::NAVPoseData_::output_mode
_output_mode_type output_mode
Definition: NAVPoseData.h:82
ros::message_operations::Printer
ROS_DECLARE_ALLINONE_SERIALIZER
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
Definition: serialization.h:74
sick_scan_xd::NAVPoseData_::ConstPtr
std::shared_ptr< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > const > ConstPtr
Definition: NAVPoseData.h:116
sick_scan_xd::NAVPoseData_::_pose_yaw_type
float _pose_yaw_type
Definition: NAVPoseData.h:108
sick_scan_xd
Definition: abstract_parser.cpp:65
roswrap::message_traits::MD5Sum< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::NAVPoseData_< ContainerAllocator > &)
Definition: NAVPoseData.h:214
roswrap::message_traits::MD5Sum< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::value
static const char * value()
Definition: NAVPoseData.h:209
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
sick_scan_xd::NAVPoseData_::mean_dev
_mean_dev_type mean_dev
Definition: NAVPoseData.h:88
sick_scan_xd::NAVPoseData_::_pose_y_type
float _pose_y_type
Definition: NAVPoseData.h:105
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
sick_scan_xd::NAVPoseData_::pose_y
_pose_y_type pose_y
Definition: NAVPoseData.h:106
roswrap::message_traits::DataType< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::NAVPoseData_< ContainerAllocator > &)
Definition: NAVPoseData.h:227
sick_scan_xd::NAVPoseData_::info_state
_info_state_type info_state
Definition: NAVPoseData.h:94
sick_scan_xd::NAVPoseData_::_pose_x_type
float _pose_x_type
Definition: NAVPoseData.h:102
sick_scan_xd::NAVPoseData_::_mean_dev_type
int32_t _mean_dev_type
Definition: NAVPoseData.h:87
sick_scan_xd::NAVPoseData_::x
_x_type x
Definition: NAVPoseData.h:70
roswrap
Definition: param_modi.cpp:41
sick_scan_xd::NAVPoseData_
Definition: NAVPoseData.h:24
roswrap::message_operations::Printer
Definition: message_operations.h:40
std_msgs::Header_
Definition: Header.h:23
sick_scan_xd::NAVPoseData_::_nav_mode_type
uint8_t _nav_mode_type
Definition: NAVPoseData.h:90
sick_scan_xd::NAVPoseData_::pose_x
_pose_x_type pose_x
Definition: NAVPoseData.h:103
roswrap::message_traits::TrueType
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Definition: message_traits.h:79
roswrap::message_traits::MD5Sum
Specialize to provide the md5sum for a message.
Definition: message_traits.h:118
sick_scan_xd::NAVPoseData_::_timestamp_type
uint32_t _timestamp_type
Definition: NAVPoseData.h:84
sick_scan_xd::NAVPoseData_::y
_y_type y
Definition: NAVPoseData.h:73
sick_scan_xd::NAVPoseData_::NAVPoseData_
NAVPoseData_()
Definition: NAVPoseData.h:28
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
sick_scan_xd::NAVPoseData_::_phi_type
uint32_t _phi_type
Definition: NAVPoseData.h:75
sick_scan_xd::NAVPoseData_::timestamp
_timestamp_type timestamp
Definition: NAVPoseData.h:85
roswrap::message_traits::Definition< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::NAVPoseData_< ContainerAllocator > &)
Definition: NAVPoseData.h:275
sick_scan_xd::NAVPoseData_::_pose_valid_type
int8_t _pose_valid_type
Definition: NAVPoseData.h:99
sick_scan_xd::operator==
bool operator==(const ::sick_scan_xd::ColaMsgSrvRequest_< ContainerAllocator1 > &lhs, const ::sick_scan_xd::ColaMsgSrvRequest_< ContainerAllocator2 > &rhs)
Definition: ColaMsgSrvRequest.h:67
sick_scan_xd::NAVPoseData_::pose_yaw
_pose_yaw_type pose_yaw
Definition: NAVPoseData.h:109
sick_scan_xd::NAVPoseData_::quant_used_reflectors
_quant_used_reflectors_type quant_used_reflectors
Definition: NAVPoseData.h:97
sick_scan_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
sick_scan_xd::NAVPoseDataConstPtr
std::shared_ptr< ::sick_scan_xd::NAVPoseData const > NAVPoseDataConstPtr
Definition: NAVPoseData.h:123
roswrap::message_traits::DataType< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::value
static const char * value()
Definition: NAVPoseData.h:222
sick_scan_xd::NAVPoseData_::_info_state_type
uint32_t _info_state_type
Definition: NAVPoseData.h:93
roswrap::message_operations::Printer< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sick_scan_xd::NAVPoseData_< ContainerAllocator > &v)
Definition: NAVPoseData.h:321
Header.h
roswrap::message_traits::Definition< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > >::value
static const char * value()
Definition: NAVPoseData.h:233
sick_scan_xd::NAVPoseData_::nav_mode
_nav_mode_type nav_mode
Definition: NAVPoseData.h:91
sick_scan_xd::NAVPoseData_::Ptr
std::shared_ptr< ::sick_scan_xd::NAVPoseData_< ContainerAllocator > > Ptr
Definition: NAVPoseData.h:115
sick_scan_xd::NAVPoseData_::pose_valid
_pose_valid_type pose_valid
Definition: NAVPoseData.h:100


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:09