place_profile_conversions.h
Go to the documentation of this file.
00001 
00004 #ifndef LAMA_COMMON_PLACE_PROFILE_CONVERSIONS_H
00005 #define LAMA_COMMON_PLACE_PROFILE_CONVERSIONS_H
00006 
00007 #include <algorithm>
00008 
00009 #include <ros/ros.h>
00010 #include <geometry_msgs/Polygon.h>
00011 #include <sensor_msgs/LaserScan.h>
00012 #include <sensor_msgs/PointCloud.h>
00013 #include <nav_msgs/OccupancyGrid.h>
00014 #include <laser_geometry/laser_geometry.h>
00015 
00016 #include <lama_common/place_profile_utils.h>
00017 #include <lama_msgs/PlaceProfile.h>
00018 
00019 #include <map_ray_caster/map_ray_caster.h>
00020 
00021 using std::vector;
00022 using lama_msgs::PlaceProfile;
00023 
00024 namespace lama_common
00025 {
00026 
00031 inline int32_t circular_index(int32_t index, size_t size)
00032 {
00033   return (index + size) % size;
00034 }
00035 
00036 geometry_msgs::Polygon placeProfileToPolygon(const PlaceProfile& profile);
00037 
00038 sensor_msgs::PointCloud placeProfileToPointCloud(const PlaceProfile& profile);
00039 
00040 PlaceProfile laserScanToPlaceProfile(const sensor_msgs::LaserScan& scan, double range_cutoff);
00041 
00042 PlaceProfile costmapToPlaceProfile(const nav_msgs::OccupancyGrid& map, double range_cutoff = 0);
00043 
00044 } // namespace lama_common
00045 
00046 #endif //  LAMA_COMMON_PLACE_PROFILE_CONVERSIONS_H


lama_common
Author(s): Gaël Ecorchard , Karel Košnar , Vojtěch Vonásek
autogenerated on Thu Jun 6 2019 22:02:03