map_grid.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 #ifndef TRAJECTORY_ROLLOUT_MAP_GRID_H_
00035 #define TRAJECTORY_ROLLOUT_MAP_GRID_H_
00036 
00037 #include <vector>
00038 #include <iostream>
00039 #include <base_local_planner/trajectory_inc.h>
00040 #include <ros/console.h>
00041 #include <ros/ros.h>
00042 
00043 #include <base_local_planner/map_cell.h>
00044 #include <costmap_2d/costmap_2d.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 
00047 namespace base_local_planner{
00052   class MapGrid{
00053     public:
00057       MapGrid();
00058 
00064       MapGrid(unsigned int size_x, unsigned int size_y);
00065 
00074       MapGrid(unsigned int size_x, unsigned int size_y, double scale, double x, double y);
00075 
00082       inline MapCell& operator() (unsigned int x, unsigned int y){
00083         return map_[size_x_ * y + x];
00084       }
00085 
00092       inline MapCell operator() (unsigned int x, unsigned int y) const {
00093         return map_[size_x_ * y + x];
00094       }
00095 
00096       inline MapCell& getCell(unsigned int x, unsigned int y){
00097         return map_[size_x_ * y + x];
00098       }
00099 
00103       ~MapGrid(){}
00104 
00109       MapGrid(const MapGrid& mg);
00110 
00115       MapGrid& operator= (const MapGrid& mg);
00116 
00120       void resetPathDist();
00121 
00129       void sizeCheck(unsigned int size_x, unsigned int size_y, double o_x, double o_y);
00130 
00134       void commonInit();
00135 
00142       size_t getIndex(int x, int y);
00143 
00149       inline void updatePathCell(MapCell* current_cell, MapCell* check_cell, 
00150           std::queue<MapCell*>& dist_queue, const costmap_2d::Costmap2D& costmap){
00151         //mark the cell as visisted
00152         check_cell->path_mark = true;
00153 
00154         //if the cell is an obstacle set the max path distance
00155         unsigned char cost = costmap.getCost(check_cell->cx, check_cell->cy);
00156         if(!getCell(check_cell->cx, check_cell->cy).within_robot && (cost == costmap_2d::LETHAL_OBSTACLE || cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE || cost == costmap_2d::NO_INFORMATION)){
00157           check_cell->path_dist = map_.size();
00158           return;
00159         }
00160 
00161         double new_path_dist = current_cell->path_dist + 1;
00162         if(new_path_dist < check_cell->path_dist)
00163           check_cell->path_dist = new_path_dist;
00164 
00165         dist_queue.push(check_cell);
00166       }
00167 
00173       inline void updateGoalCell(MapCell* current_cell, MapCell* check_cell, 
00174           std::queue<MapCell*>& dist_queue, const costmap_2d::Costmap2D& costmap ){
00176         check_cell->goal_mark = true;
00177 
00178         //if the cell is an obstacle set the max goal distance
00179         unsigned char cost = costmap.getCost(check_cell->cx, check_cell->cy);
00180         if(!getCell(check_cell->cx, check_cell->cy).within_robot && (cost == costmap_2d::LETHAL_OBSTACLE || cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE || cost == costmap_2d::NO_INFORMATION)){
00181           check_cell->goal_dist = map_.size();
00182           return;
00183         }
00184 
00185         double new_goal_dist = current_cell->goal_dist + 1;
00186         if(new_goal_dist < check_cell->goal_dist)
00187           check_cell->goal_dist = new_goal_dist;
00188 
00189         dist_queue.push(check_cell);
00190       }
00191 
00196       void computePathDistance(std::queue<MapCell*>& dist_queue, const costmap_2d::Costmap2D& costmap);
00197 
00202       void computeGoalDistance(std::queue<MapCell*>& dist_queue, const costmap_2d::Costmap2D& costmap);
00203 
00207       void setPathCells(const costmap_2d::Costmap2D& costmap, const std::vector<geometry_msgs::PoseStamped>& global_plan);
00208 
00209       unsigned int size_x_, size_y_; 
00210       std::vector<MapCell> map_; 
00211 
00212       double scale; 
00213 
00214       double goal_x_, goal_y_; 
00216       double origin_x, origin_y; 
00217   };
00218 };
00219 
00220 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


bipedRobinBase_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Wed Oct 9 2013 10:07:14