RadarScan.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/RadarScan.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SICK_SCAN_MESSAGE_RADARSCAN_H
7 #define SICK_SCAN_MESSAGE_RADARSCAN_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>
23 
24 namespace sick_scan_xd
25 {
26 template <class ContainerAllocator>
27 struct RadarScan_
28 {
30 
32  : header()
33  , radarpreheader()
34  , targets()
35  , objects() {
36  }
37  RadarScan_(const ContainerAllocator& _alloc)
38  : header(_alloc)
39  , radarpreheader(_alloc)
40  , targets(_alloc)
41  , objects(_alloc) {
42  (void)_alloc;
43  }
44 
45 
46 
47  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
49 
50  typedef ::sick_scan_xd::RadarPreHeader_<ContainerAllocator> _radarpreheader_type;
52 
53  typedef ::sensor_msgs::PointCloud2_<ContainerAllocator> _targets_type;
55 
56  typedef std::vector< ::sick_scan_xd::RadarObject_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sick_scan_xd::RadarObject_<ContainerAllocator> >::other > _objects_type;
58 
59 
60 
61 
62 
63  typedef std::shared_ptr< ::sick_scan_xd::RadarScan_<ContainerAllocator> > Ptr;
64  typedef std::shared_ptr< ::sick_scan_xd::RadarScan_<ContainerAllocator> const> ConstPtr;
65 
66 }; // struct RadarScan_
67 
68 typedef ::sick_scan_xd::RadarScan_<std::allocator<void> > RadarScan;
69 
70 typedef std::shared_ptr< ::sick_scan_xd::RadarScan > RadarScanPtr;
71 typedef std::shared_ptr< ::sick_scan_xd::RadarScan const> RadarScanConstPtr;
72 
73 // constants requiring out of line definition
74 
75 
76 
77 template<typename ContainerAllocator>
78 std::ostream& operator<<(std::ostream& s, const ::sick_scan_xd::RadarScan_<ContainerAllocator> & v)
79 {
81 return s;
82 }
83 
84 
85 template<typename ContainerAllocator1, typename ContainerAllocator2>
86 bool operator==(const ::sick_scan_xd::RadarScan_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarScan_<ContainerAllocator2> & rhs)
87 {
88  return lhs.header == rhs.header &&
89  lhs.radarpreheader == rhs.radarpreheader &&
90  lhs.targets == rhs.targets &&
91  lhs.objects == rhs.objects;
92 }
93 
94 template<typename ContainerAllocator1, typename ContainerAllocator2>
95 bool operator!=(const ::sick_scan_xd::RadarScan_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarScan_<ContainerAllocator2> & rhs)
96 {
97  return !(lhs == rhs);
98 }
99 
100 
101 } // namespace sick_scan_xd
102 
103 namespace roswrap
104 {
105 namespace message_traits
106 {
107 
108 
109 
110 
111 
112 template <class ContainerAllocator>
113 struct IsFixedSize< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
114  : FalseType
115  { };
116 
117 template <class ContainerAllocator>
118 struct IsFixedSize< ::sick_scan_xd::RadarScan_<ContainerAllocator> const>
119  : FalseType
120  { };
121 
122 template <class ContainerAllocator>
123 struct IsMessage< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
124  : TrueType
125  { };
126 
127 template <class ContainerAllocator>
128 struct IsMessage< ::sick_scan_xd::RadarScan_<ContainerAllocator> const>
129  : TrueType
130  { };
131 
132 template <class ContainerAllocator>
133 struct HasHeader< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
134  : TrueType
135  { };
136 
137 template <class ContainerAllocator>
138 struct HasHeader< ::sick_scan_xd::RadarScan_<ContainerAllocator> const>
139  : TrueType
140  { };
141 
142 
143 template<class ContainerAllocator>
144 struct MD5Sum< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
145 {
146  static const char* value()
147  {
148  return "3522a556afdfee3cdd216082c57b4a98";
149  }
150 
151  static const char* value(const ::sick_scan_xd::RadarScan_<ContainerAllocator>&) { return value(); }
152  static const uint64_t static_value1 = 0x3522a556afdfee3cULL;
153  static const uint64_t static_value2 = 0xdd216082c57b4a98ULL;
154 };
155 
156 template<class ContainerAllocator>
157 struct DataType< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
158 {
159  static const char* value()
160  {
161  return "sick_scan/RadarScan";
162  }
163 
164  static const char* value(const ::sick_scan_xd::RadarScan_<ContainerAllocator>&) { return value(); }
165 };
166 
167 template<class ContainerAllocator>
168 struct Definition< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
169 {
170  static const char* value()
171  {
172  return "#\n"
173 "# The message is divided into three parts:\n"
174 "# 1. Header: containing information about general radar parameters\n"
175 "# 2. RawTargets: List of targets containing maximum values in the range-doppler-matrix - used for tracking\n"
176 "# 3. Objects: List of objects generated by the internal tracking algorithm - based on raw targets\n"
177 "# ROS-1:\n"
178 "#Header header\n"
179 "#RadarPreHeader radarPreHeader\n"
180 "# ROS-2:\n"
181 "std_msgs/Header header\n"
182 "RadarPreHeader radarpreheader\n"
183 "sensor_msgs/PointCloud2 targets\n"
184 "sick_scan/RadarObject[] objects\n"
185 "================================================================================\n"
186 "MSG: std_msgs/Header\n"
187 "# Standard metadata for higher-level stamped data types.\n"
188 "# This is generally used to communicate timestamped data \n"
189 "# in a particular coordinate frame.\n"
190 "# \n"
191 "# sequence ID: consecutively increasing ID \n"
192 "uint32 seq\n"
193 "#Two-integer timestamp that is expressed as:\n"
194 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
195 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
196 "# time-handling sugar is provided by the client library\n"
197 "time stamp\n"
198 "#Frame this data is associated with\n"
199 "string frame_id\n"
200 "\n"
201 "================================================================================\n"
202 "MSG: sick_scan/RadarPreHeader\n"
203 "# Version information for this whole structure (MeasurementData)\n"
204 "\n"
205 "# ROS-1:\n"
206 "#uint16 uiVersionNo\n"
207 "#sick_scan/RadarPreHeaderDeviceBlock radarPreHeaderDeviceBlock\n"
208 "#sick_scan/RadarPreHeaderStatusBlock radarPreHeaderStatusBlock\n"
209 "#sick_scan/RadarPreHeaderMeasurementParam1Block radarPreHeaderMeasurementParam1Block\n"
210 "#sick_scan/RadarPreHeaderEncoderBlock[] radarPreHeaderArrayEncoderBlock\n"
211 "\n"
212 "# ROS-2:\n"
213 "uint16 uiversionno\n"
214 "sick_scan/RadarPreHeaderDeviceBlock radarpreheaderdeviceblock\n"
215 "sick_scan/RadarPreHeaderStatusBlock radarpreheaderstatusblock\n"
216 "sick_scan/RadarPreHeaderMeasurementParam1Block radarpreheadermeasurementparam1block\n"
217 "sick_scan/RadarPreHeaderEncoderBlock[] radarpreheaderarrayencoderblock\n"
218 "\n"
219 "================================================================================\n"
220 "MSG: sick_scan/RadarPreHeaderDeviceBlock\n"
221 "#\n"
222 "#\n"
223 "#\n"
224 "#\n"
225 "\n"
226 "# ROS-1:\n"
227 "#uint32 uiIdent # Logical number of the device\"\n"
228 "#uint32 udiSerialNo # Serial number of the device\n"
229 "#bool bDeviceError # State of the device\n"
230 "#bool bContaminationWarning # Contamination Warning\n"
231 "#bool bContaminationError # Contamination Error\n"
232 "\n"
233 "# ROS-2:\n"
234 "uint32 uiident # Logical number of the device\"\n"
235 "uint32 udiserialno # Serial number of the device\n"
236 "bool bdeviceerror # State of the device\n"
237 "bool bcontaminationwarning # Contamination Warning\n"
238 "bool bcontaminationerror # Contamination Error\n"
239 "\n"
240 "================================================================================\n"
241 "MSG: sick_scan/RadarPreHeaderStatusBlock\n"
242 "#\n"
243 "#\n"
244 "#\n"
245 "# ROS-1:\n"
246 "#uint32 uiTelegramCount # telegram number\n"
247 "#uint32 uiCycleCount # \"scan number\"\n"
248 "#uint32 udiSystemCountScan # system time since power on of scan gen. [us]\n"
249 "#uint32 udiSystemCountTransmit # system time since power on of scan transmission [us]\n"
250 "#uint16 uiInputs # state of digital inputs\n"
251 "#uint16 uiOutputs # state of digital outputs\n"
252 "\n"
253 "# ROS-2:\n"
254 "uint32 uitelegramcount # telegram number\n"
255 "uint32 uicyclecount # \"scan number\"\n"
256 "uint32 udisystemcountscan # system time since power on of scan gen. [us]\n"
257 "uint32 udisystemcounttransmit # system time since power on of scan transmission [us]\n"
258 "uint16 uiinputs # state of digital inputs\n"
259 "uint16 uioutputs # state of digital outputs\n"
260 "\n"
261 "================================================================================\n"
262 "MSG: sick_scan/RadarPreHeaderMeasurementParam1Block\n"
263 "# ROS-1:\n"
264 "#uint32 uiCycleDuration # Time in microseconds to detect this items\n"
265 "#uint32 uiNoiseLevel # [1/100dB]\n"
266 "# ROS-2:\n"
267 "uint32 uicycleduration # Time in microseconds to detect this items\n"
268 "uint32 uinoiselevel # [1/100dB]\n"
269 "\n"
270 "================================================================================\n"
271 "MSG: sick_scan/RadarPreHeaderEncoderBlock\n"
272 "# Array with connected encoder sensors\n"
273 "# ROS-1:\n"
274 "#uint32 udiEncoderPos # encoder position [inc]\n"
275 "#int16 iEncoderSpeed # encoder speed [inc/mm]\n"
276 "# ROS-2:\n"
277 "uint32 udiencoderpos # encoder position [inc]\n"
278 "int16 iencoderspeed # encoder speed [inc/mm]\n"
279 "\n"
280 "================================================================================\n"
281 "MSG: sensor_msgs/PointCloud2\n"
282 "# This message holds a collection of N-dimensional points, which may\n"
283 "# contain additional information such as normals, intensity, etc. The\n"
284 "# point data is stored as a binary blob, its layout described by the\n"
285 "# contents of the \"fields\" array.\n"
286 "\n"
287 "# The point cloud data may be organized 2d (image-like) or 1d\n"
288 "# (unordered). Point clouds organized as 2d images may be produced by\n"
289 "# camera depth sensors such as stereo or time-of-flight.\n"
290 "\n"
291 "# Time of sensor data acquisition, and the coordinate frame ID (for 3d\n"
292 "# points).\n"
293 "Header header\n"
294 "\n"
295 "# 2D structure of the point cloud. If the cloud is unordered, height is\n"
296 "# 1 and width is the length of the point cloud.\n"
297 "uint32 height\n"
298 "uint32 width\n"
299 "\n"
300 "# Describes the channels and their layout in the binary data blob.\n"
301 "PointField[] fields\n"
302 "\n"
303 "bool is_bigendian # Is this data bigendian?\n"
304 "uint32 point_step # Length of a point in bytes\n"
305 "uint32 row_step # Length of a row in bytes\n"
306 "uint8[] data # Actual point data, size is (row_step*height)\n"
307 "\n"
308 "bool is_dense # True if there are no invalid points\n"
309 "\n"
310 "================================================================================\n"
311 "MSG: sensor_msgs/PointField\n"
312 "# This message holds the description of one point entry in the\n"
313 "# PointCloud2 message format.\n"
314 "uint8 INT8 = 1\n"
315 "uint8 UINT8 = 2\n"
316 "uint8 INT16 = 3\n"
317 "uint8 UINT16 = 4\n"
318 "uint8 INT32 = 5\n"
319 "uint8 UINT32 = 6\n"
320 "uint8 FLOAT32 = 7\n"
321 "uint8 FLOAT64 = 8\n"
322 "\n"
323 "string name # Name of field\n"
324 "uint32 offset # Offset from start of point struct\n"
325 "uint8 datatype # Datatype enumeration, see above\n"
326 "uint32 count # How many elements in the field\n"
327 "\n"
328 "================================================================================\n"
329 "MSG: sick_scan/RadarObject\n"
330 "int32 id\n"
331 "\n"
332 "# ROS-1:\n"
333 "time tracking_time # since when the object is tracked\n"
334 "time last_seen\n"
335 "\n"
336 "# ROS-2:\n"
337 "#builtin_interfaces/Time tracking_time # since when the object is tracked\n"
338 "#builtin_interfaces/Time last_seen\n"
339 "\n"
340 "geometry_msgs/TwistWithCovariance velocity\n"
341 "\n"
342 "geometry_msgs/Pose bounding_box_center\n"
343 "geometry_msgs/Vector3 bounding_box_size\n"
344 "\n"
345 "geometry_msgs/PoseWithCovariance object_box_center\n"
346 "geometry_msgs/Vector3 object_box_size\n"
347 "\n"
348 "geometry_msgs/Point[] contour_points\n"
349 "\n"
350 "================================================================================\n"
351 "MSG: geometry_msgs/TwistWithCovariance\n"
352 "# This expresses velocity in free space with uncertainty.\n"
353 "\n"
354 "Twist twist\n"
355 "\n"
356 "# Row-major representation of the 6x6 covariance matrix\n"
357 "# The orientation parameters use a fixed-axis representation.\n"
358 "# In order, the parameters are:\n"
359 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
360 "float64[36] covariance\n"
361 "\n"
362 "================================================================================\n"
363 "MSG: geometry_msgs/Twist\n"
364 "# This expresses velocity in free space broken into its linear and angular parts.\n"
365 "Vector3 linear\n"
366 "Vector3 angular\n"
367 "\n"
368 "================================================================================\n"
369 "MSG: geometry_msgs/Vector3\n"
370 "# This represents a vector in free space. \n"
371 "# It is only meant to represent a direction. Therefore, it does not\n"
372 "# make sense to apply a translation to it (e.g., when applying a \n"
373 "# generic rigid transformation to a Vector3, tf2 will only apply the\n"
374 "# rotation). If you want your data to be translatable too, use the\n"
375 "# geometry_msgs/Point message instead.\n"
376 "\n"
377 "float64 x\n"
378 "float64 y\n"
379 "float64 z\n"
380 "================================================================================\n"
381 "MSG: geometry_msgs/Pose\n"
382 "# A representation of pose in free space, composed of position and orientation. \n"
383 "Point position\n"
384 "Quaternion orientation\n"
385 "\n"
386 "================================================================================\n"
387 "MSG: geometry_msgs/Point\n"
388 "# This contains the position of a point in free space\n"
389 "float64 x\n"
390 "float64 y\n"
391 "float64 z\n"
392 "\n"
393 "================================================================================\n"
394 "MSG: geometry_msgs/Quaternion\n"
395 "# This represents an orientation in free space in quaternion form.\n"
396 "\n"
397 "float64 x\n"
398 "float64 y\n"
399 "float64 z\n"
400 "float64 w\n"
401 "\n"
402 "================================================================================\n"
403 "MSG: geometry_msgs/PoseWithCovariance\n"
404 "# This represents a pose in free space with uncertainty.\n"
405 "\n"
406 "Pose pose\n"
407 "\n"
408 "# Row-major representation of the 6x6 covariance matrix\n"
409 "# The orientation parameters use a fixed-axis representation.\n"
410 "# In order, the parameters are:\n"
411 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
412 "float64[36] covariance\n"
413 ;
414  }
415 
416  static const char* value(const ::sick_scan_xd::RadarScan_<ContainerAllocator>&) { return value(); }
417 };
418 
419 } // namespace message_traits
420 } // namespace roswrap
421 
422 namespace roswrap
423 {
424 namespace serialization
425 {
426 
427  template<class ContainerAllocator> struct Serializer< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
428  {
429  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
430  {
431  stream.next(m.header);
432  stream.next(m.radarpreheader);
433  stream.next(m.targets);
434  stream.next(m.objects);
435  }
436 
438  }; // struct RadarScan_
439 
440 } // namespace serialization
441 } // namespace roswrap
442 
443 namespace roswrap
444 {
445 namespace message_operations
446 {
447 
448 template<class ContainerAllocator>
449 struct Printer< ::sick_scan_xd::RadarScan_<ContainerAllocator> >
450 {
451  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sick_scan_xd::RadarScan_<ContainerAllocator>& v)
452  {
453  s << indent << "header: ";
454  s << std::endl;
456  s << indent << "radarpreheader: ";
457  s << std::endl;
459  s << indent << "targets: ";
460  s << std::endl;
462  s << indent << "objects[]" << std::endl;
463  for (size_t i = 0; i < v.objects.size(); ++i)
464  {
465  s << indent << " objects[" << i << "]: ";
466  s << std::endl;
467  s << indent;
469  }
470  }
471 };
472 
473 } // namespace message_operations
474 } // namespace roswrap
475 
476 #endif // SICK_SCAN_MESSAGE_RADARSCAN_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::RadarScan_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: RadarScan.h:47
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
sick_scan_xd::RadarScan_::_targets_type
::sensor_msgs::PointCloud2_< ContainerAllocator > _targets_type
Definition: RadarScan.h:53
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::RadarScan_::_radarpreheader_type
::sick_scan_xd::RadarPreHeader_< ContainerAllocator > _radarpreheader_type
Definition: RadarScan.h:50
s
XmlRpcServer s
sick_scan_xd::RadarScan_::targets
_targets_type targets
Definition: RadarScan.h:54
roswrap::message_traits::MD5Sum< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::RadarScan_< ContainerAllocator > &)
Definition: RadarScan.h:151
roswrap::message_operations::Printer::stream
static void stream(Stream &s, const std::string &indent, const M &value)
Definition: message_operations.h:43
roswrap::serialization::Serializer< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: RadarScan.h:429
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::RadarScan_::Ptr
std::shared_ptr< ::sick_scan_xd::RadarScan_< ContainerAllocator > > Ptr
Definition: RadarScan.h:63
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
roswrap::message_traits::MD5Sum< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::value
static const char * value()
Definition: RadarScan.h:146
sick_scan_xd
Definition: abstract_parser.cpp:65
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::RadarScan_::ConstPtr
std::shared_ptr< ::sick_scan_xd::RadarScan_< ContainerAllocator > const > ConstPtr
Definition: RadarScan.h:64
sick_scan_xd::RadarScan_::RadarScan_
RadarScan_()
Definition: RadarScan.h:31
sick_scan_xd::RadarScan_::_objects_type
std::vector< ::sick_scan_xd::RadarObject_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::other > _objects_type
Definition: RadarScan.h:56
sick_scan_xd::RadarScanConstPtr
std::shared_ptr< ::sick_scan_xd::RadarScan const > RadarScanConstPtr
Definition: RadarScan.h:71
roswrap::message_traits::DataType< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::value
static const char * value()
Definition: RadarScan.h:159
sick_scan_xd::RadarScan_::header
_header_type header
Definition: RadarScan.h:48
RadarObject.h
PointCloud2.h
RadarPreHeader.h
roswrap::message_traits::Definition< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::RadarScan_< ContainerAllocator > &)
Definition: RadarScan.h:416
sick_scan_xd::RadarScan_
Definition: RadarScan.h:27
roswrap
Definition: param_modi.cpp:41
roswrap::message_traits::Definition< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::value
static const char * value()
Definition: RadarScan.h:170
sick_scan_xd::RadarScan_::RadarScan_
RadarScan_(const ContainerAllocator &_alloc)
Definition: RadarScan.h:37
roswrap::message_operations::Printer
Definition: message_operations.h:40
std_msgs::Header_
Definition: Header.h:23
roswrap::message_traits::DataType< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::RadarScan_< ContainerAllocator > &)
Definition: RadarScan.h:164
sick_scan_xd::RadarScan_::objects
_objects_type objects
Definition: RadarScan.h:57
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
sensor_msgs::PointCloud2_
Definition: PointCloud2.h:25
sick_scan_xd::RadarPreHeader_
Definition: RadarPreHeader.h:27
sick_scan_xd::RadarScan_::Type
RadarScan_< ContainerAllocator > Type
Definition: RadarScan.h:29
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
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_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
sick_scan_xd::RadarScanPtr
std::shared_ptr< ::sick_scan_xd::RadarScan > RadarScanPtr
Definition: RadarScan.h:70
sick_scan_xd::RadarScan
::sick_scan_xd::RadarScan_< std::allocator< void > > RadarScan
Definition: RadarScan.h:68
roswrap::message_operations::Printer< ::sick_scan_xd::RadarScan_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sick_scan_xd::RadarScan_< ContainerAllocator > &v)
Definition: RadarScan.h:451
Header.h
sick_scan_xd::RadarScan_::radarpreheader
_radarpreheader_type radarpreheader
Definition: RadarScan.h:51


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