Go to the documentation of this file.
6 #ifndef SENSOR_MSGS_MESSAGE_LASERSCAN_H
7 #define SENSOR_MSGS_MESSAGE_LASERSCAN_H
14 #include <ros/types.h>
15 #include <ros/serialization.h>
16 #include <ros/builtin_message_traits.h>
17 #include <ros/message_operations.h>
23 template <
class ContainerAllocator>
80 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >
_ranges_type;
83 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >
_intensities_type;
89 typedef std::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator> >
Ptr;
90 typedef std::shared_ptr< ::sensor_msgs::LaserScan_<ContainerAllocator>
const>
ConstPtr;
94 typedef ::sensor_msgs::LaserScan_<std::allocator<void> >
LaserScan;
103 template<
typename ContainerAllocator>
104 std::ostream&
operator<<(std::ostream& s, const ::sensor_msgs::LaserScan_<ContainerAllocator> & v)
114 namespace message_traits
127 template <
class ContainerAllocator>
132 template <
class ContainerAllocator>
137 template <
class ContainerAllocator>
142 template <
class ContainerAllocator>
147 template <
class ContainerAllocator>
152 template <
class ContainerAllocator>
158 template<
class ContainerAllocator>
163 return "90c7ef2dc6895d81024acba2ac42f369";
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;
171 template<
class ContainerAllocator>
176 return "sensor_msgs/LaserScan";
179 static const char*
value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) {
return value(); }
182 template<
class ContainerAllocator>
187 return "# Single scan from a planar laser range-finder\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\
193 Header header # timestamp in the header is the acquisition time of \n\
194 # the first ray in the scan.\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\
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\
204 float32 time_increment # time between measurements [seconds] - if your scanner\n\
205 # is moving, this will be used in interpolating position\n\
207 float32 scan_time # time between scans [seconds]\n\
209 float32 range_min # minimum range value [m]\n\
210 float32 range_max # maximum range value [m]\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\
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\
223 # sequence ID: consecutively increasing ID \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\
230 #Frame this data is associated with\n\
237 static const char*
value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) {
return value(); }
245 namespace serialization
250 template<
typename Stream,
typename T>
inline static void allInOne(
Stream& stream, T m)
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);
272 namespace message_operations
275 template<
class ContainerAllocator>
278 template<
typename Stream>
static void stream(Stream& s,
const std::string&
indent, const ::sensor_msgs::LaserScan_<ContainerAllocator>& v)
287 s <<
indent <<
"angle_increment: ";
289 s <<
indent <<
"time_increment: ";
297 s <<
indent <<
"ranges[]" << std::endl;
298 for (
size_t i = 0; i < v.ranges.size(); ++i)
300 s <<
indent <<
" ranges[" << i <<
"]: ";
303 s <<
indent <<
"intensities[]" << std::endl;
304 for (
size_t i = 0; i < v.intensities.size(); ++i)
306 s <<
indent <<
" intensities[" << i <<
"]: ";
315 #endif // SENSOR_MSGS_MESSAGE_LASERSCAN_H
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::LaserScan_< ContainerAllocator > &v)
std::shared_ptr< ::sensor_msgs::LaserScan_< ContainerAllocator > > Ptr
Templated serialization class. Default implementation provides backwards compatibility with old messa...
_range_max_type range_max
std::shared_ptr< ::sensor_msgs::LaserScan_< ContainerAllocator > const > ConstPtr
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
_intensities_type intensities
LaserScan_< ContainerAllocator > Type
float _time_increment_type
static void stream(Stream &s, const std::string &indent, const M &value)
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::LaserScan_< ContainerAllocator > &)
static void allInOne(Stream &stream, T m)
float _angle_increment_type
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
_angle_increment_type angle_increment
Specialize to provide the datatype for a message.
Specialize to provide the definition for a message.
::sensor_msgs::LaserScan_< std::allocator< void > > LaserScan
std::ostream & operator<<(std::ostream &s, const ::sensor_msgs::BatteryState_< ContainerAllocator > &v)
_angle_min_type angle_min
std::vector< float, typename ContainerAllocator::template rebind< float >::other > _ranges_type
static const char * value()
static const char * value()
LaserScan_(const ContainerAllocator &_alloc)
std::vector< float, typename ContainerAllocator::template rebind< float >::other > _intensities_type
::std_msgs::Header_< ContainerAllocator > _header_type
std::shared_ptr< ::sensor_msgs::LaserScan const > LaserScanConstPtr
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
Specialize to provide the md5sum for a message.
_range_min_type range_min
_time_increment_type time_increment
static const char * value()
Stream base-class, provides common functionality for IStream and OStream.
_angle_max_type angle_max
std::shared_ptr< ::sensor_msgs::LaserScan > LaserScanPtr
_scan_time_type scan_time
Tools for manipulating sensor_msgs.
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08