local_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_LOCAL_PLANNER_ADAPTER_H
36 #define NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H
37 
42 #include <pluginlib/class_loader.h>
43 #include <memory>
44 #include <string>
45 #include <vector>
46 
47 namespace nav_core_adapter
48 {
49 
55 {
56 public:
58 
59  // Standard ROS Local Planner Interface
60  void initialize(std::string name, tf2_ros::Buffer* tf, costmap_2d::Costmap2DROS* costmap_ros) override;
61  bool computeVelocityCommands(geometry_msgs::Twist& cmd_vel) override;
62  bool isGoalReached() override;
63  bool setPlan(const std::vector<geometry_msgs::PoseStamped>& plan) override;
64 
65 protected:
69  bool getRobotPose(nav_2d_msgs::Pose2DStamped& pose2d);
70 
75  bool hasGoalChanged(const nav_2d_msgs::Pose2DStamped& new_goal);
76 
77  // The most recent goal pose
78  nav_2d_msgs::Pose2DStamped last_goal_;
80 
84  std::shared_ptr<nav_2d_utils::OdomSubscriber> odom_sub_;
85 
86  // Plugin handling
89 
90  // Pointer Copies
92 
93  std::shared_ptr<CostmapAdapter> costmap_adapter_;
95 };
96 
97 } // namespace nav_core_adapter
98 
99 #endif // NAV_CORE_ADAPTER_LOCAL_PLANNER_ADAPTER_H
nav_core_adapter::LocalPlannerAdapter::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override
Collect the additional information needed by nav_core2 and call the child computeVelocityCommands.
Definition: local_planner_adapter.cpp:80
nav_core_adapter::LocalPlannerAdapter::costmap_adapter_
std::shared_ptr< CostmapAdapter > costmap_adapter_
Definition: local_planner_adapter.h:93
class_loader.h
boost::shared_ptr< nav_core2::LocalPlanner >
nav_core_adapter::LocalPlannerAdapter::planner_loader_
pluginlib::ClassLoader< nav_core2::LocalPlanner > planner_loader_
Definition: local_planner_adapter.h:87
nav_core_adapter::LocalPlannerAdapter::last_goal_
nav_2d_msgs::Pose2DStamped last_goal_
Definition: local_planner_adapter.h:78
nav_core_adapter::LocalPlannerAdapter::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros) override
Load the nav_core2 local planner and initialize it.
Definition: local_planner_adapter.cpp:57
nav_core_adapter::LocalPlannerAdapter::odom_sub_
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
helper class for subscribing to odometry
Definition: local_planner_adapter.h:84
base_local_planner.h
nav_core_adapter::LocalPlannerAdapter
used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base.
Definition: local_planner_adapter.h:54
nav_core_adapter::LocalPlannerAdapter::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan) override
Convert from 2d to 3d and call child setPlan.
Definition: local_planner_adapter.cpp:133
local_planner.h
tf2_ros::Buffer
pluginlib::ClassLoader< nav_core2::LocalPlanner >
nav_core_adapter::LocalPlannerAdapter::planner_
boost::shared_ptr< nav_core2::LocalPlanner > planner_
Definition: local_planner_adapter.h:88
nav_core_adapter::LocalPlannerAdapter::hasGoalChanged
bool hasGoalChanged(const nav_2d_msgs::Pose2DStamped &new_goal)
See if the back of the global plan matches the most recent goal pose.
Definition: local_planner_adapter.cpp:162
costmap_adapter.h
nav_core_adapter::LocalPlannerAdapter::has_active_goal_
bool has_active_goal_
Definition: local_planner_adapter.h:79
TFListenerPtr
std::shared_ptr< tf2_ros::Buffer > TFListenerPtr
nav_core_adapter::LocalPlannerAdapter::isGoalReached
bool isGoalReached() override
Collect the additional information needed by nav_core2 and call the child isGoalReached.
Definition: local_planner_adapter.cpp:114
nav_core_adapter
Definition: costmap_adapter.h:43
nav_core_adapter::LocalPlannerAdapter::getRobotPose
bool getRobotPose(nav_2d_msgs::Pose2DStamped &pose2d)
Get the robot pose from the costmap and store as Pose2DStamped.
Definition: local_planner_adapter.cpp:173
nav_core_adapter::LocalPlannerAdapter::LocalPlannerAdapter
LocalPlannerAdapter()
Definition: local_planner_adapter.cpp:49
nav_core_adapter::LocalPlannerAdapter::tf_
TFListenerPtr tf_
Definition: local_planner_adapter.h:91
tf
odom_subscriber.h
nav_core_adapter::LocalPlannerAdapter::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition: local_planner_adapter.h:94
costmap_2d::Costmap2DROS
nav_core::BaseLocalPlanner


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