mesh_planner_execution.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2020, Sebastian Pütz
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  * authors:
34  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
35  *
36  */
38 
39 namespace mbf_mesh_nav
40 {
42  const MeshPtr& mesh_ptr, const MoveBaseFlexConfig& config)
43  : AbstractPlannerExecution(name, planner_ptr, toAbstract(config)), mesh_ptr_(mesh_ptr)
44 {
45  ros::NodeHandle private_nh("~");
46  private_nh.param("planner_lock_mesh", lock_mesh_, true);
47 }
48 
50 {
51 }
52 
53 mbf_abstract_nav::MoveBaseFlexConfig MeshPlannerExecution::toAbstract(const MoveBaseFlexConfig& config)
54 {
55  // copy the planner-related abstract configuration common to all MBF-based
56  // navigation
57  mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
58  abstract_config.planner_frequency = config.planner_frequency;
59  abstract_config.planner_patience = config.planner_patience;
60  abstract_config.planner_max_retries = config.planner_max_retries;
61  return abstract_config;
62 }
63 
64 uint32_t MeshPlannerExecution::makePlan(const geometry_msgs::PoseStamped &start,
65  const geometry_msgs::PoseStamped &goal,
66  double tolerance,
67  std::vector<geometry_msgs::PoseStamped> &plan,
68  double &cost,
69  std::string &message)
70 {
71  ros::Time start_time = ros::Time::now();
72  uint32_t outcome = planner_->makePlan(start, goal, tolerance, plan, cost, message);
73  ROS_INFO_STREAM("Runtime of " << plugin_name_ << ":" << (ros::Time::now() - start_time).toNSec() * 1e-6 << "ms");
74  return outcome;
75 }
76 
77 } /* namespace mbf_mesh_nav */
boost::shared_ptr
mbf_mesh_nav::MeshPlannerExecution::toAbstract
mbf_abstract_nav::MoveBaseFlexConfig toAbstract(const MoveBaseFlexConfig &config)
Definition: mesh_planner_execution.cpp:53
mbf_abstract_nav::AbstractPlannerExecution::plugin_name_
std::string plugin_name_
mbf_mesh_nav::MeshPlannerExecution::makePlan
virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)
Calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance...
Definition: mesh_planner_execution.cpp:64
mesh_planner_execution.h
mbf_mesh_nav::MeshPlannerExecution::~MeshPlannerExecution
virtual ~MeshPlannerExecution()
Destructor.
Definition: mesh_planner_execution.cpp:49
mbf_mesh_nav::MeshPlannerExecution::MeshPlannerExecution
MeshPlannerExecution(const std::string name, const mbf_mesh_core::MeshPlanner::Ptr &planner_ptr, const MeshPtr &mesh, const MoveBaseFlexConfig &config)
Constructor.
Definition: mesh_planner_execution.cpp:41
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
mbf_mesh_nav
Definition: mesh_controller_execution.h:46
mbf_mesh_nav::MeshPlannerExecution::lock_mesh_
bool lock_mesh_
Whether to lock mesh before calling the planner (see issue #4 for details)
Definition: mesh_planner_execution.h:104
ros::Time
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mbf_abstract_nav::AbstractExecutionBase::start
virtual bool start()
mbf_abstract_nav::AbstractPlannerExecution::planner_
mbf_abstract_core::AbstractPlanner::Ptr planner_
ros::NodeHandle
ros::Time::now
static Time now()


mbf_mesh_nav
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:57