RadarObject.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/RadarObject.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SICK_SCAN_MESSAGE_RADAROBJECT_H
7 #define SICK_SCAN_MESSAGE_RADAROBJECT_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 
20 #include <geometry_msgs/Pose.h>
21 #include <geometry_msgs/Vector3.h>
23 #include <geometry_msgs/Vector3.h>
24 #include <geometry_msgs/Point.h>
25 
26 namespace sick_scan_xd
27 {
28 template <class ContainerAllocator>
30 {
32 
34  : id(0)
35  , tracking_time()
36  , last_seen()
37  , velocity()
41  , object_box_size()
42  , contour_points() {
43  }
44  RadarObject_(const ContainerAllocator& _alloc)
45  : id(0)
46  , tracking_time()
47  , last_seen()
48  , velocity(_alloc)
49  , bounding_box_center(_alloc)
50  , bounding_box_size(_alloc)
51  , object_box_center(_alloc)
52  , object_box_size(_alloc)
53  , contour_points(_alloc) {
54  (void)_alloc;
55  }
56 
57 
58 
59  typedef int32_t _id_type;
61 
64 
67 
68  typedef ::geometry_msgs::TwistWithCovariance_<ContainerAllocator> _velocity_type;
70 
71  typedef ::geometry_msgs::Pose_<ContainerAllocator> _bounding_box_center_type;
73 
74  typedef ::geometry_msgs::Vector3_<ContainerAllocator> _bounding_box_size_type;
76 
77  typedef ::geometry_msgs::PoseWithCovariance_<ContainerAllocator> _object_box_center_type;
79 
80  typedef ::geometry_msgs::Vector3_<ContainerAllocator> _object_box_size_type;
82 
83  typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > _contour_points_type;
85 
86 
87 
88 
89 
90  typedef std::shared_ptr< ::sick_scan_xd::RadarObject_<ContainerAllocator> > Ptr;
91  typedef std::shared_ptr< ::sick_scan_xd::RadarObject_<ContainerAllocator> const> ConstPtr;
92 
93 }; // struct RadarObject_
94 
95 typedef ::sick_scan_xd::RadarObject_<std::allocator<void> > RadarObject;
96 
97 typedef std::shared_ptr< ::sick_scan_xd::RadarObject > RadarObjectPtr;
98 typedef std::shared_ptr< ::sick_scan_xd::RadarObject const> RadarObjectConstPtr;
99 
100 // constants requiring out of line definition
101 
102 
103 
104 template<typename ContainerAllocator>
105 std::ostream& operator<<(std::ostream& s, const ::sick_scan_xd::RadarObject_<ContainerAllocator> & v)
106 {
108 return s;
109 }
110 
111 
112 template<typename ContainerAllocator1, typename ContainerAllocator2>
113 bool operator==(const ::sick_scan_xd::RadarObject_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarObject_<ContainerAllocator2> & rhs)
114 {
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;
124 }
125 
126 template<typename ContainerAllocator1, typename ContainerAllocator2>
127 bool operator!=(const ::sick_scan_xd::RadarObject_<ContainerAllocator1> & lhs, const ::sick_scan_xd::RadarObject_<ContainerAllocator2> & rhs)
128 {
129  return !(lhs == rhs);
130 }
131 
132 
133 } // namespace sick_scan_xd
134 
135 namespace roswrap
136 {
137 namespace message_traits
138 {
139 
140 
141 
142 
143 
144 template <class ContainerAllocator>
145 struct IsFixedSize< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
146  : FalseType
147  { };
148 
149 template <class ContainerAllocator>
150 struct IsFixedSize< ::sick_scan_xd::RadarObject_<ContainerAllocator> const>
151  : FalseType
152  { };
153 
154 template <class ContainerAllocator>
155 struct IsMessage< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
156  : TrueType
157  { };
158 
159 template <class ContainerAllocator>
160 struct IsMessage< ::sick_scan_xd::RadarObject_<ContainerAllocator> const>
161  : TrueType
162  { };
163 
164 template <class ContainerAllocator>
165 struct HasHeader< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
166  : FalseType
167  { };
168 
169 template <class ContainerAllocator>
170 struct HasHeader< ::sick_scan_xd::RadarObject_<ContainerAllocator> const>
171  : FalseType
172  { };
173 
174 
175 template<class ContainerAllocator>
176 struct MD5Sum< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
177 {
178  static const char* value()
179  {
180  return "a5d0f2d250163ffa0098d0fc8218fc4a";
181  }
182 
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;
186 };
187 
188 template<class ContainerAllocator>
189 struct DataType< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
190 {
191  static const char* value()
192  {
193  return "sick_scan/RadarObject";
194  }
195 
196  static const char* value(const ::sick_scan_xd::RadarObject_<ContainerAllocator>&) { return value(); }
197 };
198 
199 template<class ContainerAllocator>
200 struct Definition< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
201 {
202  static const char* value()
203  {
204  return "int32 id\n"
205 "\n"
206 "# ROS-1:\n"
207 "time tracking_time # since when the object is tracked\n"
208 "time last_seen\n"
209 "\n"
210 "# ROS-2:\n"
211 "#builtin_interfaces/Time tracking_time # since when the object is tracked\n"
212 "#builtin_interfaces/Time last_seen\n"
213 "\n"
214 "geometry_msgs/TwistWithCovariance velocity\n"
215 "\n"
216 "geometry_msgs/Pose bounding_box_center\n"
217 "geometry_msgs/Vector3 bounding_box_size\n"
218 "\n"
219 "geometry_msgs/PoseWithCovariance object_box_center\n"
220 "geometry_msgs/Vector3 object_box_size\n"
221 "\n"
222 "geometry_msgs/Point[] contour_points\n"
223 "\n"
224 "================================================================================\n"
225 "MSG: geometry_msgs/TwistWithCovariance\n"
226 "# This expresses velocity in free space with uncertainty.\n"
227 "\n"
228 "Twist twist\n"
229 "\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"
235 "\n"
236 "================================================================================\n"
237 "MSG: geometry_msgs/Twist\n"
238 "# This expresses velocity in free space broken into its linear and angular parts.\n"
239 "Vector3 linear\n"
240 "Vector3 angular\n"
241 "\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"
250 "\n"
251 "float64 x\n"
252 "float64 y\n"
253 "float64 z\n"
254 "================================================================================\n"
255 "MSG: geometry_msgs/Pose\n"
256 "# A representation of pose in free space, composed of position and orientation. \n"
257 "Point position\n"
258 "Quaternion orientation\n"
259 "\n"
260 "================================================================================\n"
261 "MSG: geometry_msgs/Point\n"
262 "# This contains the position of a point in free space\n"
263 "float64 x\n"
264 "float64 y\n"
265 "float64 z\n"
266 "\n"
267 "================================================================================\n"
268 "MSG: geometry_msgs/Quaternion\n"
269 "# This represents an orientation in free space in quaternion form.\n"
270 "\n"
271 "float64 x\n"
272 "float64 y\n"
273 "float64 z\n"
274 "float64 w\n"
275 "\n"
276 "================================================================================\n"
277 "MSG: geometry_msgs/PoseWithCovariance\n"
278 "# This represents a pose in free space with uncertainty.\n"
279 "\n"
280 "Pose pose\n"
281 "\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"
287 ;
288  }
289 
290  static const char* value(const ::sick_scan_xd::RadarObject_<ContainerAllocator>&) { return value(); }
291 };
292 
293 } // namespace message_traits
294 } // namespace roswrap
295 
296 namespace roswrap
297 {
298 namespace serialization
299 {
300 
301  template<class ContainerAllocator> struct Serializer< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
302  {
303  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
304  {
305  stream.next(m.id);
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);
314  }
315 
317  }; // struct RadarObject_
318 
319 } // namespace serialization
320 } // namespace roswrap
321 
322 namespace roswrap
323 {
324 namespace message_operations
325 {
326 
327 template<class ContainerAllocator>
328 struct Printer< ::sick_scan_xd::RadarObject_<ContainerAllocator> >
329 {
330  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sick_scan_xd::RadarObject_<ContainerAllocator>& v)
331  {
332  s << indent << "id: ";
333  Printer<int32_t>::stream(s, indent + " ", v.id);
334  s << indent << "tracking_time: ";
335  Printer<ros::Time>::stream(s, indent + " ", v.tracking_time);
336  s << indent << "last_seen: ";
337  Printer<ros::Time>::stream(s, indent + " ", v.last_seen);
338  s << indent << "velocity: ";
339  s << std::endl;
341  s << indent << "bounding_box_center: ";
342  s << std::endl;
344  s << indent << "bounding_box_size: ";
345  s << std::endl;
347  s << indent << "object_box_center: ";
348  s << std::endl;
350  s << indent << "object_box_size: ";
351  s << std::endl;
353  s << indent << "contour_points[]" << std::endl;
354  for (size_t i = 0; i < v.contour_points.size(); ++i)
355  {
356  s << indent << " contour_points[" << i << "]: ";
357  s << std::endl;
358  s << indent;
360  }
361  }
362 };
363 
364 } // namespace message_operations
365 } // namespace roswrap
366 
367 #endif // SICK_SCAN_MESSAGE_RADAROBJECT_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
roswrap::message_traits::Definition< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::RadarObject_< ContainerAllocator > &)
Definition: RadarObject.h:290
sick_scan_xd::RadarObject_::id
_id_type id
Definition: RadarObject.h:60
Point.h
multiscan_pcap_player.indent
indent
Definition: multiscan_pcap_player.py:252
geometry_msgs::TwistWithCovariance_
Definition: TwistWithCovariance.h:24
roswrap::serialization::Serializer< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: RadarObject.h:303
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
sick_scan_xd::RadarObjectPtr
std::shared_ptr< ::sick_scan_xd::RadarObject > RadarObjectPtr
Definition: RadarObject.h:97
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
s
XmlRpcServer s
sick_scan_xd::RadarObject_::_tracking_time_type
ros::Time _tracking_time_type
Definition: RadarObject.h:62
sick_scan_xd::RadarObject_::_id_type
int32_t _id_type
Definition: RadarObject.h:59
Pose.h
sick_scan_xd::RadarObject_
Definition: RadarObject.h:29
sick_scan_xd::RadarObject_::_object_box_size_type
::geometry_msgs::Vector3_< ContainerAllocator > _object_box_size_type
Definition: RadarObject.h:80
sick_scan_xd::RadarObject_::_object_box_center_type
::geometry_msgs::PoseWithCovariance_< ContainerAllocator > _object_box_center_type
Definition: RadarObject.h:77
sick_scan_xd::RadarObject_::bounding_box_size
_bounding_box_size_type bounding_box_size
Definition: RadarObject.h:75
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
sick_scan_xd::RadarObject_::Ptr
std::shared_ptr< ::sick_scan_xd::RadarObject_< ContainerAllocator > > Ptr
Definition: RadarObject.h:90
geometry_msgs::Vector3_
Definition: kinetic/include/geometry_msgs/Vector3.h:23
sick_scan_xd::RadarObject_::Type
RadarObject_< ContainerAllocator > Type
Definition: RadarObject.h:31
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
Definition: abstract_parser.cpp:65
sick_scan_xd::RadarObject_::velocity
_velocity_type velocity
Definition: RadarObject.h:69
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
roswrap::message_traits::DataType< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::RadarObject_< ContainerAllocator > &)
Definition: RadarObject.h:196
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
geometry_msgs::Pose_
Definition: Pose.h:25
sick_scan_xd::RadarObject_::last_seen
_last_seen_type last_seen
Definition: RadarObject.h:66
sick_scan_xd::RadarObject
::sick_scan_xd::RadarObject_< std::allocator< void > > RadarObject
Definition: RadarObject.h:95
sick_scan_xd::RadarObject_::_bounding_box_center_type
::geometry_msgs::Pose_< ContainerAllocator > _bounding_box_center_type
Definition: RadarObject.h:71
sick_scan_xd::RadarObject_::_last_seen_type
ros::Time _last_seen_type
Definition: RadarObject.h:65
sick_scan_xd::RadarObject_::object_box_size
_object_box_size_type object_box_size
Definition: RadarObject.h:81
roswrap
Definition: param_modi.cpp:41
sick_scan_xd::RadarObject_::RadarObject_
RadarObject_()
Definition: RadarObject.h:33
roswrap::message_operations::Printer
Definition: message_operations.h:40
geometry_msgs::PoseWithCovariance_
Definition: PoseWithCovariance.h:25
sick_scan_xd::RadarObject_::_contour_points_type
std::vector< ::geometry_msgs::Point_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::geometry_msgs::Point_< ContainerAllocator > >::other > _contour_points_type
Definition: RadarObject.h:83
roswrap::message_traits::MD5Sum< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::value
static const char * value()
Definition: RadarObject.h:178
PoseWithCovariance.h
Vector3.h
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
roswrap::message_traits::Definition< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::value
static const char * value()
Definition: RadarObject.h:202
sick_scan_xd::RadarObject_::_bounding_box_size_type
::geometry_msgs::Vector3_< ContainerAllocator > _bounding_box_size_type
Definition: RadarObject.h:74
sick_scan_xd::RadarObject_::_velocity_type
::geometry_msgs::TwistWithCovariance_< ContainerAllocator > _velocity_type
Definition: RadarObject.h:68
sick_scan_xd::RadarObject_::ConstPtr
std::shared_ptr< ::sick_scan_xd::RadarObject_< ContainerAllocator > const > ConstPtr
Definition: RadarObject.h:91
sick_scan_xd::RadarObject_::tracking_time
_tracking_time_type tracking_time
Definition: RadarObject.h:63
roswrap::message_operations::Printer< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sick_scan_xd::RadarObject_< ContainerAllocator > &v)
Definition: RadarObject.h:330
ros::Time
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::RadarObject_::contour_points
_contour_points_type contour_points
Definition: RadarObject.h:84
roswrap::message_traits::MD5Sum< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::RadarObject_< ContainerAllocator > &)
Definition: RadarObject.h:183
roswrap::message_traits::DataType< ::sick_scan_xd::RadarObject_< ContainerAllocator > >::value
static const char * value()
Definition: RadarObject.h:191
sick_scan_xd::RadarObject_::object_box_center
_object_box_center_type object_box_center
Definition: RadarObject.h:78
TwistWithCovariance.h
sick_scan_xd::RadarObjectConstPtr
std::shared_ptr< ::sick_scan_xd::RadarObject const > RadarObjectConstPtr
Definition: RadarObject.h:98
sick_scan_xd::RadarObject_::bounding_box_center
_bounding_box_center_type bounding_box_center
Definition: RadarObject.h:72
sick_scan_xd::RadarObject_::RadarObject_
RadarObject_(const ContainerAllocator &_alloc)
Definition: RadarObject.h:44


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