6 #ifndef SICK_SCAN_MESSAGE_RADARPREHEADERENCODERBLOCK_H
7 #define SICK_SCAN_MESSAGE_RADARPREHEADERENCODERBLOCK_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
22 template <
class ContainerAllocator>
49 typedef std::shared_ptr< ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator> >
Ptr;
50 typedef std::shared_ptr< ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator>
const>
ConstPtr;
63 template<
typename ContainerAllocator>
64 std::ostream&
operator<<(std::ostream& s, const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator> & v)
71 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
72 bool operator==(const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator2> & rhs)
74 return lhs.udiencoderpos == rhs.udiencoderpos &&
75 lhs.iencoderspeed == rhs.iencoderspeed;
78 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
79 bool operator!=(const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator2> & rhs)
89 namespace message_traits
96 template <
class ContainerAllocator>
101 template <
class ContainerAllocator>
106 template <
class ContainerAllocator>
111 template <
class ContainerAllocator>
116 template <
class ContainerAllocator>
121 template <
class ContainerAllocator>
127 template<
class ContainerAllocator>
132 return "fe409801376c90135322466d8a5244ac";
135 static const char*
value(const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator>&) {
return value(); }
136 static const uint64_t static_value1 = 0xfe409801376c9013ULL;
137 static const uint64_t static_value2 = 0x5322466d8a5244acULL;
140 template<
class ContainerAllocator>
145 return "sick_scan/RadarPreHeaderEncoderBlock";
148 static const char*
value(const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator>&) {
return value(); }
151 template<
class ContainerAllocator>
156 return "# Array with connected encoder sensors\n"
158 "#uint32 udiEncoderPos # encoder position [inc]\n"
159 "#int16 iEncoderSpeed # encoder speed [inc/mm]\n"
161 "uint32 udiencoderpos # encoder position [inc]\n"
162 "int16 iencoderspeed # encoder speed [inc/mm]\n"
166 static const char*
value(const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator>&) {
return value(); }
174 namespace serialization
179 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
181 stream.next(m.udiencoderpos);
182 stream.next(m.iencoderspeed);
193 namespace message_operations
196 template<
class ContainerAllocator>
199 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sick_scan_xd::RadarPreHeaderEncoderBlock_<ContainerAllocator>& v)
201 s <<
indent <<
"udiencoderpos: ";
203 s <<
indent <<
"iencoderspeed: ";
211 #endif // SICK_SCAN_MESSAGE_RADARPREHEADERENCODERBLOCK_H