30 #ifndef VIGIR_FOOTSTEP_PLANNING_GRID_MAP_MODEL_H__ 31 #define VIGIR_FOOTSTEP_PLANNING_GRID_MAP_MODEL_H__ 35 #include <nav_msgs/OccupancyGrid.h> 37 #include <vigir_footstep_planning_plugins/plugins/collision_check_grid_map_plugin.h> 46 :
public CollisionCheckGridMapPlugin
51 bool loadParams(
const vigir_generic_params::ParameterSet& params = vigir_generic_params::ParameterSet())
override;
54 void mapCallback(
const nav_msgs::OccupancyGridConstPtr& occupancy_grid_map_);
71 bool collision_check(
double x,
double y,
double cos_theta,
double sin_theta,
double height,
double width)
const;
Stores a nav_msgs::OccupancyGrid in a convenient opencv cv::Mat as binary map (free: 255...