NAVLandmarkData.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/NAVLandmarkData.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SICK_SCAN_MESSAGE_NAVLANDMARKDATA_H
7 #define SICK_SCAN_MESSAGE_NAVLANDMARKDATA_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>
21 
22 namespace sick_scan_xd
23 {
24 template <class ContainerAllocator>
26 {
28 
30  : header()
31  , landmark_filter(0)
32  , num_reflectors(0)
33  , reflectors() {
34  }
35  NAVLandmarkData_(const ContainerAllocator& _alloc)
36  : header(_alloc)
37  , landmark_filter(0)
38  , num_reflectors(0)
39  , reflectors(_alloc) {
40  (void)_alloc;
41  }
42 
43 
44 
45  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
47 
48  typedef uint8_t _landmark_filter_type;
50 
51  typedef uint16_t _num_reflectors_type;
53 
54  typedef std::vector< ::sick_scan_xd::NAVReflectorData_<ContainerAllocator> , typename std::allocator_traits<ContainerAllocator>::template rebind_alloc< ::sick_scan_xd::NAVReflectorData_<ContainerAllocator> >> _reflectors_type;
56 
57 
58 
59 
60 
61  typedef std::shared_ptr< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> > Ptr;
62  typedef std::shared_ptr< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> const> ConstPtr;
63 
64 }; // struct NAVLandmarkData_
65 
66 typedef ::sick_scan_xd::NAVLandmarkData_<std::allocator<void> > NAVLandmarkData;
67 
68 typedef std::shared_ptr< ::sick_scan_xd::NAVLandmarkData > NAVLandmarkDataPtr;
69 typedef std::shared_ptr< ::sick_scan_xd::NAVLandmarkData const> NAVLandmarkDataConstPtr;
70 
71 // constants requiring out of line definition
72 
73 
74 
75 template<typename ContainerAllocator>
76 std::ostream& operator<<(std::ostream& s, const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> & v)
77 {
79 return s;
80 }
81 
82 
83 template<typename ContainerAllocator1, typename ContainerAllocator2>
84 bool operator==(const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator1> & lhs, const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator2> & rhs)
85 {
86  return lhs.header == rhs.header &&
87  lhs.landmark_filter == rhs.landmark_filter &&
88  lhs.num_reflectors == rhs.num_reflectors &&
89  lhs.reflectors == rhs.reflectors;
90 }
91 
92 template<typename ContainerAllocator1, typename ContainerAllocator2>
93 bool operator!=(const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator1> & lhs, const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator2> & rhs)
94 {
95  return !(lhs == rhs);
96 }
97 
98 
99 } // namespace sick_scan_xd
100 
101 namespace roswrap
102 {
103 namespace message_traits
104 {
105 
106 
107 
108 
109 
110 template <class ContainerAllocator>
111 struct IsMessage< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
112  : TrueType
113  { };
114 
115 template <class ContainerAllocator>
116 struct IsMessage< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> const>
117  : TrueType
118  { };
119 
120 template <class ContainerAllocator>
121 struct IsFixedSize< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
122  : FalseType
123  { };
124 
125 template <class ContainerAllocator>
126 struct IsFixedSize< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> const>
127  : FalseType
128  { };
129 
130 template <class ContainerAllocator>
131 struct HasHeader< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
132  : TrueType
133  { };
134 
135 template <class ContainerAllocator>
136 struct HasHeader< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> const>
137  : TrueType
138  { };
139 
140 
141 template<class ContainerAllocator>
142 struct MD5Sum< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
143 {
144  static const char* value()
145  {
146  return "6978f0aa2a911a9f94328887e912f9fb";
147  }
148 
149  static const char* value(const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator>&) { return value(); }
150  static const uint64_t static_value1 = 0x6978f0aa2a911a9fULL;
151  static const uint64_t static_value2 = 0x94328887e912f9fbULL;
152 };
153 
154 template<class ContainerAllocator>
155 struct DataType< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
156 {
157  static const char* value()
158  {
159  return "sick_scan/NAVLandmarkData";
160  }
161 
162  static const char* value(const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator>&) { return value(); }
163 };
164 
165 template<class ContainerAllocator>
166 struct Definition< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
167 {
168  static const char* value()
169  {
170  return "# ROS message of NAV350LandmarkData, see sick_nav_scandata_parser.h and NAV-350 telegram listing for details.\n"
171 "std_msgs/Header header\n"
172 "\n"
173 "uint8 landmark_filter\n"
174 "uint16 num_reflectors\n"
175 "sick_scan/NAVReflectorData[] reflectors\n"
176 "\n"
177 "================================================================================\n"
178 "MSG: std_msgs/Header\n"
179 "# Standard metadata for higher-level stamped data types.\n"
180 "# This is generally used to communicate timestamped data \n"
181 "# in a particular coordinate frame.\n"
182 "# \n"
183 "# sequence ID: consecutively increasing ID \n"
184 "uint32 seq\n"
185 "#Two-integer timestamp that is expressed as:\n"
186 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
187 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
188 "# time-handling sugar is provided by the client library\n"
189 "time stamp\n"
190 "#Frame this data is associated with\n"
191 "string frame_id\n"
192 "\n"
193 "================================================================================\n"
194 "MSG: sick_scan/NAVReflectorData\n"
195 "# ROS message of NAV350ReflectorData, see sick_nav_scandata_parser.h and NAV-350 telegram listing for details.\n"
196 "\n"
197 "# cartesian data in lidar coordinates in mm\n"
198 "uint16 cartesian_data_valid\n"
199 "int32 x\n"
200 "int32 y\n"
201 "\n"
202 "# polar data in lidar coordinates in mm and mdeg\n"
203 "uint16 polar_data_valid\n"
204 "uint32 dist\n"
205 "uint32 phi\n"
206 "\n"
207 "# optional reflector data\n"
208 "uint16 opt_reflector_data_valid\n"
209 "uint16 local_id\n"
210 "uint16 global_id\n"
211 "uint8 type \n"
212 "uint16 sub_type\n"
213 "uint16 quality\n"
214 "uint32 timestamp\n"
215 "uint16 size\n"
216 "uint16 hit_count\n"
217 "uint16 mean_echo\n"
218 "uint16 start_index\n"
219 "uint16 end_index\n"
220 "\n"
221 "# reflector position in ros coordinates\n"
222 "int8 pos_valid # pose_x, pose_y and pose_yaw are valid if pose_valid > 0\n"
223 "float32 pos_x # x position in ros coordinates in m\n"
224 "float32 pos_y # y position in ros coordinates in m\n"
225 ;
226  }
227 
228  static const char* value(const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator>&) { return value(); }
229 };
230 
231 } // namespace message_traits
232 } // namespace roswrap
233 
234 namespace roswrap
235 {
236 namespace serialization
237 {
238 
239  template<class ContainerAllocator> struct Serializer< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
240  {
241  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
242  {
243  stream.next(m.header);
244  stream.next(m.landmark_filter);
245  stream.next(m.num_reflectors);
246  stream.next(m.reflectors);
247  }
248 
250  }; // struct NAVLandmarkData_
251 
252 } // namespace serialization
253 } // namespace roswrap
254 
255 namespace roswrap
256 {
257 namespace message_operations
258 {
259 
260 template<class ContainerAllocator>
261 struct Printer< ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator> >
262 {
263  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sick_scan_xd::NAVLandmarkData_<ContainerAllocator>& v)
264  {
265  s << indent << "header: ";
266  s << std::endl;
268  s << indent << "landmark_filter: ";
269  Printer<uint8_t>::stream(s, indent + " ", v.landmark_filter);
270  s << indent << "num_reflectors: ";
271  Printer<uint16_t>::stream(s, indent + " ", v.num_reflectors);
272  s << indent << "reflectors[]" << std::endl;
273  for (size_t i = 0; i < v.reflectors.size(); ++i)
274  {
275  s << indent << " reflectors[" << i << "]: ";
276  s << std::endl;
277  s << indent;
279  }
280  }
281 };
282 
283 } // namespace message_operations
284 } // namespace roswrap
285 
286 #endif // SICK_SCAN_MESSAGE_NAVLANDMARKDATA_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::NAVLandmarkData
::sick_scan_xd::NAVLandmarkData_< std::allocator< void > > NAVLandmarkData
Definition: NAVLandmarkData.h:66
roswrap::message_traits::DataType< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::value
static const char * value()
Definition: NAVLandmarkData.h:157
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
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
const
#define const
Definition: getopt.c:38
sick_scan_xd::NAVLandmarkData_::_num_reflectors_type
uint16_t _num_reflectors_type
Definition: NAVLandmarkData.h:51
s
XmlRpcServer s
sick_scan_xd::NAVLandmarkData_::num_reflectors
_num_reflectors_type num_reflectors
Definition: NAVLandmarkData.h:52
roswrap::message_traits::MD5Sum< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > &)
Definition: NAVLandmarkData.h:149
roswrap::message_traits::DataType< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > &)
Definition: NAVLandmarkData.h:162
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
roswrap::message_operations::Printer< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > &v)
Definition: NAVLandmarkData.h:263
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::NAVLandmarkData_::Ptr
std::shared_ptr< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > > Ptr
Definition: NAVLandmarkData.h:61
sick_scan_xd
Definition: abstract_parser.cpp:65
roswrap::message_traits::MD5Sum< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::value
static const char * value()
Definition: NAVLandmarkData.h:144
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
sick_scan_xd::NAVLandmarkData_::Type
NAVLandmarkData_< ContainerAllocator > Type
Definition: NAVLandmarkData.h:27
sick_scan_xd::NAVLandmarkData_
Definition: NAVLandmarkData.h:25
sick_scan_xd::NAVLandmarkDataConstPtr
std::shared_ptr< ::sick_scan_xd::NAVLandmarkData const > NAVLandmarkDataConstPtr
Definition: NAVLandmarkData.h:69
sick_scan_xd::NAVLandmarkData_::reflectors
_reflectors_type reflectors
Definition: NAVLandmarkData.h:55
roswrap::message_traits::Definition< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::value
static const char * value()
Definition: NAVLandmarkData.h:168
roswrap
Definition: param_modi.cpp:41
sick_scan_xd::NAVLandmarkData_::_landmark_filter_type
uint8_t _landmark_filter_type
Definition: NAVLandmarkData.h:48
roswrap::message_operations::Printer
Definition: message_operations.h:40
std_msgs::Header_
Definition: Header.h:23
sick_scan_xd::NAVLandmarkData_::NAVLandmarkData_
NAVLandmarkData_()
Definition: NAVLandmarkData.h:29
sick_scan_xd::NAVLandmarkData_::_reflectors_type
std::vector< ::sick_scan_xd::NAVReflectorData_< ContainerAllocator >, typename std::allocator_traits< ContainerAllocator >::template rebind_alloc< ::sick_scan_xd::NAVReflectorData_< ContainerAllocator > > > _reflectors_type
Definition: NAVLandmarkData.h:54
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::NAVLandmarkData_::landmark_filter
_landmark_filter_type landmark_filter
Definition: NAVLandmarkData.h:49
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
sick_scan_xd::NAVLandmarkData_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: NAVLandmarkData.h:45
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::NAVLandmarkDataPtr
std::shared_ptr< ::sick_scan_xd::NAVLandmarkData > NAVLandmarkDataPtr
Definition: NAVLandmarkData.h:68
roswrap::message_traits::Definition< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > &)
Definition: NAVLandmarkData.h:228
sick_scan_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
roswrap::serialization::Serializer< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: NAVLandmarkData.h:241
NAVReflectorData.h
sick_scan_xd::NAVLandmarkData_::NAVLandmarkData_
NAVLandmarkData_(const ContainerAllocator &_alloc)
Definition: NAVLandmarkData.h:35
Header.h
sick_scan_xd::NAVLandmarkData_::header
_header_type header
Definition: NAVLandmarkData.h:46
sick_scan_xd::NAVLandmarkData_::ConstPtr
std::shared_ptr< ::sick_scan_xd::NAVLandmarkData_< ContainerAllocator > const > ConstPtr
Definition: NAVLandmarkData.h:62


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