00001
00002 #ifndef SENSOR_MSGS_BOOST_SERIALIZATION_LASERSCAN_H
00003 #define SENSOR_MSGS_BOOST_SERIALIZATION_LASERSCAN_H
00004
00005 #include <boost/serialization/serialization.hpp>
00006 #include <boost/serialization/nvp.hpp>
00007 #include <sensor_msgs/LaserScan.h>
00008 #include <ros/common.h>
00009 #if ROS_VERSION_MINIMUM(1,4,0)
00010 #include <std_msgs/Header.h>
00011 #else
00012 #include <roslib/Header.h>
00013 #endif
00014
00015 namespace boost
00016 {
00017 namespace serialization
00018 {
00019
00020 template<class Archive, class ContainerAllocator>
00021 void serialize(Archive& a, ::sensor_msgs::LaserScan_<ContainerAllocator> & m, unsigned int)
00022 {
00023 a & make_nvp("header",m.header);
00024 a & make_nvp("angle_min",m.angle_min);
00025 a & make_nvp("angle_max",m.angle_max);
00026 a & make_nvp("angle_increment",m.angle_increment);
00027 a & make_nvp("time_increment",m.time_increment);
00028 a & make_nvp("scan_time",m.scan_time);
00029 a & make_nvp("range_min",m.range_min);
00030 a & make_nvp("range_max",m.range_max);
00031 a & make_nvp("ranges",m.ranges);
00032 a & make_nvp("intensities",m.intensities);
00033 }
00034
00035 }
00036 }
00037
00038 #endif // SENSOR_MSGS_BOOST_SERIALIZATION_LASERSCAN_H
00039