Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 #ifndef VIGIR_FOOTSTEP_PLANNING_HOT_MAP_HEURISTIC_H__
00030 #define VIGIR_FOOTSTEP_PLANNING_HOT_MAP_HEURISTIC_H__
00031
00032 #include <ros/ros.h>
00033 #include <boost/thread/mutex.hpp>
00034
00035 #include <nav_msgs/OccupancyGrid.h>
00036
00037 #include <vigir_footstep_planning_lib/math.h>
00038
00039 #include <vigir_footstep_planning_plugins/plugins/heuristic_plugin.h>
00040
00041
00042
00043 namespace vigir_footstep_planning
00044 {
00045 class HotMapHeuristic
00046 : public HeuristicPlugin
00047 {
00048 struct StateKey
00049 {
00050 StateKey(const State& s, double cell_size, double angle_bin_size)
00051 : x(state_2_cell(s.getX(), cell_size))
00052 , y(state_2_cell(s.getY(), cell_size))
00053 , yaw(angle_state_2_cell(s.getYaw(), angle_bin_size))
00054 {
00055 }
00056
00057 bool operator<(const StateKey& key) const
00058 {
00059 if (x < key.x) return true;
00060 if (x > key.x) return false;
00061 if (y < key.y) return true;
00062 if (y > key.y) return false;
00063 if (yaw < key.yaw) return true;
00064 if (yaw > key.yaw) return false;
00065 return false;
00066 }
00067
00068 int x;
00069 int y;
00070 int yaw;
00071 };
00072
00073 public:
00074 HotMapHeuristic();
00075
00076 bool loadParams(const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet()) override;
00077
00078 bool initialize(const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet()) override;
00079
00080 void reset();
00081
00082 double getHeuristicValue(const State& from, const State& to, const State& start, const State& goal) const override;
00083
00084
00085 typedef std::map<StateKey, unsigned int> HotMap;
00086
00087 protected:
00088 void publishHotMap(const ros::TimerEvent& publish_timer) const;
00089
00090
00091 ros::Publisher hot_map_pub_;
00092
00093 ros::Timer publish_timer_;
00094
00095
00096 mutable boost::shared_mutex hot_map_shared_mutex_;
00097
00098 mutable HotMap hot_map_;
00099 mutable unsigned int total_hit_counter_;
00100
00101 double cell_size_;
00102 double angle_bin_size_;
00103 };
00104 }
00105
00106 #endif