costmap.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef NAV_CORE2_COSTMAP_H
36 #define NAV_CORE2_COSTMAP_H
37 
38 #include <nav_grid/nav_grid.h>
39 #include <nav_core2/common.h>
40 #include <nav_core2/bounds.h>
41 #include <boost/thread.hpp>
42 #include <string>
43 
44 namespace nav_core2
45 {
46 
47 class Costmap : public nav_grid::NavGrid<unsigned char>
48 {
49 public:
50  static const unsigned char NO_INFORMATION = 255;
51  static const unsigned char LETHAL_OBSTACLE = 254;
52  static const unsigned char INSCRIBED_INFLATED_OBSTACLE = 253;
53  static const unsigned char FREE_SPACE = 0;
54 
55  using Ptr = std::shared_ptr<Costmap>;
56 
60  virtual ~Costmap() {}
61 
72  virtual void initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf) {}
73 
74  inline unsigned char getCost(const unsigned int x, const unsigned int y)
75  {
76  return getValue(x, y);
77  }
78 
79  inline unsigned char getCost(const nav_grid::Index& index)
80  {
81  return getValue(index.x, index.y);
82  }
83 
84  inline void setCost(const unsigned int x, const unsigned int y, const unsigned char cost)
85  {
86  setValue(x, y, cost);
87  }
88 
89  inline void setCost(const nav_grid::Index& index, const unsigned char cost)
90  {
91  setValue(index, cost);
92  }
93 
101  virtual void update() {}
102 
103  using mutex_t = boost::recursive_mutex;
107  virtual mutex_t* getMutex() = 0;
108 
112  virtual bool canTrackChanges() { return false; }
113 
137  virtual UIntBounds getChangeBounds(const std::string& ns)
138  {
139  if (!canTrackChanges())
140  {
141  throw std::runtime_error("You called 'getChangeBounds()' on a derived Costmap type that is not capable of "
142  "tracking changes (i.e. canTrackChanges() returns false). You shouldn't do that.");
143  }
144  else
145  {
146  throw std::runtime_error("You called 'getChangeBounds()' on a derived Costmap type that is capable of tracking "
147  "changes but has not properly implemented this function. You should yell at the author "
148  "of the derived Costmap.");
149  }
150  return UIntBounds();
151  }
152 };
153 } // namespace nav_core2
154 
155 #endif // NAV_CORE2_COSTMAP_H
virtual void setValue(const unsigned int x, const unsigned int y, const T &value)=0
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
Definition: costmap.h:52
void setCost(const nav_grid::Index &index, const unsigned char cost)
Definition: costmap.h:89
void setCost(const unsigned int x, const unsigned int y, const unsigned char cost)
Definition: costmap.h:84
virtual T getValue(const unsigned int x, const unsigned int y) const =0
virtual UIntBounds getChangeBounds(const std::string &ns)
If canTrackChanges, get the bounding box for how much of the costmap has changed. ...
Definition: costmap.h:137
static const unsigned char NO_INFORMATION
Definition: costmap.h:50
unsigned char getCost(const unsigned int x, const unsigned int y)
Definition: costmap.h:74
unsigned char getCost(const nav_grid::Index &index)
Definition: costmap.h:79
boost::recursive_mutex mutex_t
Definition: costmap.h:103
virtual bool canTrackChanges()
Flag to indicate whether this costmap is able to track how much has changed.
Definition: costmap.h:112
virtual void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf)
Initialization function for the Costmap.
Definition: costmap.h:72
std::shared_ptr< Costmap > Ptr
Definition: costmap.h:55
static const unsigned char LETHAL_OBSTACLE
Definition: costmap.h:51
std::shared_ptr< tf::TransformListener > TFListenerPtr
Definition: common.h:40
static const unsigned char FREE_SPACE
Definition: costmap.h:53
virtual void update()
Update the values in the costmap.
Definition: costmap.h:101
virtual mutex_t * getMutex()=0
Accessor for boost mutex.
virtual ~Costmap()
Virtual Destructor.
Definition: costmap.h:60


nav_core2
Author(s):
autogenerated on Wed Jun 26 2019 20:06:06