29 #ifndef VIGIR_FOOTSTEP_PLANNING_HOT_MAP_HEURISTIC_H__ 30 #define VIGIR_FOOTSTEP_PLANNING_HOT_MAP_HEURISTIC_H__ 33 #include <boost/thread/mutex.hpp> 35 #include <nav_msgs/OccupancyGrid.h> 37 #include <vigir_footstep_planning_lib/math.h> 39 #include <vigir_footstep_planning_plugins/plugins/heuristic_plugin.h> 46 :
public HeuristicPlugin
50 StateKey(
const State& s,
double cell_size,
double angle_bin_size)
51 :
x(state_2_cell(s.getX(), cell_size))
52 ,
y(state_2_cell(s.getY(), cell_size))
53 ,
yaw(angle_state_2_cell(s.getYaw(), angle_bin_size))
59 if (
x < key.
x)
return true;
60 if (
x > key.
x)
return false;
61 if (
y < key.
y)
return true;
62 if (
y > key.
y)
return false;
63 if (
yaw < key.
yaw)
return true;
64 if (
yaw > key.
yaw)
return false;
76 bool loadParams(
const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet())
override;
78 bool initialize(
const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet())
override;
82 double getHeuristicValue(
const State& from,
const State& to,
const State& start,
const State& goal)
const override;
85 typedef std::map<StateKey, unsigned int>
HotMap;