5 #ifndef SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H 6 #define SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H 24 template <
class ContainerAllocator>
81 typedef std::vector< ::sensor_msgs::LaserEcho_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_<ContainerAllocator> >::other >
_ranges_type;
84 typedef std::vector< ::sensor_msgs::LaserEcho_<ContainerAllocator> ,
typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_<ContainerAllocator> >::other >
_intensities_type;
104 template<
typename ContainerAllocator>
105 std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator> &
v)
115 namespace message_traits
128 template <
class ContainerAllocator>
133 template <
class ContainerAllocator>
138 template <
class ContainerAllocator>
143 template <
class ContainerAllocator>
148 template <
class ContainerAllocator>
153 template <
class ContainerAllocator>
159 template<
class ContainerAllocator>
164 return "6fefb0c6da89d7c8abe4b339f5c2f8fb";
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;
172 template<
class ContainerAllocator>
177 return "sensor_msgs/MultiEchoLaserScan";
180 static const char*
value(const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>&) {
return value(); }
183 template<
class ContainerAllocator>
188 return "# Single scan from a multi-echo planar laser range-finder\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\ 194 Header header # timestamp in the header is the acquisition time of \n\ 195 # the first ray in the scan.\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\ 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\ 205 float32 time_increment # time between measurements [seconds] - if your scanner\n\ 206 # is moving, this will be used in interpolating position\n\ 208 float32 scan_time # time between scans [seconds]\n\ 210 float32 range_min # minimum range value [m]\n\ 211 float32 range_max # maximum range value [m]\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\ 225 # sequence ID: consecutively increasing ID \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\ 232 #Frame this data is associated with\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\ 242 float32[] echoes # Multiple values of ranges or intensities.\n\ 243 # Each array represents data from the same angle increment.\n\ 247 static const char*
value(const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>&) {
return value(); }
255 namespace serialization
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);
282 namespace message_operations
285 template<
class ContainerAllocator>
288 template<
typename Stream>
static void stream(Stream&
s,
const std::string& indent, const ::sensor_msgs::MultiEchoLaserScan_<ContainerAllocator>&
v)
290 s << indent <<
"header: ";
293 s << indent <<
"angle_min: ";
295 s << indent <<
"angle_max: ";
297 s << indent <<
"angle_increment: ";
299 s << indent <<
"time_increment: ";
301 s << indent <<
"scan_time: ";
303 s << indent <<
"range_min: ";
305 s << indent <<
"range_max: ";
307 s << indent <<
"ranges[]" << std::endl;
308 for (
size_t i = 0;
i < v.ranges.size(); ++
i)
310 s << indent <<
" ranges[" <<
i <<
"]: ";
315 s << indent <<
"intensities[]" << std::endl;
316 for (
size_t i = 0;
i < v.intensities.size(); ++
i)
318 s << indent <<
" intensities[" <<
i <<
"]: ";
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 > &)
static void allInOne(Stream &stream, T m)
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 ...
_time_increment_type time_increment
GLsizei const GLchar *const * string
Specialize to provide the datatype for a message.
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 > &)
_range_min_type range_min
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)
_angle_max_type angle_max
::sensor_msgs::MultiEchoLaserScan_< std::allocator< void > > MultiEchoLaserScan
static const char * value(const ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > &)
MultiEchoLaserScan_< ContainerAllocator > Type
Tools for manipulating sensor_msgs.
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > const > ConstPtr
static const char * value()
static const char * value()
#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.
_intensities_type intensities
_angle_increment_type angle_increment
std::vector< ::sensor_msgs::LaserEcho_< ContainerAllocator >, typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_< ContainerAllocator > >::other > _ranges_type
float _angle_increment_type
MultiEchoLaserScan_(const ContainerAllocator &_alloc)
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan_< ContainerAllocator > > Ptr
_range_max_type range_max
_scan_time_type scan_time
Templated serialization class. Default implementation provides backwards compatibility with old messa...
float _time_increment_type
static const char * value()
_angle_min_type angle_min
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan const > MultiEchoLaserScanConstPtr
boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan > MultiEchoLaserScanPtr