6 #ifndef SICK_SCAN_MESSAGE_RADAROBJECT_H
7 #define SICK_SCAN_MESSAGE_RADAROBJECT_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
28 template <
class ContainerAllocator>
68 typedef ::geometry_msgs::TwistWithCovariance_<ContainerAllocator>
_velocity_type;
83 typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other >
_contour_points_type;
90 typedef std::shared_ptr< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
Ptr;
91 typedef std::shared_ptr< ::sick_scan_xd::RadarObject_<ContainerAllocator>
const>
ConstPtr;
95 typedef ::sick_scan_xd::RadarObject_<std::allocator<void> >
RadarObject;
104 template<
typename ContainerAllocator>
105 std::ostream&
operator<<(std::ostream& s, const ::sick_scan_xd::RadarObject_<ContainerAllocator> & v)
112 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
113 bool operator==(const ::sick_scan_xd::RadarObject_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarObject_<ContainerAllocator2> & rhs)
115 return lhs.id == rhs.id &&
116 lhs.tracking_time == rhs.tracking_time &&
117 lhs.last_seen == rhs.last_seen &&
118 lhs.velocity == rhs.velocity &&
119 lhs.bounding_box_center == rhs.bounding_box_center &&
120 lhs.bounding_box_size == rhs.bounding_box_size &&
121 lhs.object_box_center == rhs.object_box_center &&
122 lhs.object_box_size == rhs.object_box_size &&
123 lhs.contour_points == rhs.contour_points;
126 template<
typename ContainerAllocator1,
typename ContainerAllocator2>
127 bool operator!=(const ::sick_scan_xd::RadarObject_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarObject_<ContainerAllocator2> & rhs)
129 return !(lhs == rhs);
137 namespace message_traits
144 template <
class ContainerAllocator>
149 template <
class ContainerAllocator>
154 template <
class ContainerAllocator>
159 template <
class ContainerAllocator>
164 template <
class ContainerAllocator>
169 template <
class ContainerAllocator>
175 template<
class ContainerAllocator>
180 return "a5d0f2d250163ffa0098d0fc8218fc4a";
183 static const char*
value(const ::sick_scan_xd::RadarObject_<ContainerAllocator>&) {
return value(); }
184 static const uint64_t static_value1 = 0xa5d0f2d250163ffaULL;
185 static const uint64_t static_value2 = 0x0098d0fc8218fc4aULL;
188 template<
class ContainerAllocator>
193 return "sick_scan/RadarObject";
196 static const char*
value(const ::sick_scan_xd::RadarObject_<ContainerAllocator>&) {
return value(); }
199 template<
class ContainerAllocator>
207 "time tracking_time # since when the object is tracked\n"
211 "#builtin_interfaces/Time tracking_time # since when the object is tracked\n"
212 "#builtin_interfaces/Time last_seen\n"
214 "geometry_msgs/TwistWithCovariance velocity\n"
216 "geometry_msgs/Pose bounding_box_center\n"
217 "geometry_msgs/Vector3 bounding_box_size\n"
219 "geometry_msgs/PoseWithCovariance object_box_center\n"
220 "geometry_msgs/Vector3 object_box_size\n"
222 "geometry_msgs/Point[] contour_points\n"
224 "================================================================================\n"
225 "MSG: geometry_msgs/TwistWithCovariance\n"
226 "# This expresses velocity in free space with uncertainty.\n"
230 "# Row-major representation of the 6x6 covariance matrix\n"
231 "# The orientation parameters use a fixed-axis representation.\n"
232 "# In order, the parameters are:\n"
233 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
234 "float64[36] covariance\n"
236 "================================================================================\n"
237 "MSG: geometry_msgs/Twist\n"
238 "# This expresses velocity in free space broken into its linear and angular parts.\n"
242 "================================================================================\n"
243 "MSG: geometry_msgs/Vector3\n"
244 "# This represents a vector in free space. \n"
245 "# It is only meant to represent a direction. Therefore, it does not\n"
246 "# make sense to apply a translation to it (e.g., when applying a \n"
247 "# generic rigid transformation to a Vector3, tf2 will only apply the\n"
248 "# rotation). If you want your data to be translatable too, use the\n"
249 "# geometry_msgs/Point message instead.\n"
254 "================================================================================\n"
255 "MSG: geometry_msgs/Pose\n"
256 "# A representation of pose in free space, composed of position and orientation. \n"
258 "Quaternion orientation\n"
260 "================================================================================\n"
261 "MSG: geometry_msgs/Point\n"
262 "# This contains the position of a point in free space\n"
267 "================================================================================\n"
268 "MSG: geometry_msgs/Quaternion\n"
269 "# This represents an orientation in free space in quaternion form.\n"
276 "================================================================================\n"
277 "MSG: geometry_msgs/PoseWithCovariance\n"
278 "# This represents a pose in free space with uncertainty.\n"
282 "# Row-major representation of the 6x6 covariance matrix\n"
283 "# The orientation parameters use a fixed-axis representation.\n"
284 "# In order, the parameters are:\n"
285 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
286 "float64[36] covariance\n"
290 static const char*
value(const ::sick_scan_xd::RadarObject_<ContainerAllocator>&) {
return value(); }
298 namespace serialization
303 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
306 stream.next(m.tracking_time);
307 stream.next(m.last_seen);
308 stream.next(m.velocity);
309 stream.next(m.bounding_box_center);
310 stream.next(m.bounding_box_size);
311 stream.next(m.object_box_center);
312 stream.next(m.object_box_size);
313 stream.next(m.contour_points);
324 namespace message_operations
327 template<
class ContainerAllocator>
330 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sick_scan_xd::RadarObject_<ContainerAllocator>& v)
334 s <<
indent <<
"tracking_time: ";
341 s <<
indent <<
"bounding_box_center: ";
344 s <<
indent <<
"bounding_box_size: ";
347 s <<
indent <<
"object_box_center: ";
350 s <<
indent <<
"object_box_size: ";
353 s <<
indent <<
"contour_points[]" << std::endl;
354 for (
size_t i = 0; i < v.contour_points.size(); ++i)
356 s <<
indent <<
" contour_points[" << i <<
"]: ";
367 #endif // SICK_SCAN_MESSAGE_RADAROBJECT_H