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 #include <costmap_2d/costmap_2d_ros.h>
00056
00057 namespace base_local_planner {
00065 double distance(double x1, double y1, double x2, double y2);
00066
00075 bool goalPositionReached(const tf::Stamped<tf::Pose>& global_pose, double goal_x, double goal_y, double xy_goal_tolerance);
00076
00085 bool goalOrientationReached(const tf::Stamped<tf::Pose>& global_pose, double goal_th, double yaw_goal_tolerance);
00086
00093 void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub, double r, double g, double b, double a);
00094
00101 void prunePlan(const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan);
00102
00111 bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
00112 const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame,
00113 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
00114
00128 bool isGoalReached(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan,
00129 const costmap_2d::Costmap2DROS& costmap_ros, const std::string& global_frame,
00130 const nav_msgs::Odometry& base_odom, double rot_stopped_vel, double trans_stopped_vel,
00131 double xy_goal_tolerance, double yaw_goal_tolerance);
00132
00140 bool stopped(const nav_msgs::Odometry& base_odom,
00141 const double& rot_stopped_velocity, const double& trans_stopped_velocity);
00142 };
00143 #endif