Namespaces | Functions
goal_functions.h File Reference
#include <ros/ros.h>
#include <tf/transform_listener.h>
#include <tf/transform_datatypes.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Point.h>
#include <string>
#include <cmath>
#include <angles/angles.h>
#include <costmap_2d/costmap_2d.h>
Include dependency graph for goal_functions.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 base_local_planner
 

Functions

double base_local_planner::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 More...
 
bool base_local_planner::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. More...
 
double base_local_planner::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 More...
 
bool base_local_planner::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. More...
 
void base_local_planner::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. More...
 
void base_local_planner::publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
 Publish a plan for visualization purposes. More...
 
bool base_local_planner::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. More...
 
bool base_local_planner::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, selects only the (first) part of the plan that is within the costmap area. More...
 


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