MultiEchoLaserScan.h
Go to the documentation of this file.
1 // Generated by gencpp from file sensor_msgs/MultiEchoLaserScan.msg
2 // DO NOT EDIT!
3 
4 
5 #ifndef SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H
6 #define SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H
7 
8 
9 #include <string>
10 #include <vector>
11 #include <map>
12 
13 #include <ros/types.h>
14 #include <ros/serialization.h>
16 #include <ros/message_operations.h>
17 
18 #include <std_msgs/Header.h>
19 #include <sensor_msgs/LaserEcho.h>
20 #include <sensor_msgs/LaserEcho.h>
21 
22 namespace sensor_msgs
23 {
24 template <class ContainerAllocator>
26 {
28 
30  : header()
31  , angle_min(0.0)
32  , angle_max(0.0)
33  , angle_increment(0.0)
34  , time_increment(0.0)
35  , scan_time(0.0)
36  , range_min(0.0)
37  , range_max(0.0)
38  , ranges()
39  , intensities() {
40  }
41  MultiEchoLaserScan_(const ContainerAllocator& _alloc)
42  : header(_alloc)
43  , angle_min(0.0)
44  , angle_max(0.0)
45  , angle_increment(0.0)
46  , time_increment(0.0)
47  , scan_time(0.0)
48  , range_min(0.0)
49  , range_max(0.0)
50  , ranges(_alloc)
51  , intensities(_alloc) {
52  (void)_alloc;
53  }
54 
55 
56 
57  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
58  _header_type header;
59 
60  typedef float _angle_min_type;
61  _angle_min_type angle_min;
62 
63  typedef float _angle_max_type;
64  _angle_max_type angle_max;
65 
66  typedef float _angle_increment_type;
67  _angle_increment_type angle_increment;
68 
69  typedef float _time_increment_type;
70  _time_increment_type time_increment;
71 
72  typedef float _scan_time_type;
73  _scan_time_type scan_time;
74 
75  typedef float _range_min_type;
76  _range_min_type range_min;
77 
78  typedef float _range_max_type;
79  _range_max_type range_max;
80 
81  typedef std::vector< ::sensor_msgs::LaserEcho_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_<ContainerAllocator> >::other > _ranges_type;
82  _ranges_type ranges;
83 
84  typedef std::vector< ::sensor_msgs::LaserEcho_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_<ContainerAllocator> >::other > _intensities_type;
85  _intensities_type intensities;
86 
87 
88 
89 
92 
93 }; // struct MultiEchoLaserScan_
94 
95 typedef ::sensor_msgs::MultiEchoLaserScan_<std::allocator<void> > MultiEchoLaserScan;
96 
99 
100 // constants requiring out of line definition
101 
102 
103 
104 template<typename ContainerAllocator>
105 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> & v)
106 {
108 return s;
109 }
110 
111 } // namespace sensor_msgs
112 
113 namespace rs2rosinternal
114 {
115 namespace message_traits
116 {
117 
118 
119 
120 // BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True}
121 // {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']}
122 
123 // !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types']
124 
125 
126 
127 
128 template <class ContainerAllocator>
129 struct IsFixedSize< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
130  : FalseType
131  { };
132 
133 template <class ContainerAllocator>
134 struct IsFixedSize< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> const>
135  : FalseType
136  { };
137 
138 template <class ContainerAllocator>
139 struct IsMessage< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
140  : TrueType
141  { };
142 
143 template <class ContainerAllocator>
144 struct IsMessage< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> const>
145  : TrueType
146  { };
147 
148 template <class ContainerAllocator>
149 struct HasHeader< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
150  : TrueType
151  { };
152 
153 template <class ContainerAllocator>
154 struct HasHeader< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> const>
155  : TrueType
156  { };
157 
158 
159 template<class ContainerAllocator>
160 struct MD5Sum< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
161 {
162  static const char* value()
163  {
164  return "6fefb0c6da89d7c8abe4b339f5c2f8fb";
165  }
166 
167  static const char* value(const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>&) { return value(); }
168  static const uint64_t static_value1 = 0x6fefb0c6da89d7c8ULL;
169  static const uint64_t static_value2 = 0xabe4b339f5c2f8fbULL;
170 };
171 
172 template<class ContainerAllocator>
173 struct DataType< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
174 {
175  static const char* value()
176  {
177  return "sensor_msgs/MultiEchoLaserScan";
178  }
179 
180  static const char* value(const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>&) { return value(); }
181 };
182 
183 template<class ContainerAllocator>
184 struct Definition< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
185 {
186  static const char* value()
187  {
188  return "# Single scan from a multi-echo planar laser range-finder\n\
189 #\n\
190 # If you have another ranging device with different behavior (e.g. a sonar\n\
191 # array), please find or create a different message, since applications\n\
192 # will make fairly laser-specific assumptions about this data\n\
193 \n\
194 Header header # timestamp in the header is the acquisition time of \n\
195  # the first ray in the scan.\n\
196  #\n\
197  # in frame frame_id, angles are measured around \n\
198  # the positive Z axis (counterclockwise, if Z is up)\n\
199  # with zero angle being forward along the x axis\n\
200  \n\
201 float32 angle_min # start angle of the scan [rad]\n\
202 float32 angle_max # end angle of the scan [rad]\n\
203 float32 angle_increment # angular distance between measurements [rad]\n\
204 \n\
205 float32 time_increment # time between measurements [seconds] - if your scanner\n\
206  # is moving, this will be used in interpolating position\n\
207  # of 3d points\n\
208 float32 scan_time # time between scans [seconds]\n\
209 \n\
210 float32 range_min # minimum range value [m]\n\
211 float32 range_max # maximum range value [m]\n\
212 \n\
213 LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)\n\
214  # +Inf measurements are out of range\n\
215  # -Inf measurements are too close to determine exact distance.\n\
216 LaserEcho[] intensities # intensity data [device-specific units]. If your\n\
217  # device does not provide intensities, please leave\n\
218  # the array empty.\n\
219 ================================================================================\n\
220 MSG: std_msgs/Header\n\
221 # Standard metadata for higher-level stamped data types.\n\
222 # This is generally used to communicate timestamped data \n\
223 # in a particular coordinate frame.\n\
224 # \n\
225 # sequence ID: consecutively increasing ID \n\
226 uint32 seq\n\
227 #Two-integer timestamp that is expressed as:\n\
228 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
229 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
230 # time-handling sugar is provided by the client library\n\
231 time stamp\n\
232 #Frame this data is associated with\n\
233 # 0: no frame\n\
234 # 1: global frame\n\
235 string frame_id\n\
236 \n\
237 ================================================================================\n\
238 MSG: sensor_msgs/LaserEcho\n\
239 # This message is a submessage of MultiEchoLaserScan and is not intended\n\
240 # to be used separately.\n\
241 \n\
242 float32[] echoes # Multiple values of ranges or intensities.\n\
243  # Each array represents data from the same angle increment.\n\
244 ";
245  }
246 
247  static const char* value(const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>&) { return value(); }
248 };
249 
250 } // namespace message_traits
251 } // namespace rs2rosinternal
252 
253 namespace rs2rosinternal
254 {
255 namespace serialization
256 {
257 
258  template<class ContainerAllocator> struct Serializer< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
259  {
260  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
261  {
262  stream.next(m.header);
263  stream.next(m.angle_min);
264  stream.next(m.angle_max);
265  stream.next(m.angle_increment);
266  stream.next(m.time_increment);
267  stream.next(m.scan_time);
268  stream.next(m.range_min);
269  stream.next(m.range_max);
270  stream.next(m.ranges);
271  stream.next(m.intensities);
272  }
273 
275  }; // struct MultiEchoLaserScan_
276 
277 } // namespace serialization
278 } // namespace rs2rosinternal
279 
280 namespace rs2rosinternal
281 {
282 namespace message_operations
283 {
284 
285 template<class ContainerAllocator>
286 struct Printer< ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> >
287 {
288  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>& v)
289  {
290  s << indent << "header: ";
291  s << std::endl;
293  s << indent << "angle_min: ";
294  Printer<float>::stream(s, indent + " ", v.angle_min);
295  s << indent << "angle_max: ";
296  Printer<float>::stream(s, indent + " ", v.angle_max);
297  s << indent << "angle_increment: ";
298  Printer<float>::stream(s, indent + " ", v.angle_increment);
299  s << indent << "time_increment: ";
300  Printer<float>::stream(s, indent + " ", v.time_increment);
301  s << indent << "scan_time: ";
302  Printer<float>::stream(s, indent + " ", v.scan_time);
303  s << indent << "range_min: ";
304  Printer<float>::stream(s, indent + " ", v.range_min);
305  s << indent << "range_max: ";
306  Printer<float>::stream(s, indent + " ", v.range_max);
307  s << indent << "ranges[]" << std::endl;
308  for (size_t i = 0; i < v.ranges.size(); ++i)
309  {
310  s << indent << " ranges[" << i << "]: ";
311  s << std::endl;
312  s << indent;
314  }
315  s << indent << "intensities[]" << std::endl;
316  for (size_t i = 0; i < v.intensities.size(); ++i)
317  {
318  s << indent << " intensities[" << i << "]: ";
319  s << std::endl;
320  s << indent;
321  Printer< ::sensor_msgs::LaserEcho_<ContainerAllocator> >::stream(s, indent + " ", v.intensities[i]);
322  }
323  }
324 };
325 
326 } // namespace message_operations
327 } // namespace rs2rosinternal
328 
329 #endif // SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static const char * value(const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > &)
GLdouble s
const GLfloat * m
Definition: glext.h:6814
std::vector< ::sensor_msgs::LaserEcho_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_< ContainerAllocator > >::other > _intensities_type
Specialize to provide the md5sum for a message.
::std_msgs::Header_< ContainerAllocator > _header_type
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
GLsizei const GLchar *const * string
Specialize to provide the datatype for a message.
HasHeader informs whether or not there is a header that gets serialized as the first thing in the mes...
GLuint GLuint stream
Definition: glext.h:1790
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
static const char * value(const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > &)
Stream base-class, provides common functionality for IStream and OStream.
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > &v)
::sensor_msgs::MultiEchoLaserScan_< std::allocator< void > > MultiEchoLaserScan
static const char * value(const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > &)
MultiEchoLaserScan_< ContainerAllocator > Type
Tools for manipulating sensor_msgs.
Definition: BatteryState.h:20
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > const > ConstPtr
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
Definition: stdint.h:90
Specialize to provide the definition for a message.
_angle_increment_type angle_increment
std::vector< ::sensor_msgs::LaserEcho_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_< ContainerAllocator > >::other > _ranges_type
MultiEchoLaserScan_(const ContainerAllocator &_alloc)
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > > Ptr
int i
Templated serialization class. Default implementation provides backwards compatibility with old messa...
GLdouble v
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan const > MultiEchoLaserScanConstPtr
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan > MultiEchoLaserScanPtr


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:47:22