wrapper_local_planner.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * wrapper_local_planner.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
42 
43 namespace mbf_nav_core_wrapper
44 {
45 
47  const geometry_msgs::PoseStamped &robot_pose,
48  const geometry_msgs::TwistStamped &robot_velocity,
49  geometry_msgs::TwistStamped &cmd_vel,
50  std::string &message)
51 {
52  bool success = nav_core_plugin_->computeVelocityCommands(cmd_vel.twist);
53  message = success ? "Goal reached" : "Controller failed";
54  return success ? 0 : 100; // SUCCESS | FAILURE
55 }
56 
58 {
59  return nav_core_plugin_->isGoalReached();
60 }
61 
62 bool WrapperLocalPlanner::isGoalReached(double xy_tolerance, double yaw_tolerance)
63 {
64  return isGoalReached();
65 }
66 
67 bool WrapperLocalPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped> &plan)
68 {
69  return nav_core_plugin_->setPlan(plan);
70 }
71 
73 {
74  ROS_WARN_STREAM("The cancel method is not implemented. "
75  "Note: you are running a nav_core based plugin, "
76  "which is wrapped into the MBF interface.");
77  return false;
78 }
79 
80 void WrapperLocalPlanner::initialize(std::string name,
81  TF *tf,
82  costmap_2d::Costmap2DROS *costmap_ros)
83 {
84  nav_core_plugin_->initialize(name, tf, costmap_ros);
85 }
86 
88  : nav_core_plugin_(plugin)
89 {}
90 
92 {}
93 
94 }; /* namespace mbf_abstract_core */
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Set the plan that the local planner is following.
virtual ~WrapperLocalPlanner()
Virtual destructor for the interface.
WrapperLocalPlanner(boost::shared_ptr< nav_core::BaseLocalPlanner >plugin)
Public constructor used for handling a nav_core-based plugin.
virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped &robot_pose, const geometry_msgs::TwistStamped &robot_velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
virtual bool isGoalReached()
Check if the goal pose has been achieved by the local planner.
virtual void initialize(std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the local planner.
boost::shared_ptr< nav_core::BaseLocalPlanner > nav_core_plugin_
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
#define ROS_WARN_STREAM(args)


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Fri Nov 6 2020 03:56:29