6 #ifndef SICK_SCAN_MESSAGE_RADARPREHEADER_H
7 #define SICK_SCAN_MESSAGE_RADARPREHEADER_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
26 template <
class ContainerAllocator>
61 typedef std::vector< ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator> >::other >
_radarpreheaderarrayencoderblock_type;
68 typedef std::shared_ptr< ::sick_scan_xd::RadarPreHeader_<ContainerAllocator> >
Ptr;
69 typedef std::shared_ptr< ::sick_scan_xd::RadarPreHeader_<ContainerAllocator>
const>
ConstPtr;
73 typedef ::sick_scan_xd::RadarPreHeader_<std::allocator<void> >
RadarPreHeader;
82 template<
typename ContainerAllocator>
83 std::ostream&
operator<<(std::ostream& s, const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator> & v)
90 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
91 bool operator==(const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator2> & rhs)
93 return lhs.uiversionno == rhs.uiversionno &&
94 lhs.radarpreheaderdeviceblock == rhs.radarpreheaderdeviceblock &&
95 lhs.radarpreheaderstatusblock == rhs.radarpreheaderstatusblock &&
96 lhs.radarpreheadermeasurementparam1block == rhs.radarpreheadermeasurementparam1block &&
97 lhs.radarpreheaderarrayencoderblock == rhs.radarpreheaderarrayencoderblock;
100 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
101 bool operator!=(const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator2> & rhs)
103 return !(lhs == rhs);
111 namespace message_traits
118 template <
class ContainerAllocator>
123 template <
class ContainerAllocator>
128 template <
class ContainerAllocator>
133 template <
class ContainerAllocator>
138 template <
class ContainerAllocator>
143 template <
class ContainerAllocator>
149 template<
class ContainerAllocator>
154 return "93c686aba0ebefe54be53e989cc7f823";
157 static const char*
value(const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator>&) {
return value(); }
158 static const uint64_t static_value1 = 0x93c686aba0ebefe5ULL;
159 static const uint64_t static_value2 = 0x4be53e989cc7f823ULL;
162 template<
class ContainerAllocator>
167 return "sick_scan/RadarPreHeader";
170 static const char*
value(const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator>&) {
return value(); }
173 template<
class ContainerAllocator>
178 return "# Version information for this whole structure (MeasurementData)\n"
181 "#uint16 uiVersionNo\n"
182 "#sick_scan/RadarPreHeaderDeviceBlock radarPreHeaderDeviceBlock\n"
183 "#sick_scan/RadarPreHeaderStatusBlock radarPreHeaderStatusBlock\n"
184 "#sick_scan/RadarPreHeaderMeasurementParam1Block radarPreHeaderMeasurementParam1Block\n"
185 "#sick_scan/RadarPreHeaderEncoderBlock[] radarPreHeaderArrayEncoderBlock\n"
188 "uint16 uiversionno\n"
189 "sick_scan/RadarPreHeaderDeviceBlock radarpreheaderdeviceblock\n"
190 "sick_scan/RadarPreHeaderStatusBlock radarpreheaderstatusblock\n"
191 "sick_scan/RadarPreHeaderMeasurementParam1Block radarpreheadermeasurementparam1block\n"
192 "sick_scan/RadarPreHeaderEncoderBlock[] radarpreheaderarrayencoderblock\n"
194 "================================================================================\n"
195 "MSG: sick_scan/RadarPreHeaderDeviceBlock\n"
202 "#uint32 uiIdent # Logical number of the device\"\n"
203 "#uint32 udiSerialNo # Serial number of the device\n"
204 "#bool bDeviceError # State of the device\n"
205 "#bool bContaminationWarning # Contamination Warning\n"
206 "#bool bContaminationError # Contamination Error\n"
209 "uint32 uiident # Logical number of the device\"\n"
210 "uint32 udiserialno # Serial number of the device\n"
211 "bool bdeviceerror # State of the device\n"
212 "bool bcontaminationwarning # Contamination Warning\n"
213 "bool bcontaminationerror # Contamination Error\n"
215 "================================================================================\n"
216 "MSG: sick_scan/RadarPreHeaderStatusBlock\n"
221 "#uint32 uiTelegramCount # telegram number\n"
222 "#uint32 uiCycleCount # \"scan number\"\n"
223 "#uint32 udiSystemCountScan # system time since power on of scan gen. [us]\n"
224 "#uint32 udiSystemCountTransmit # system time since power on of scan transmission [us]\n"
225 "#uint16 uiInputs # state of digital inputs\n"
226 "#uint16 uiOutputs # state of digital outputs\n"
229 "uint32 uitelegramcount # telegram number\n"
230 "uint32 uicyclecount # \"scan number\"\n"
231 "uint32 udisystemcountscan # system time since power on of scan gen. [us]\n"
232 "uint32 udisystemcounttransmit # system time since power on of scan transmission [us]\n"
233 "uint16 uiinputs # state of digital inputs\n"
234 "uint16 uioutputs # state of digital outputs\n"
236 "================================================================================\n"
237 "MSG: sick_scan/RadarPreHeaderMeasurementParam1Block\n"
239 "#uint32 uiCycleDuration # Time in microseconds to detect this items\n"
240 "#uint32 uiNoiseLevel # [1/100dB]\n"
242 "uint32 uicycleduration # Time in microseconds to detect this items\n"
243 "uint32 uinoiselevel # [1/100dB]\n"
245 "================================================================================\n"
246 "MSG: sick_scan/RadarPreHeaderEncoderBlock\n"
247 "# Array with connected encoder sensors\n"
249 "#uint32 udiEncoderPos # encoder position [inc]\n"
250 "#int16 iEncoderSpeed # encoder speed [inc/mm]\n"
252 "uint32 udiencoderpos # encoder position [inc]\n"
253 "int16 iencoderspeed # encoder speed [inc/mm]\n"
257 static const char*
value(const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator>&) {
return value(); }
265 namespace serialization
270 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
272 stream.next(m.uiversionno);
273 stream.next(m.radarpreheaderdeviceblock);
274 stream.next(m.radarpreheaderstatusblock);
275 stream.next(m.radarpreheadermeasurementparam1block);
276 stream.next(m.radarpreheaderarrayencoderblock);
287 namespace message_operations
290 template<
class ContainerAllocator>
293 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sick_scan_xd::RadarPreHeader_<ContainerAllocator>& v)
295 s <<
indent <<
"uiversionno: ";
297 s <<
indent <<
"radarpreheaderdeviceblock: ";
300 s <<
indent <<
"radarpreheaderstatusblock: ";
303 s <<
indent <<
"radarpreheadermeasurementparam1block: ";
306 s <<
indent <<
"radarpreheaderarrayencoderblock[]" << std::endl;
307 for (
size_t i = 0; i < v.radarpreheaderarrayencoderblock.size(); ++i)
309 s <<
indent <<
" radarpreheaderarrayencoderblock[" << i <<
"]: ";
320 #endif // SICK_SCAN_MESSAGE_RADARPREHEADER_H