costmap_controller_execution.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  * costmap_controller_execution.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
41 
42 namespace mbf_costmap_nav
43 {
44 
46  const std::string name,
47  const mbf_costmap_core::CostmapController::Ptr &controller_ptr,
48  const ros::Publisher& vel_pub,
49  const ros::Publisher& goal_pub,
50  const TFPtr &tf_listener_ptr,
51  CostmapPtr &costmap_ptr,
52  const MoveBaseFlexConfig &config,
53  boost::function<void()> setup_fn,
54  boost::function<void()> cleanup_fn)
55  : AbstractControllerExecution(name, controller_ptr, vel_pub, goal_pub, tf_listener_ptr,
56  toAbstract(config), setup_fn, cleanup_fn),
57  costmap_ptr_(costmap_ptr)
58 {
59  ros::NodeHandle private_nh("~");
60  private_nh.param("controller_lock_costmap", lock_costmap_, true);
61 }
62 
64 {
65 }
66 
67 mbf_abstract_nav::MoveBaseFlexConfig CostmapControllerExecution::toAbstract(const MoveBaseFlexConfig &config)
68 {
69  // copy the controller-related abstract configuration common to all MBF-based navigation
70  mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
71  abstract_config.controller_frequency = config.controller_frequency;
72  abstract_config.controller_patience = config.controller_patience;
73  abstract_config.controller_max_retries = config.controller_max_retries;
74  abstract_config.oscillation_timeout = config.oscillation_timeout;
75  abstract_config.oscillation_distance = config.oscillation_distance;
76  return abstract_config;
77 }
78 
80  const geometry_msgs::PoseStamped& robot_pose,
81  const geometry_msgs::TwistStamped& robot_velocity,
82  geometry_msgs::TwistStamped& vel_cmd,
83  std::string& message)
84 {
85  // Lock the costmap while planning, but following issue #4, we allow to move the responsibility to the planner itself
86  if (lock_costmap_)
87  {
88  boost::lock_guard<costmap_2d::Costmap2D::mutex_t> lock(*(costmap_ptr_->getCostmap()->getMutex()));
89  return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);
90  }
91  return controller_->computeVelocityCommands(robot_pose, robot_velocity, vel_cmd, message);
92 }
93 
94 } /* namespace mbf_costmap_nav */
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
CostmapPtr & costmap_ptr_
costmap for 2d navigation planning
bool param(const std::string &param_name, T &param_val, const T &default_val) const
mbf_abstract_core::AbstractController::Ptr controller_
bool lock_costmap_
Whether to lock costmap before calling the controller (see issue #4 for details)
CostmapControllerExecution(const std::string name, const mbf_costmap_core::CostmapController::Ptr &controller_ptr, const ros::Publisher &vel_pub, const ros::Publisher &goal_pub, const TFPtr &tf_listener_ptr, CostmapPtr &costmap_ptr, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
Constructor.
virtual uint32_t computeVelocityCmd(const geometry_msgs::PoseStamped &robot_pose, const geometry_msgs::TwistStamped &robot_velocity, geometry_msgs::TwistStamped &vel_cmd, std::string &message)
Request plugin for a new velocity command. We override this method so we can lock the local costmap b...


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:40