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 
00066 
00073       inline MapCell& operator() (unsigned int x, unsigned int y){
00074         return map_[size_x_ * y + x];
00075       }
00076 
00083       inline MapCell operator() (unsigned int x, unsigned int y) const {
00084         return map_[size_x_ * y + x];
00085       }
00086 
00087       inline MapCell& getCell(unsigned int x, unsigned int y){
00088         return map_[size_x_ * y + x];
00089       }
00090 
00094       ~MapGrid(){}
00095 
00100       MapGrid(const MapGrid& mg);
00101 
00106       MapGrid& operator= (const MapGrid& mg);
00107 
00111       void resetPathDist();
00112 
00118       void sizeCheck(unsigned int size_x, unsigned int size_y);
00119 
00123       void commonInit();
00124 
00131       size_t getIndex(int x, int y);
00132 
00136       inline double obstacleCosts() {
00137         return map_.size();
00138       }
00139 
00144       inline double unreachableCellCosts() {
00145         return map_.size() + 1;
00146       }
00147 
00153       inline bool updatePathCell(MapCell* current_cell, MapCell* check_cell,
00154           const costmap_2d::Costmap2D& costmap);
00155 
00163       static void adjustPlanResolution(const std::vector<geometry_msgs::PoseStamped>& global_plan_in,
00164             std::vector<geometry_msgs::PoseStamped>& global_plan_out, double resolution);
00165 
00170       void computeTargetDistance(std::queue<MapCell*>& dist_queue, const costmap_2d::Costmap2D& costmap);
00171 
00176       void computeGoalDistance(std::queue<MapCell*>& dist_queue, const costmap_2d::Costmap2D& costmap);
00177 
00181       void setTargetCells(const costmap_2d::Costmap2D& costmap, const std::vector<geometry_msgs::PoseStamped>& global_plan);
00182 
00186       void setLocalGoal(const costmap_2d::Costmap2D& costmap,
00187             const std::vector<geometry_msgs::PoseStamped>& global_plan);
00188 
00189       double goal_x_, goal_y_; 
00191       unsigned int size_x_, size_y_; 
00192 
00193     private:
00194 
00195       std::vector<MapCell> map_; 
00196 
00197   };
00198 };
00199 
00200 #endif


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Mon Oct 6 2014 02:45:34