layered_costmap.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, 2013, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Eitan Marder-Eppstein
00036  *         David V. Lu!!
00037  *********************************************************************/
00038 #ifndef COSTMAP_2D_LAYERED_COSTMAP_H_
00039 #define COSTMAP_2D_LAYERED_COSTMAP_H_
00040 
00041 #include <costmap_2d/cost_values.h>
00042 #include <costmap_2d/layer.h>
00043 #include <costmap_2d/costmap_2d.h>
00044 #include <vector>
00045 #include <string>
00046 
00047 namespace costmap_2d
00048 {
00049 class Layer;
00050 
00055 class LayeredCostmap
00056 {
00057 public:
00061   LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown);
00062 
00066   ~LayeredCostmap();
00067 
00072   void updateMap(double robot_x, double robot_y, double robot_yaw);
00073 
00074   std::string getGlobalFrameID() const
00075   {
00076     return global_frame_;
00077   }
00078 
00079   void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y,
00080                  bool size_locked = false);
00081 
00082   void getUpdatedBounds(double& minx, double& miny, double& maxx, double& maxy)
00083   {
00084     minx = minx_;
00085     miny = miny_;
00086     maxx = maxx_;
00087     maxy = maxy_;
00088   }
00089 
00090   bool isCurrent();
00091 
00092   Costmap2D* getCostmap()
00093   {
00094     return &costmap_;
00095   }
00096 
00097   bool isRolling()
00098   {
00099     return rolling_window_;
00100   }
00101 
00102   bool isTrackingUnknown()
00103   {
00104     return costmap_.getDefaultValue() == costmap_2d::NO_INFORMATION;
00105   }
00106 
00107   std::vector<boost::shared_ptr<Layer> >* getPlugins()
00108   {
00109     return &plugins_;
00110   }
00111 
00112   void addPlugin(boost::shared_ptr<Layer> plugin)
00113   {
00114     plugins_.push_back(plugin);
00115   }
00116 
00117   bool isSizeLocked()
00118   {
00119     return size_locked_;
00120   }
00121 
00122   void getBounds(unsigned int* x0, unsigned int* xn, unsigned int* y0, unsigned int* yn)
00123   {
00124     *x0 = bx0_;
00125     *xn = bxn_;
00126     *y0 = by0_;
00127     *yn = byn_;
00128   }
00129 
00130   bool isInitialized()
00131   {
00132       return initialized_;
00133   }
00134 
00138   void setFootprint(const std::vector<geometry_msgs::Point>& footprint_spec);
00139 
00141   const std::vector<geometry_msgs::Point>& getFootprint() { return footprint_; }
00142 
00148   double getCircumscribedRadius() { return circumscribed_radius_; }
00149 
00155   double getInscribedRadius() { return inscribed_radius_; }
00156 
00157 private:
00158   Costmap2D costmap_;
00159   std::string global_frame_;
00160 
00161   bool rolling_window_;  
00162 
00163   bool current_;
00164   double minx_, miny_, maxx_, maxy_;
00165   unsigned int bx0_, bxn_, by0_, byn_;
00166 
00167   std::vector<boost::shared_ptr<Layer> > plugins_;
00168 
00169   bool initialized_;
00170   bool size_locked_;
00171   double circumscribed_radius_, inscribed_radius_;
00172   std::vector<geometry_msgs::Point> footprint_;
00173 };
00174 
00175 }  // namespace costmap_2d
00176 
00177 #endif  // COSTMAP_2D_LAYERED_COSTMAP_H_


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:46:15