message_traits.hpp
Go to the documentation of this file.
00001 #pragma once
00002 
00003 #include <grid_map_msgs/GridMap.h>
00004 #include <grid_map_msgs/GridMap.h>
00005 
00006 namespace ros {
00007 namespace message_traits {
00008 
00009 template<>
00010 struct HasHeader<grid_map_msgs::GridMap> : public TrueType {};
00011 
00012 template <>
00013 struct Header<grid_map_msgs::GridMap, typename boost::enable_if<HasHeader<grid_map_msgs::GridMap>>::type>
00014 {
00015   static std_msgs::Header* pointer(grid_map_msgs::GridMap& m)
00016   {
00017     return &m.info.header;
00018   }
00019 
00020   static std_msgs::Header const* pointer(const grid_map_msgs::GridMap& m)
00021   {
00022     return &m.info.header;
00023   }
00024 };
00025 
00026 template<>
00027 struct FrameId<grid_map_msgs::GridMap, typename boost::enable_if<HasHeader<grid_map_msgs::GridMap>>::type>
00028 {
00029   static std::string* pointer(grid_map_msgs::GridMap& m)
00030   {
00031     return &m.info.header.frame_id;
00032   }
00033 
00034   static std::string const* pointer(const grid_map_msgs::GridMap& m)
00035   {
00036     return &m.info.header.frame_id;
00037   }
00038 
00039   static std::string value(const grid_map_msgs::GridMap& m)
00040   {
00041     return m.info.header.frame_id;
00042   }
00043 };
00044 
00045 template<>
00046 struct TimeStamp<grid_map_msgs::GridMap, typename boost::enable_if<HasHeader<grid_map_msgs::GridMap>>::type>
00047 {
00048   static ros::Time* pointer(grid_map_msgs::GridMap& m)
00049   {
00050     return &m.info.header.stamp;
00051   }
00052 
00053   static ros::Time const* pointer(const grid_map_msgs::GridMap& m)
00054   {
00055     return &m.info.header.stamp;
00056   }
00057 
00058   static ros::Time value(const grid_map_msgs::GridMap& m)
00059   {
00060     return m.info.header.stamp;
00061   }
00062 };
00063 
00064 }
00065 }


grid_map_ros
Author(s): Péter Fankhauser
autogenerated on Tue Jul 9 2019 05:06:32