37 #ifndef BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_ 38 #define BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_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> 90 void prunePlan(
const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan);
103 const std::vector<geometry_msgs::PoseStamped>& global_plan,
106 const std::string& global_frame,
107 std::vector<geometry_msgs::PoseStamped>& transformed_plan);
118 const std::vector<geometry_msgs::PoseStamped>& global_plan,
119 const std::string& global_frame,
136 const std::vector<geometry_msgs::PoseStamped>& global_plan,
138 const std::string& global_frame,
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);
151 bool stopped(
const nav_msgs::Odometry& base_odom,
152 const double& rot_stopped_velocity,
153 const double& trans_stopped_velocity);
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 ...