Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
00038 #define BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
00039
00040 #include <ros/ros.h>
00041 #include <tf/transform_listener.h>
00042 #include <tf/transform_datatypes.h>
00043 #include <nav_msgs/Odometry.h>
00044 #include <nav_msgs/Path.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 #include <geometry_msgs/Twist.h>
00047 #include <geometry_msgs/Point.h>
00048 #include <tf/transform_listener.h>
00049
00050 #include <string>
00051 #include <cmath>
00052
00053 #include <angles/angles.h>
00054 #include <costmap_2d/costmap_2d.h>
00055
00056 namespace base_local_planner {
00057
00065 double getGoalPositionDistance(const tf::Stamped<tf::Pose>& global_pose, double goal_x, double goal_y);
00066
00074 double getGoalOrientationAngleDifference(const tf::Stamped<tf::Pose>& global_pose, double goal_th);
00075
00082 void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub);
00083
00090 void prunePlan(const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan);
00091
00102 bool transformGlobalPlan(const tf::TransformListener& tf,
00103 const std::vector<geometry_msgs::PoseStamped>& global_plan,
00104 const tf::Stamped<tf::Pose>& global_robot_pose,
00105 const costmap_2d::Costmap2D& costmap,
00106 const std::string& global_frame,
00107 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
00108
00117 bool getGoalPose(const tf::TransformListener& tf,
00118 const std::vector<geometry_msgs::PoseStamped>& global_plan,
00119 const std::string& global_frame,
00120 tf::Stamped<tf::Pose> &goal_pose);
00121
00135 bool isGoalReached(const tf::TransformListener& tf,
00136 const std::vector<geometry_msgs::PoseStamped>& global_plan,
00137 const costmap_2d::Costmap2D& costmap,
00138 const std::string& global_frame,
00139 tf::Stamped<tf::Pose>& global_pose,
00140 const nav_msgs::Odometry& base_odom,
00141 double rot_stopped_vel, double trans_stopped_vel,
00142 double xy_goal_tolerance, double yaw_goal_tolerance);
00143
00151 bool stopped(const nav_msgs::Odometry& base_odom,
00152 const double& rot_stopped_velocity,
00153 const double& trans_stopped_velocity);
00154 };
00155 #endif