local_planner_util.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  *********************************************************************/
37 
39 
41 
42 namespace base_local_planner {
43 
46  costmap_2d::Costmap2D* costmap,
47  std::string global_frame) {
48  if(!initialized_) {
49  tf_ = tf;
50  costmap_ = costmap;
51  global_frame_ = global_frame;
52  initialized_ = true;
53  }
54  else{
55  ROS_WARN("Planner utils have already been initialized, doing nothing.");
56  }
57 }
58 
59 void LocalPlannerUtil::reconfigureCB(LocalPlannerLimits &config, bool restore_defaults)
60 {
61  if(setup_ && restore_defaults) {
62  config = default_limits_;
63  }
64 
65  if(!setup_) {
66  default_limits_ = config;
67  setup_ = true;
68  }
69  boost::mutex::scoped_lock l(limits_configuration_mutex_);
70  limits_ = LocalPlannerLimits(config);
71 }
72 
74  return costmap_;
75 }
76 
77 LocalPlannerLimits LocalPlannerUtil::getCurrentLimits() {
78  boost::mutex::scoped_lock l(limits_configuration_mutex_);
79  return limits_;
80 }
81 
82 
83 bool LocalPlannerUtil::getGoal(geometry_msgs::PoseStamped& goal_pose) {
84  //we assume the global goal is the last point in the global plan
88  goal_pose);
89 }
90 
91 bool LocalPlannerUtil::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan) {
92  if(!initialized_){
93  ROS_ERROR("Planner utils have not been initialized, please call initialize() first");
94  return false;
95  }
96 
97  //reset the global plan
98  global_plan_.clear();
99 
100  global_plan_ = orig_global_plan;
101 
102  return true;
103 }
104 
105 bool LocalPlannerUtil::getLocalPlan(const geometry_msgs::PoseStamped& global_pose, std::vector<geometry_msgs::PoseStamped>& transformed_plan) {
106  //get the global plan in our frame
108  *tf_,
109  global_plan_,
110  global_pose,
111  *costmap_,
113  transformed_plan)) {
114  ROS_WARN("Could not transform the global plan to the frame of the controller");
115  return false;
116  }
117 
118  //now we'll prune the plan based on the position of the robot
119  if(limits_.prune_plan) {
120  base_local_planner::prunePlan(global_pose, transformed_plan, global_plan_);
121  }
122  return true;
123 }
124 
125 
126 
127 
128 } // namespace
base_local_planner::LocalPlannerUtil::setup_
bool setup_
Definition: local_planner_util.h:107
base_local_planner::LocalPlannerUtil::limits_configuration_mutex_
boost::mutex limits_configuration_mutex_
Definition: local_planner_util.h:106
base_local_planner::LocalPlannerUtil::getLocalPlan
bool getLocalPlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
Definition: local_planner_util.cpp:140
base_local_planner::LocalPlannerLimits::prune_plan
bool prune_plan
Definition: local_planner_limits.h:123
base_local_planner::getGoalPose
bool getGoalPose(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, geometry_msgs::PoseStamped &goal_pose)
Returns last pose in plan.
Definition: goal_functions.cpp:174
base_local_planner::LocalPlannerUtil::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Definition: local_planner_util.cpp:126
base_local_planner::transformGlobalPlan
bool transformGlobalPlan(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &global_robot_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
Transforms the global plan of the robot from the planner frame to the frame of the costmap,...
Definition: goal_functions.cpp:96
costmap_2d::Costmap2D
base_local_planner::LocalPlannerUtil::limits_
LocalPlannerLimits limits_
Definition: local_planner_util.h:109
base_local_planner::LocalPlannerUtil::reconfigureCB
void reconfigureCB(LocalPlannerLimits &config, bool restore_defaults)
Callback to update the local planner's parameters.
Definition: local_planner_util.cpp:94
local_planner_util.h
goal_functions.h
base_local_planner::LocalPlannerUtil::getCostmap
costmap_2d::Costmap2D * getCostmap()
Definition: local_planner_util.cpp:108
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
base_local_planner::LocalPlannerUtil::costmap_
costmap_2d::Costmap2D * costmap_
Definition: local_planner_util.h:99
base_local_planner::LocalPlannerUtil::initialize
void initialize(tf2_ros::Buffer *tf, costmap_2d::Costmap2D *costmap, std::string global_frame)
Definition: local_planner_util.cpp:79
base_local_planner::LocalPlannerUtil::default_limits_
LocalPlannerLimits default_limits_
Definition: local_planner_util.h:108
base_local_planner::prunePlan
void prunePlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
Trim off parts of the global plan that are far enough behind the robot.
Definition: goal_functions.cpp:77
base_local_planner::LocalPlannerUtil::initialized_
bool initialized_
Definition: local_planner_util.h:110
base_local_planner::LocalPlannerUtil::global_frame_
std::string global_frame_
Definition: local_planner_util.h:97
ROS_ERROR
#define ROS_ERROR(...)
base_local_planner::LocalPlannerUtil::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: local_planner_util.h:103
base_local_planner::LocalPlannerUtil::tf_
tf2_ros::Buffer * tf_
Definition: local_planner_util.h:100
base_local_planner::LocalPlannerUtil::getCurrentLimits
LocalPlannerLimits getCurrentLimits()
Definition: local_planner_util.cpp:112
tf
base_local_planner::LocalPlannerUtil::getGoal
bool getGoal(geometry_msgs::PoseStamped &goal_pose)
Definition: local_planner_util.cpp:118
base_local_planner
Definition: costmap_model.h:44


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24