costmap_adapter.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_CORE_ADAPTER_COSTMAP_ADAPTER_H
36 #define NAV_CORE_ADAPTER_COSTMAP_ADAPTER_H
37 
38 #include <nav_core2/common.h>
39 #include <nav_core2/costmap.h>
41 #include <string>
42 
44 {
46 
48 {
49 public:
53  virtual ~CostmapAdapter();
54 
60  void initialize(costmap_2d::Costmap2DROS* costmap_ros, bool needs_destruction = false);
61 
62  // Standard Costmap Interface
63  void initialize(const ros::NodeHandle& parent, const std::string& name, TFListenerPtr tf) override;
65 
66  // NavGrid Interface
67  void reset() override;
68  void update() override;
69  void setValue(const unsigned int x, const unsigned int y, const unsigned char& value) override;
70  unsigned char getValue(const unsigned int x, const unsigned int y) const override;
71  void setInfo(const nav_grid::NavGridInfo& new_info) override;
72  void updateInfo(const nav_grid::NavGridInfo& new_info) override;
73 
74  // Get Costmap Pointer for Backwards Compatibility
76 
77 protected:
81 };
82 
83 } // namespace nav_core_adapter
84 
85 #endif // NAV_CORE_ADAPTER_COSTMAP_ADAPTER_H
nav_core2::Costmap::mutex_t
boost::recursive_mutex mutex_t
nav_core_adapter::CostmapAdapter::update
void update() override
Definition: costmap_adapter.cpp:89
common.h
costmap_2d::Costmap2D
nav_core_adapter::CostmapAdapter::~CostmapAdapter
virtual ~CostmapAdapter()
Deconstructor for possibly freeing the costmap_ros_ object.
Definition: costmap_adapter.cpp:58
costmap_2d_ros.h
nav_core_adapter::CostmapAdapter::getMutex
nav_core2::Costmap::mutex_t * getMutex() override
Definition: costmap_adapter.cpp:79
costmap.h
nav_core_adapter::infoFromCostmap
nav_grid::NavGridInfo infoFromCostmap(costmap_2d::Costmap2DROS *costmap_ros)
Definition: costmap_adapter.cpp:45
nav_core_adapter::CostmapAdapter::getValue
unsigned char getValue(const unsigned int x, const unsigned int y) const override
Definition: costmap_adapter.cpp:101
nav_core_adapter::CostmapAdapter::needs_destruction_
bool needs_destruction_
Definition: costmap_adapter.h:80
nav_core_adapter::CostmapAdapter::setInfo
void setInfo(const nav_grid::NavGridInfo &new_info) override
Definition: costmap_adapter.cpp:107
nav_grid::NavGridInfo
nav_core_adapter::CostmapAdapter::getCostmap2DROS
costmap_2d::Costmap2DROS * getCostmap2DROS() const
Definition: costmap_adapter.h:75
nav_core_adapter::CostmapAdapter::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition: costmap_adapter.h:78
nav_core_adapter::CostmapAdapter::updateInfo
void updateInfo(const nav_grid::NavGridInfo &new_info) override
Definition: costmap_adapter.cpp:112
nav_core_adapter::CostmapAdapter::setValue
void setValue(const unsigned int x, const unsigned int y, const unsigned char &value) override
Definition: costmap_adapter.cpp:96
TFListenerPtr
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
nav_core_adapter
Definition: costmap_adapter.h:43
nav_core_adapter::CostmapAdapter::initialize
void initialize(costmap_2d::Costmap2DROS *costmap_ros, bool needs_destruction=false)
Initialize from an existing Costmap2DROS object.
Definition: costmap_adapter.cpp:66
nav_core_adapter::CostmapAdapter
Definition: costmap_adapter.h:47
tf
nav_core2::Costmap
nav_core_adapter::CostmapAdapter::reset
void reset() override
Definition: costmap_adapter.cpp:84
nav_core_adapter::CostmapAdapter::costmap_
costmap_2d::Costmap2D * costmap_
Definition: costmap_adapter.h:79
costmap_2d::Costmap2DROS
ros::NodeHandle


nav_core_adapter
Author(s):
autogenerated on Sun May 18 2025 02:47:37