LaserScan.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 sensor_msgs/LaserScan.msg
3 // DO NOT EDIT!
4 
5 
6 #ifndef SENSOR_MSGS_MESSAGE_LASERSCAN_H
7 #define SENSOR_MSGS_MESSAGE_LASERSCAN_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>
20 
21 namespace sensor_msgs
22 {
23 template <class ContainerAllocator>
24 struct LaserScan_
25 {
27 
29  : header()
30  , angle_min(0.0)
31  , angle_max(0.0)
32  , angle_increment(0.0)
33  , time_increment(0.0)
34  , scan_time(0.0)
35  , range_min(0.0)
36  , range_max(0.0)
37  , ranges()
38  , intensities() {
39  }
40  LaserScan_(const ContainerAllocator& _alloc)
41  : header(_alloc)
42  , angle_min(0.0)
43  , angle_max(0.0)
44  , angle_increment(0.0)
45  , time_increment(0.0)
46  , scan_time(0.0)
47  , range_min(0.0)
48  , range_max(0.0)
49  , ranges(_alloc)
50  , intensities(_alloc) {
51  (void)_alloc;
52  }
53 
54 
55 
56  typedef ::std_msgs::Header_<ContainerAllocator> _header_type;
58 
59  typedef float _angle_min_type;
61 
62  typedef float _angle_max_type;
64 
65  typedef float _angle_increment_type;
67 
68  typedef float _time_increment_type;
70 
71  typedef float _scan_time_type;
73 
74  typedef float _range_min_type;
76 
77  typedef float _range_max_type;
79 
80  typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _ranges_type;
82 
83  typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other > _intensities_type;
85 
86 
87 
88 
89  typedef std::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> > Ptr;
90  typedef std::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> const> ConstPtr;
91 
92 }; // struct LaserScan_
93 
94 typedef ::sensor_msgs::LaserScan_<std::allocator<void> > LaserScan;
95 
96 typedef std::shared_ptr< ::sensor_msgs::LaserScan > LaserScanPtr;
97 typedef std::shared_ptr< ::sensor_msgs::LaserScan const> LaserScanConstPtr;
98 
99 // constants requiring out of line definition
100 
101 
102 
103 template<typename ContainerAllocator>
104 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::LaserScan_<ContainerAllocator> & v)
105 {
107 return s;
108 }
109 
110 } // namespace sensor_msgs
111 
112 namespace roswrap
113 {
114 namespace message_traits
115 {
116 
117 
118 
119 // BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True}
120 // {'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']}
121 
122 // !!!!!!!!!!! ['__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']
123 
124 
125 
126 
127 template <class ContainerAllocator>
128 struct IsFixedSize< ::sensor_msgs::LaserScan_<ContainerAllocator> >
129  : FalseType
130  { };
131 
132 template <class ContainerAllocator>
133 struct IsFixedSize< ::sensor_msgs::LaserScan_<ContainerAllocator> const>
134  : FalseType
135  { };
136 
137 template <class ContainerAllocator>
138 struct IsMessage< ::sensor_msgs::LaserScan_<ContainerAllocator> >
139  : TrueType
140  { };
141 
142 template <class ContainerAllocator>
143 struct IsMessage< ::sensor_msgs::LaserScan_<ContainerAllocator> const>
144  : TrueType
145  { };
146 
147 template <class ContainerAllocator>
148 struct HasHeader< ::sensor_msgs::LaserScan_<ContainerAllocator> >
149  : TrueType
150  { };
151 
152 template <class ContainerAllocator>
153 struct HasHeader< ::sensor_msgs::LaserScan_<ContainerAllocator> const>
154  : TrueType
155  { };
156 
157 
158 template<class ContainerAllocator>
159 struct MD5Sum< ::sensor_msgs::LaserScan_<ContainerAllocator> >
160 {
161  static const char* value()
162  {
163  return "90c7ef2dc6895d81024acba2ac42f369";
164  }
165 
166  static const char* value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) { return value(); }
167  static const uint64_t static_value1 = 0x90c7ef2dc6895d81ULL;
168  static const uint64_t static_value2 = 0x024acba2ac42f369ULL;
169 };
170 
171 template<class ContainerAllocator>
172 struct DataType< ::sensor_msgs::LaserScan_<ContainerAllocator> >
173 {
174  static const char* value()
175  {
176  return "sensor_msgs/LaserScan";
177  }
178 
179  static const char* value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) { return value(); }
180 };
181 
182 template<class ContainerAllocator>
183 struct Definition< ::sensor_msgs::LaserScan_<ContainerAllocator> >
184 {
185  static const char* value()
186  {
187  return "# Single scan from a planar laser range-finder\n\
188 #\n\
189 # If you have another ranging device with different behavior (e.g. a sonar\n\
190 # array), please find or create a different message, since applications\n\
191 # will make fairly laser-specific assumptions about this data\n\
192 \n\
193 Header header # timestamp in the header is the acquisition time of \n\
194  # the first ray in the scan.\n\
195  #\n\
196  # in frame frame_id, angles are measured around \n\
197  # the positive Z axis (counterclockwise, if Z is up)\n\
198  # with zero angle being forward along the x axis\n\
199  \n\
200 float32 angle_min # start angle of the scan [rad]\n\
201 float32 angle_max # end angle of the scan [rad]\n\
202 float32 angle_increment # angular distance between measurements [rad]\n\
203 \n\
204 float32 time_increment # time between measurements [seconds] - if your scanner\n\
205  # is moving, this will be used in interpolating position\n\
206  # of 3d points\n\
207 float32 scan_time # time between scans [seconds]\n\
208 \n\
209 float32 range_min # minimum range value [m]\n\
210 float32 range_max # maximum range value [m]\n\
211 \n\
212 float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n\
213 float32[] intensities # intensity data [device-specific units]. If your\n\
214  # device does not provide intensities, please leave\n\
215  # the array empty.\n\
216 \n\
217 ================================================================================\n\
218 MSG: std_msgs/Header\n\
219 # Standard metadata for higher-level stamped data types.\n\
220 # This is generally used to communicate timestamped data \n\
221 # in a particular coordinate frame.\n\
222 # \n\
223 # sequence ID: consecutively increasing ID \n\
224 uint32 seq\n\
225 #Two-integer timestamp that is expressed as:\n\
226 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\
227 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\
228 # time-handling sugar is provided by the client library\n\
229 time stamp\n\
230 #Frame this data is associated with\n\
231 # 0: no frame\n\
232 # 1: global frame\n\
233 string frame_id\n\
234 ";
235  }
236 
237  static const char* value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) { return value(); }
238 };
239 
240 } // namespace message_traits
241 } // namespace roswrap
242 
243 namespace roswrap
244 {
245 namespace serialization
246 {
247 
248  template<class ContainerAllocator> struct Serializer< ::sensor_msgs::LaserScan_<ContainerAllocator> >
249  {
250  template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
251  {
252  stream.next(m.header);
253  stream.next(m.angle_min);
254  stream.next(m.angle_max);
255  stream.next(m.angle_increment);
256  stream.next(m.time_increment);
257  stream.next(m.scan_time);
258  stream.next(m.range_min);
259  stream.next(m.range_max);
260  stream.next(m.ranges);
261  stream.next(m.intensities);
262  }
263 
265  }; // struct LaserScan_
266 
267 } // namespace serialization
268 } // namespace roswrap
269 
270 namespace roswrap
271 {
272 namespace message_operations
273 {
274 
275 template<class ContainerAllocator>
276 struct Printer< ::sensor_msgs::LaserScan_<ContainerAllocator> >
277 {
278  template<typename Stream> static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::LaserScan_<ContainerAllocator>& v)
279  {
280  s << indent << "header: ";
281  s << std::endl;
283  s << indent << "angle_min: ";
284  Printer<float>::stream(s, indent + " ", v.angle_min);
285  s << indent << "angle_max: ";
286  Printer<float>::stream(s, indent + " ", v.angle_max);
287  s << indent << "angle_increment: ";
288  Printer<float>::stream(s, indent + " ", v.angle_increment);
289  s << indent << "time_increment: ";
290  Printer<float>::stream(s, indent + " ", v.time_increment);
291  s << indent << "scan_time: ";
292  Printer<float>::stream(s, indent + " ", v.scan_time);
293  s << indent << "range_min: ";
294  Printer<float>::stream(s, indent + " ", v.range_min);
295  s << indent << "range_max: ";
296  Printer<float>::stream(s, indent + " ", v.range_max);
297  s << indent << "ranges[]" << std::endl;
298  for (size_t i = 0; i < v.ranges.size(); ++i)
299  {
300  s << indent << " ranges[" << i << "]: ";
301  Printer<float>::stream(s, indent + " ", v.ranges[i]);
302  }
303  s << indent << "intensities[]" << std::endl;
304  for (size_t i = 0; i < v.intensities.size(); ++i)
305  {
306  s << indent << " intensities[" << i << "]: ";
307  Printer<float>::stream(s, indent + " ", v.intensities[i]);
308  }
309  }
310 };
311 
312 } // namespace message_operations
313 } // namespace roswrap
314 
315 #endif // SENSOR_MSGS_MESSAGE_LASERSCAN_H
sensor_msgs::LaserScan_
Definition: LaserScan.h:24
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
roswrap::message_operations::Printer< ::sensor_msgs::LaserScan_< ContainerAllocator > >::stream
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::LaserScan_< ContainerAllocator > &v)
Definition: LaserScan.h:278
sensor_msgs::LaserScan_::Ptr
std::shared_ptr< ::sensor_msgs::LaserScan_< ContainerAllocator > > Ptr
Definition: LaserScan.h:89
multiscan_pcap_player.indent
indent
Definition: multiscan_pcap_player.py:252
roswrap::serialization::Serializer
Templated serialization class. Default implementation provides backwards compatibility with old messa...
Definition: serialization.h:120
sensor_msgs::LaserScan_::range_max
_range_max_type range_max
Definition: LaserScan.h:78
sensor_msgs::LaserScan_::ConstPtr
std::shared_ptr< ::sensor_msgs::LaserScan_< ContainerAllocator > const > ConstPtr
Definition: LaserScan.h:90
sensor_msgs::LaserScan_::_angle_max_type
float _angle_max_type
Definition: LaserScan.h:62
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
roswrap::message_traits::MD5Sum< ::sensor_msgs::LaserScan_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
Definition: LaserScan.h:166
sensor_msgs::LaserScan_::intensities
_intensities_type intensities
Definition: LaserScan.h:84
const
#define const
Definition: getopt.c:38
s
XmlRpcServer s
sensor_msgs::LaserScan_::Type
LaserScan_< ContainerAllocator > Type
Definition: LaserScan.h:26
sensor_msgs::LaserScan_::_time_increment_type
float _time_increment_type
Definition: LaserScan.h:68
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
roswrap::message_traits::DataType< ::sensor_msgs::LaserScan_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
Definition: LaserScan.h:179
roswrap::serialization::Serializer< ::sensor_msgs::LaserScan_< ContainerAllocator > >::allInOne
static void allInOne(Stream &stream, T m)
Definition: LaserScan.h:250
ros::message_operations::Printer
sensor_msgs::LaserScan_::_angle_increment_type
float _angle_increment_type
Definition: LaserScan.h:65
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
sensor_msgs::LaserScan_::angle_increment
_angle_increment_type angle_increment
Definition: LaserScan.h:66
roswrap::message_traits::DataType
Specialize to provide the datatype for a message.
Definition: message_traits.h:135
roswrap::message_traits::Definition
Specialize to provide the definition for a message.
Definition: message_traits.h:152
sensor_msgs::LaserScan
::sensor_msgs::LaserScan_< std::allocator< void > > LaserScan
Definition: LaserScan.h:94
sensor_msgs::operator<<
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
Definition: BatteryState.h:187
sensor_msgs::LaserScan_::angle_min
_angle_min_type angle_min
Definition: LaserScan.h:60
sensor_msgs::LaserScan_::_ranges_type
std::vector< float, typename ContainerAllocator::template rebind< float >::other > _ranges_type
Definition: LaserScan.h:80
sensor_msgs::LaserScan_::_angle_min_type
float _angle_min_type
Definition: LaserScan.h:59
roswrap::message_traits::MD5Sum< ::sensor_msgs::LaserScan_< ContainerAllocator > >::value
static const char * value()
Definition: LaserScan.h:161
roswrap
Definition: param_modi.cpp:41
roswrap::message_traits::DataType< ::sensor_msgs::LaserScan_< ContainerAllocator > >::value
static const char * value()
Definition: LaserScan.h:174
roswrap::message_operations::Printer
Definition: message_operations.h:40
std_msgs::Header_
Definition: Header.h:23
sensor_msgs::LaserScan_::LaserScan_
LaserScan_()
Definition: LaserScan.h:28
sensor_msgs::LaserScan_::LaserScan_
LaserScan_(const ContainerAllocator &_alloc)
Definition: LaserScan.h:40
sensor_msgs::LaserScan_::_intensities_type
std::vector< float, typename ContainerAllocator::template rebind< float >::other > _intensities_type
Definition: LaserScan.h:83
sensor_msgs::LaserScan_::_header_type
::std_msgs::Header_< ContainerAllocator > _header_type
Definition: LaserScan.h:56
sensor_msgs::LaserScanConstPtr
std::shared_ptr< ::sensor_msgs::LaserScan const > LaserScanConstPtr
Definition: LaserScan.h:97
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
sensor_msgs::LaserScan_::range_min
_range_min_type range_min
Definition: LaserScan.h:75
roswrap::message_traits::IsMessage
Am I message or not.
Definition: message_traits.h:112
sensor_msgs::LaserScan_::time_increment
_time_increment_type time_increment
Definition: LaserScan.h:69
roswrap::message_traits::Definition< ::sensor_msgs::LaserScan_< ContainerAllocator > >::value
static const char * value()
Definition: LaserScan.h:185
sick_scan_base.h
roswrap::serialization::Stream
Stream base-class, provides common functionality for IStream and OStream.
Definition: serialization.h:705
sensor_msgs::LaserScan_::header
_header_type header
Definition: LaserScan.h:57
sensor_msgs::LaserScan_::_range_max_type
float _range_max_type
Definition: LaserScan.h:77
sensor_msgs::LaserScan_::angle_max
_angle_max_type angle_max
Definition: LaserScan.h:63
sensor_msgs::LaserScanPtr
std::shared_ptr< ::sensor_msgs::LaserScan > LaserScanPtr
Definition: LaserScan.h:96
sensor_msgs::LaserScan_::_scan_time_type
float _scan_time_type
Definition: LaserScan.h:71
sensor_msgs::LaserScan_::_range_min_type
float _range_min_type
Definition: LaserScan.h:74
sensor_msgs::LaserScan_::ranges
_ranges_type ranges
Definition: LaserScan.h:81
sensor_msgs::LaserScan_::scan_time
_scan_time_type scan_time
Definition: LaserScan.h:72
sensor_msgs
Tools for manipulating sensor_msgs.
Header.h
roswrap::message_traits::Definition< ::sensor_msgs::LaserScan_< ContainerAllocator > >::value
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
Definition: LaserScan.h:237


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