include
nav_core_adapter
global_planner_adapter.h
Go to the documentation of this file.
1
/*
2
* Software License Agreement (BSD License)
3
*
4
* Copyright (c) 2017, 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_GLOBAL_PLANNER_ADAPTER_H
36
#define NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER_H
37
38
#include <
nav_core/base_global_planner.h
>
39
#include <
nav_core2/global_planner.h
>
40
#include <
nav_core_adapter/costmap_adapter.h
>
41
#include <
pluginlib/class_loader.h
>
42
#include <memory>
43
#include <string>
44
#include <vector>
45
46
namespace
nav_core_adapter
47
{
48
53
class
GlobalPlannerAdapter
:
public
nav_core::BaseGlobalPlanner
54
{
55
public
:
56
GlobalPlannerAdapter
();
57
58
// Standard ROS Global Planner Interface
59
void
initialize
(std::string name,
costmap_2d::Costmap2DROS
* costmap_ros)
override
;
60
bool
makePlan
(
const
geometry_msgs::PoseStamped&
start
,
61
const
geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan)
override
;
62
63
protected
:
64
// Plugin handling
65
pluginlib::ClassLoader<nav_core2::GlobalPlanner>
planner_loader_
;
66
boost::shared_ptr<nav_core2::GlobalPlanner>
planner_
;
67
ros::Publisher
path_pub_
;
68
69
TFListenerPtr
tf_
;
70
71
std::shared_ptr<CostmapAdapter>
costmap_adapter_
;
72
costmap_2d::Costmap2DROS
*
costmap_ros_
;
73
};
74
75
}
// namespace nav_core_adapter
76
77
#endif // NAV_CORE_ADAPTER_GLOBAL_PLANNER_ADAPTER_H
ros::Publisher
nav_core_adapter::GlobalPlannerAdapter::tf_
TFListenerPtr tf_
Definition:
global_planner_adapter.h:69
nav_core_adapter::GlobalPlannerAdapter::makePlan
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) override
Definition:
global_planner_adapter.cpp:72
class_loader.h
boost::shared_ptr< nav_core2::GlobalPlanner >
nav_core_adapter::GlobalPlannerAdapter::GlobalPlannerAdapter
GlobalPlannerAdapter()
Definition:
global_planner_adapter.cpp:48
nav_core_adapter::GlobalPlannerAdapter::planner_loader_
pluginlib::ClassLoader< nav_core2::GlobalPlanner > planner_loader_
Definition:
global_planner_adapter.h:65
nav_core_adapter::GlobalPlannerAdapter::costmap_adapter_
std::shared_ptr< CostmapAdapter > costmap_adapter_
Definition:
global_planner_adapter.h:71
pluginlib::ClassLoader< nav_core2::GlobalPlanner >
costmap_adapter.h
nav_core_adapter::GlobalPlannerAdapter::path_pub_
ros::Publisher path_pub_
Definition:
global_planner_adapter.h:67
start
ROSCPP_DECL void start()
nav_core_adapter::GlobalPlannerAdapter::planner_
boost::shared_ptr< nav_core2::GlobalPlanner > planner_
Definition:
global_planner_adapter.h:66
base_global_planner.h
TFListenerPtr
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
nav_core_adapter
Definition:
costmap_adapter.h:43
nav_core_adapter::GlobalPlannerAdapter::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition:
global_planner_adapter.h:72
nav_core_adapter::GlobalPlannerAdapter::initialize
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros) override
Load the nav_core2 global planner and initialize it.
Definition:
global_planner_adapter.cpp:56
nav_core::BaseGlobalPlanner
global_planner.h
costmap_2d::Costmap2DROS
nav_core_adapter::GlobalPlannerAdapter
used for employing a nav_core2 global planner interface as a nav_core plugin, like in move_base.
Definition:
global_planner_adapter.h:53
nav_core_adapter
Author(s):
autogenerated on Sun May 18 2025 02:47:37