5 #ifndef SENSOR_MSGS_MESSAGE_LASERSCAN_H 6 #define SENSOR_MSGS_MESSAGE_LASERSCAN_H 22 template <
class ContainerAllocator>
79 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >
_ranges_type;
82 typedef std::vector<float, typename ContainerAllocator::template rebind<float>::other >
_intensities_type;
93 typedef ::sensor_msgs::LaserScan_<std::allocator<void> >
LaserScan;
102 template<
typename ContainerAllocator>
103 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::LaserScan_<ContainerAllocator> &
v)
113 namespace message_traits
126 template <
class ContainerAllocator>
131 template <
class ContainerAllocator>
136 template <
class ContainerAllocator>
141 template <
class ContainerAllocator>
146 template <
class ContainerAllocator>
151 template <
class ContainerAllocator>
157 template<
class ContainerAllocator>
162 return "90c7ef2dc6895d81024acba2ac42f369";
165 static const char*
value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) {
return value(); }
166 static const uint64_t static_value1 = 0x90c7ef2dc6895d81ULL;
167 static const uint64_t static_value2 = 0x024acba2ac42f369ULL;
170 template<
class ContainerAllocator>
175 return "sensor_msgs/LaserScan";
178 static const char*
value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) {
return value(); }
181 template<
class ContainerAllocator>
186 return "# Single scan from a planar laser range-finder\n\ 188 # If you have another ranging device with different behavior (e.g. a sonar\n\ 189 # array), please find or create a different message, since applications\n\ 190 # will make fairly laser-specific assumptions about this data\n\ 192 Header header # timestamp in the header is the acquisition time of \n\ 193 # the first ray in the scan.\n\ 195 # in frame frame_id, angles are measured around \n\ 196 # the positive Z axis (counterclockwise, if Z is up)\n\ 197 # with zero angle being forward along the x axis\n\ 199 float32 angle_min # start angle of the scan [rad]\n\ 200 float32 angle_max # end angle of the scan [rad]\n\ 201 float32 angle_increment # angular distance between measurements [rad]\n\ 203 float32 time_increment # time between measurements [seconds] - if your scanner\n\ 204 # is moving, this will be used in interpolating position\n\ 206 float32 scan_time # time between scans [seconds]\n\ 208 float32 range_min # minimum range value [m]\n\ 209 float32 range_max # maximum range value [m]\n\ 211 float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n\ 212 float32[] intensities # intensity data [device-specific units]. If your\n\ 213 # device does not provide intensities, please leave\n\ 214 # the array empty.\n\ 216 ================================================================================\n\ 217 MSG: std_msgs/Header\n\ 218 # Standard metadata for higher-level stamped data types.\n\ 219 # This is generally used to communicate timestamped data \n\ 220 # in a particular coordinate frame.\n\ 222 # sequence ID: consecutively increasing ID \n\ 224 #Two-integer timestamp that is expressed as:\n\ 225 # * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ 226 # * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ 227 # time-handling sugar is provided by the client library\n\ 229 #Frame this data is associated with\n\ 236 static const char*
value(const ::sensor_msgs::LaserScan_<ContainerAllocator>&) {
return value(); }
244 namespace serialization
251 stream.next(m.header);
252 stream.next(m.angle_min);
253 stream.next(m.angle_max);
254 stream.next(m.angle_increment);
255 stream.next(m.time_increment);
256 stream.next(m.scan_time);
257 stream.next(m.range_min);
258 stream.next(m.range_max);
259 stream.next(m.ranges);
260 stream.next(m.intensities);
271 namespace message_operations
274 template<
class ContainerAllocator>
277 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::LaserScan_<ContainerAllocator>&
v)
279 s << indent <<
"header: ";
282 s << indent <<
"angle_min: ";
284 s << indent <<
"angle_max: ";
286 s << indent <<
"angle_increment: ";
288 s << indent <<
"time_increment: ";
290 s << indent <<
"scan_time: ";
292 s << indent <<
"range_min: ";
294 s << indent <<
"range_max: ";
296 s << indent <<
"ranges[]" << std::endl;
297 for (
size_t i = 0;
i < v.ranges.size(); ++
i)
299 s << indent <<
" ranges[" <<
i <<
"]: ";
302 s << indent <<
"intensities[]" << std::endl;
303 for (
size_t i = 0;
i < v.intensities.size(); ++
i)
305 s << indent <<
" intensities[" <<
i <<
"]: ";
314 #endif // SENSOR_MSGS_MESSAGE_LASERSCAN_H
static const char * value()
typedef void(APIENTRY *GLDEBUGPROC)(GLenum source
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
_range_max_type range_max
Specialize to provide the md5sum for a message.
boost::shared_ptr< ::sensor_msgs::LaserScan_< ContainerAllocator > const > ConstPtr
::sensor_msgs::LaserScan_< std::allocator< void > > LaserScan
static void allInOne(Stream &stream, T m)
Base type for compile-type true/false tests. Compatible with Boost.MPL. classes inheriting from this ...
GLsizei const GLchar *const * string
float _angle_increment_type
Specialize to provide the datatype for a message.
_angle_increment_type angle_increment
A fixed-size datatype is one whose size is constant, i.e. it has no variable-length arrays or strings...
_intensities_type intensities
LaserScan_< ContainerAllocator > Type
static void stream(Stream &s, const std::string &indent, const ::sensor_msgs::LaserScan_< ContainerAllocator > &v)
Stream base-class, provides common functionality for IStream and OStream.
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
boost::shared_ptr< ::sensor_msgs::LaserScan > LaserScanPtr
std::vector< float, typename ContainerAllocator::template rebind< float >::other > _ranges_type
_time_increment_type time_increment
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
boost::shared_ptr< ::sensor_msgs::LaserScan const > LaserScanConstPtr
float _time_increment_type
Tools for manipulating sensor_msgs.
#define ROS_DECLARE_ALLINONE_SERIALIZER
Declare your serializer to use an allInOne member instead of requiring 3 different serialization func...
unsigned __int64 uint64_t
Specialize to provide the definition for a message.
LaserScan_(const ContainerAllocator &_alloc)
std::vector< float, typename ContainerAllocator::template rebind< float >::other > _intensities_type
boost::shared_ptr< ::sensor_msgs::LaserScan_< ContainerAllocator > > Ptr
static const char * value()
::std_msgs::Header_< ContainerAllocator > _header_type
_angle_min_type angle_min
_scan_time_type scan_time
_range_min_type range_min
static const char * value(const ::sensor_msgs::LaserScan_< ContainerAllocator > &)
_angle_max_type angle_max
Templated serialization class. Default implementation provides backwards compatibility with old messa...
static const char * value()