SickLdmrsObjectArray.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/SickLdmrsObjectArray.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SICK_SCAN_MESSAGE_SICKLDMRSOBJECTARRAY_H
7 #define SICK_SCAN_MESSAGE_SICKLDMRSOBJECTARRAY_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>
21 
22 namespace sick_scan_xd
23 {
24 template <class ContainerAllocator>
26 {
28 
30  : header()
31  , objects() {
32  }
33  SickLdmrsObjectArray_(const ContainerAllocator& _alloc)
34  : header(_alloc)
35  , objects(_alloc) {
36  (void)_alloc;
37  }
38 
39 
40 
41  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
43 
44  typedef std::vector< ::sick_scan_xd::SickLdmrsObject_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sick_scan_xd::SickLdmrsObject_<ContainerAllocator> >::other > _objects_type;
46 
47 
48 
49 
50 
51  typedef std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> > Ptr;
52  typedef std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> const> ConstPtr;
53 
54 }; // struct SickLdmrsObjectArray_
55 
56 typedef ::sick_scan_xd::SickLdmrsObjectArray_<std::allocator<void> > SickLdmrsObjectArray;
57 
58 typedef std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray > SickLdmrsObjectArrayPtr;
59 typedef std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray const> SickLdmrsObjectArrayConstPtr;
60 
61 // constants requiring out of line definition
62 
63 
64 
65 template<typename ContainerAllocator>
66 std::ostream& operator<<(std::ostream& s, const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> & v)
67 {
69 return s;
70 }
71 
72 
73 template<typename ContainerAllocator1, typename ContainerAllocator2>
74 bool operator==(const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator1> & lhs, const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator2> & rhs)
75 {
76  return lhs.header == rhs.header &&
77  lhs.objects == rhs.objects;
78 }
79 
80 template<typename ContainerAllocator1, typename ContainerAllocator2>
81 bool operator!=(const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator1> & lhs, const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator2> & rhs)
82 {
83  return !(lhs == rhs);
84 }
85 
86 
87 } // namespace sick_scan_xd
88 
89 namespace roswrap
90 {
91 namespace message_traits
92 {
93 
94 
95 
96 
97 
98 template <class ContainerAllocator>
99 struct IsFixedSize< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
100  : FalseType
101  { };
102 
103 template <class ContainerAllocator>
105  : FalseType
106  { };
107 
108 template <class ContainerAllocator>
109 struct IsMessage< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
110  : TrueType
111  { };
112 
113 template <class ContainerAllocator>
115  : TrueType
116  { };
117 
118 template <class ContainerAllocator>
119 struct HasHeader< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
120  : TrueType
121  { };
122 
123 template <class ContainerAllocator>
125  : TrueType
126  { };
127 
128 
129 template<class ContainerAllocator>
130 struct MD5Sum< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
131 {
132  static const char* value()
133  {
134  return "09128101facd48306fd0cf85eaf2be8f";
135  }
136 
137  static const char* value(const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator>&) { return value(); }
138  static const uint64_t static_value1 = 0x09128101facd4830ULL;
139  static const uint64_t static_value2 = 0x6fd0cf85eaf2be8fULL;
140 };
141 
142 template<class ContainerAllocator>
143 struct DataType< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
144 {
145  static const char* value()
146  {
147  return "sick_scan/SickLdmrsObjectArray";
148  }
149 
150  static const char* value(const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator>&) { return value(); }
151 };
152 
153 template<class ContainerAllocator>
154 struct Definition< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
155 {
156  static const char* value()
157  {
158  return "# ROS-1: \n"
159 "Header header\n"
160 "# ROS-2: \n"
161 "# std_msgs/Header header\n"
162 "SickLdmrsObject[] objects\n"
163 "\n"
164 "================================================================================\n"
165 "MSG: std_msgs/Header\n"
166 "# Standard metadata for higher-level stamped data types.\n"
167 "# This is generally used to communicate timestamped data \n"
168 "# in a particular coordinate frame.\n"
169 "# \n"
170 "# sequence ID: consecutively increasing ID \n"
171 "uint32 seq\n"
172 "#Two-integer timestamp that is expressed as:\n"
173 "# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n"
174 "# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n"
175 "# time-handling sugar is provided by the client library\n"
176 "time stamp\n"
177 "#Frame this data is associated with\n"
178 "string frame_id\n"
179 "\n"
180 "================================================================================\n"
181 "MSG: sick_scan/SickLdmrsObject\n"
182 "int32 id\n"
183 "\n"
184 "# ROS-1:\n"
185 "time tracking_time # since when the object is tracked\n"
186 "time last_seen\n"
187 "\n"
188 "# ROS-2:\n"
189 "#builtin_interfaces/Time tracking_time # since when the object is tracked\n"
190 "#builtin_interfaces/Time last_seen\n"
191 "\n"
192 "geometry_msgs/TwistWithCovariance velocity\n"
193 "\n"
194 "geometry_msgs/Pose bounding_box_center\n"
195 "geometry_msgs/Vector3 bounding_box_size\n"
196 "\n"
197 "geometry_msgs/PoseWithCovariance object_box_center\n"
198 "geometry_msgs/Vector3 object_box_size\n"
199 "\n"
200 "geometry_msgs/Point[] contour_points\n"
201 "\n"
202 "================================================================================\n"
203 "MSG: geometry_msgs/TwistWithCovariance\n"
204 "# This expresses velocity in free space with uncertainty.\n"
205 "\n"
206 "Twist twist\n"
207 "\n"
208 "# Row-major representation of the 6x6 covariance matrix\n"
209 "# The orientation parameters use a fixed-axis representation.\n"
210 "# In order, the parameters are:\n"
211 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
212 "float64[36] covariance\n"
213 "\n"
214 "================================================================================\n"
215 "MSG: geometry_msgs/Twist\n"
216 "# This expresses velocity in free space broken into its linear and angular parts.\n"
217 "Vector3 linear\n"
218 "Vector3 angular\n"
219 "\n"
220 "================================================================================\n"
221 "MSG: geometry_msgs/Vector3\n"
222 "# This represents a vector in free space. \n"
223 "# It is only meant to represent a direction. Therefore, it does not\n"
224 "# make sense to apply a translation to it (e.g., when applying a \n"
225 "# generic rigid transformation to a Vector3, tf2 will only apply the\n"
226 "# rotation). If you want your data to be translatable too, use the\n"
227 "# geometry_msgs/Point message instead.\n"
228 "\n"
229 "float64 x\n"
230 "float64 y\n"
231 "float64 z\n"
232 "================================================================================\n"
233 "MSG: geometry_msgs/Pose\n"
234 "# A representation of pose in free space, composed of position and orientation. \n"
235 "Point position\n"
236 "Quaternion orientation\n"
237 "\n"
238 "================================================================================\n"
239 "MSG: geometry_msgs/Point\n"
240 "# This contains the position of a point in free space\n"
241 "float64 x\n"
242 "float64 y\n"
243 "float64 z\n"
244 "\n"
245 "================================================================================\n"
246 "MSG: geometry_msgs/Quaternion\n"
247 "# This represents an orientation in free space in quaternion form.\n"
248 "\n"
249 "float64 x\n"
250 "float64 y\n"
251 "float64 z\n"
252 "float64 w\n"
253 "\n"
254 "================================================================================\n"
255 "MSG: geometry_msgs/PoseWithCovariance\n"
256 "# This represents a pose in free space with uncertainty.\n"
257 "\n"
258 "Pose pose\n"
259 "\n"
260 "# Row-major representation of the 6x6 covariance matrix\n"
261 "# The orientation parameters use a fixed-axis representation.\n"
262 "# In order, the parameters are:\n"
263 "# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n"
264 "float64[36] covariance\n"
265 ;
266  }
267 
268  static const char* value(const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator>&) { return value(); }
269 };
270 
271 } // namespace message_traits
272 } // namespace roswrap
273 
274 namespace roswrap
275 {
276 namespace serialization
277 {
278 
279  template<class ContainerAllocator> struct Serializer< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
280  {
281  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
282  {
283  stream.next(m.header);
284  stream.next(m.objects);
285  }
286 
288  }; // struct SickLdmrsObjectArray_
289 
290 } // namespace serialization
291 } // namespace roswrap
292 
293 namespace roswrap
294 {
295 namespace message_operations
296 {
297 
298 template<class ContainerAllocator>
299 struct Printer< ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator> >
300 {
301  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sick_scan_xd::SickLdmrsObjectArray_<ContainerAllocator>& v)
302  {
303  s << indent << "header: ";
304  s << std::endl;
306  s << indent << "objects[]" << std::endl;
307  for (size_t i = 0; i < v.objects.size(); ++i)
308  {
309  s << indent << " objects[" << i << "]: ";
310  s << std::endl;
311  s << indent;
313  }
314  }
315 };
316 
317 } // namespace message_operations
318 } // namespace roswrap
319 
320 #endif // SICK_SCAN_MESSAGE_SICKLDMRSOBJECTARRAY_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::SickLdmrsObjectArrayConstPtr
std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray const > SickLdmrsObjectArrayConstPtr
Definition: SickLdmrsObjectArray.h:59
roswrap::message_operations::Printer< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > &v)
Definition: SickLdmrsObjectArray.h:301
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
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
s
XmlRpcServer s
sick_scan_xd::SickLdmrsObjectArray_::_objects_type
std::vector< ::sick_scan_xd::SickLdmrsObject_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sick_scan_xd::SickLdmrsObject_< ContainerAllocator > >::other > _objects_type
Definition: SickLdmrsObjectArray.h:44
sick_scan_xd::SickLdmrsObjectArray_::SickLdmrsObjectArray_
SickLdmrsObjectArray_(const ContainerAllocator &_alloc)
Definition: SickLdmrsObjectArray.h:33
sick_scan_xd::SickLdmrsObjectArray_::Type
SickLdmrsObjectArray_< ContainerAllocator > Type
Definition: SickLdmrsObjectArray.h:27
roswrap::serialization::Serializer< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: SickLdmrsObjectArray.h:281
roswrap::message_operations::Printer::stream
static void stream(Stream &s, const std::string &indent, const M &value)
Definition: message_operations.h:43
sick_scan_xd::SickLdmrsObjectArrayPtr
std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray > SickLdmrsObjectArrayPtr
Definition: SickLdmrsObjectArray.h:58
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::SickLdmrsObjectArray_::header
_header_type header
Definition: SickLdmrsObjectArray.h:42
roswrap::message_traits::DataType< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > &)
Definition: SickLdmrsObjectArray.h:150
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::SickLdmrsObjectArray
::sick_scan_xd::SickLdmrsObjectArray_< std::allocator< void > > SickLdmrsObjectArray
Definition: SickLdmrsObjectArray.h:56
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
sick_scan_xd::SickLdmrsObjectArray_
Definition: SickLdmrsObjectArray.h:25
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
SickLdmrsObject.h
roswrap::message_traits::Definition< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > &)
Definition: SickLdmrsObjectArray.h:268
sick_scan_xd::SickLdmrsObjectArray_::ConstPtr
std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > const > ConstPtr
Definition: SickLdmrsObjectArray.h:52
roswrap::message_traits::DataType< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::value
static const char * value()
Definition: SickLdmrsObjectArray.h:145
roswrap
Definition: param_modi.cpp:41
roswrap::message_operations::Printer
Definition: message_operations.h:40
std_msgs::Header_
Definition: Header.h:23
sick_scan_xd::SickLdmrsObjectArray_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: SickLdmrsObjectArray.h:41
roswrap::message_traits::MD5Sum< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::value
static const char * value(const ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > &)
Definition: SickLdmrsObjectArray.h:137
sick_scan_xd::SickLdmrsObjectArray_::objects
_objects_type objects
Definition: SickLdmrsObjectArray.h:45
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
sick_scan_xd::SickLdmrsObjectArray_::Ptr
std::shared_ptr< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > > Ptr
Definition: SickLdmrsObjectArray.h:51
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
Header.h
roswrap::message_traits::MD5Sum< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::value
static const char * value()
Definition: SickLdmrsObjectArray.h:132
sick_scan_xd::SickLdmrsObjectArray_::SickLdmrsObjectArray_
SickLdmrsObjectArray_()
Definition: SickLdmrsObjectArray.h:29
roswrap::message_traits::Definition< ::sick_scan_xd::SickLdmrsObjectArray_< ContainerAllocator > >::value
static const char * value()
Definition: SickLdmrsObjectArray.h:156


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