goal_functions.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, 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 #ifndef BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
38 #define BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
39 
40 #include <ros/ros.h>
41 #include <tf/transform_listener.h>
42 #include <tf/transform_datatypes.h>
43 #include <nav_msgs/Odometry.h>
44 #include <nav_msgs/Path.h>
45 #include <geometry_msgs/PoseStamped.h>
46 #include <geometry_msgs/Twist.h>
47 #include <geometry_msgs/Point.h>
48 #include <tf/transform_listener.h>
49 
50 #include <string>
51 #include <cmath>
52 
53 #include <angles/angles.h>
54 #include <costmap_2d/costmap_2d.h>
55 
56 namespace base_local_planner {
57 
65  double getGoalPositionDistance(const tf::Stamped<tf::Pose>& global_pose, double goal_x, double goal_y);
66 
74  double getGoalOrientationAngleDifference(const tf::Stamped<tf::Pose>& global_pose, double goal_th);
75 
82  void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub);
83 
90  void prunePlan(const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan);
91 
103  const std::vector<geometry_msgs::PoseStamped>& global_plan,
104  const tf::Stamped<tf::Pose>& global_robot_pose,
105  const costmap_2d::Costmap2D& costmap,
106  const std::string& global_frame,
107  std::vector<geometry_msgs::PoseStamped>& transformed_plan);
108 
118  const std::vector<geometry_msgs::PoseStamped>& global_plan,
119  const std::string& global_frame,
120  tf::Stamped<tf::Pose> &goal_pose);
121 
136  const std::vector<geometry_msgs::PoseStamped>& global_plan,
137  const costmap_2d::Costmap2D& costmap,
138  const std::string& global_frame,
139  tf::Stamped<tf::Pose>& global_pose,
140  const nav_msgs::Odometry& base_odom,
141  double rot_stopped_vel, double trans_stopped_vel,
142  double xy_goal_tolerance, double yaw_goal_tolerance);
143 
151  bool stopped(const nav_msgs::Odometry& base_odom,
152  const double& rot_stopped_velocity,
153  const double& trans_stopped_velocity);
154 };
155 #endif
bool getGoalPose(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, tf::Stamped< tf::Pose > &goal_pose)
Returns last pose in plan.
bool isGoalReached(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, tf::Stamped< tf::Pose > &global_pose, const nav_msgs::Odometry &base_odom, double rot_stopped_vel, double trans_stopped_vel, double xy_goal_tolerance, double yaw_goal_tolerance)
Check if the goal pose has been achieved.
double getGoalPositionDistance(const tf::Stamped< tf::Pose > &global_pose, double goal_x, double goal_y)
return squared distance to check if the goal position has been achieved
void prunePlan(const tf::Stamped< tf::Pose > &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.
bool stopped(const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
Check whether the robot is stopped or not.
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &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...
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
Publish a plan for visualization purposes.
double getGoalOrientationAngleDifference(const tf::Stamped< tf::Pose > &global_pose, double goal_th)
return angle difference to goal to check if the goal orientation has been achieved ...


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Thu Jan 21 2021 04:05:49