Go to the documentation of this file.
37 #ifndef BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
38 #define BASE_LOCAL_PLANNER_GOAL_FUNCTIONS_H_
41 #include <nav_msgs/Odometry.h>
42 #include <nav_msgs/Path.h>
43 #include <geometry_msgs/PoseStamped.h>
44 #include <geometry_msgs/Twist.h>
45 #include <geometry_msgs/Point.h>
46 #include <tf2_ros/buffer.h>
51 #include <angles/angles.h>
110 const geometry_msgs::PoseStamped& global_robot_pose,
126 geometry_msgs::PoseStamped &goal_pose);
145 geometry_msgs::PoseStamped& global_pose,
146 const nav_msgs::Odometry& base_odom,
147 double rot_stopped_vel,
double trans_stopped_vel,
148 double xy_goal_tolerance,
double yaw_goal_tolerance);
157 bool stopped(
const nav_msgs::Odometry& base_odom,
158 const double& rot_stopped_velocity,
159 const double& trans_stopped_velocity);
168 bool stopped(
const geometry_msgs::PoseStamped& robot_vel,
169 const double& rot_stopped_velocity,
170 const double& trans_stopped_velocity);
bool isGoalReached(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, geometry_msgs::PoseStamped &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.
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.
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,...
double getGoalPositionDistance(const geometry_msgs::PoseStamped &global_pose, double goal_x, double goal_y)
return squared distance to check if the goal position has been achieved
double getGoalOrientationAngleDifference(const geometry_msgs::PoseStamped &global_pose, double goal_th)
return angle difference to goal to check if the goal orientation has been achieved
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.
void planFromLookahead(const std::vector< geometry_msgs::PoseStamped > &plan, double lookahead, std::vector< geometry_msgs::PoseStamped > &new_plan)
Filters the plan from the lookahead distance up to the end.
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
Publish a plan for visualization purposes.
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.