00001
00002 #ifndef SENSOR_MSGS_BOOST_SERIALIZATION_RANGE_H
00003 #define SENSOR_MSGS_BOOST_SERIALIZATION_RANGE_H
00004
00005 #include <boost/serialization/serialization.hpp>
00006 #include <boost/serialization/nvp.hpp>
00007 #include <sensor_msgs/Range.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::Range_<ContainerAllocator> & m, unsigned int)
00022 {
00023 a & make_nvp("header",m.header);
00024 a & make_nvp("radiation_type",m.radiation_type);
00025 a & make_nvp("field_of_view",m.field_of_view);
00026 a & make_nvp("min_range",m.min_range);
00027 a & make_nvp("max_range",m.max_range);
00028 a & make_nvp("range",m.range);
00029 }
00030
00031 }
00032 }
00033
00034 #endif // SENSOR_MSGS_BOOST_SERIALIZATION_RANGE_H
00035