Classes | Enumerations | Functions | Variables
base_local_planner Namespace Reference

Classes

class  CostmapModel
 A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using the costmap. More...
class  FootprintHelper
class  FootprintHelperTest
class  LatchedStopRotateController
class  LineIterator
class  LocalPlannerLimits
class  LocalPlannerUtil
 Helper class implementing infrastructure code many local planner implementations may need. More...
class  MapCell
 Stores path distance and goal distance information used for scoring trajectories. More...
class  MapGrid
 A grid of MapCell cells that is used to propagate path and goal distances for the trajectory controller. More...
class  MapGridCostFunction
struct  MapGridCostPoint
class  MapGridVisualizer
class  ObstacleCostFunction
 Uses costmap 2d to assign negative costs if robot footprint is in obstacle on any point of the trajectory. More...
class  OdometryHelperRos
class  OscillationCostFunction
class  PlanarLaserScan
 Stores a scan from a planar laser that can be used to clear freespace. More...
class  PointGrid
 A class that implements the WorldModel interface to provide free-space collision checks for the trajectory controller. This class stores points binned into a grid and performs point-in-polygon checks when necessary to determine the legality of a footprint at a given position/orientation. More...
class  PreferForwardCostFunction
class  SimpleScoredSamplingPlanner
 Generates a local plan using the given generator and cost functions. Assumes less cost are best, and negative costs indicate infinite costs. More...
class  SimpleTrajectoryGenerator
class  Trajectory
 Holds a trajectory generated by considering an x, y, and theta velocity. More...
class  TrajectoryCostFunction
 Provides an interface for critics of trajectories During each sampling run, a batch of many trajectories will be scored using such a cost function. The prepare method is called before each batch run, and then for each trajectory of the sampling set, score_trajectory may be called. More...
class  TrajectoryGeneratorTest
class  TrajectoryPlanner
 Computes control velocities for a robot given a costmap, a plan, and the robot's position in the world. More...
class  TrajectoryPlannerROS
 A ROS wrapper for the trajectory controller that queries the param server to construct a controller. More...
class  TrajectoryPlannerTest
class  TrajectorySampleGenerator
 Provides an interface for navigation trajectory generators. More...
class  TrajectorySearch
 Interface for modules finding a trajectory to use for navigation commands next. More...
class  VelocityIterator
class  VoxelGridModel
 A class that implements the WorldModel interface to provide grid based collision checks for the trajectory controller using a 3D voxel grid. More...
class  WavefrontMapAccessor
class  WorldModel
 An interface the trajectory controller uses to interact with the world regardless of the underlying world model. More...

Enumerations

enum  CostAggregationType { Last, Sum, Product }

Functions

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
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.
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
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.
bool isGoalReached (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2D &costmap __attribute__((unused)), 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)
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.
void publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
 Publish a plan for visualization purposes.
TrajectoryPlannerTestsetup_testclass_singleton ()
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.
 TEST (MapGridTest, initNull)
 TEST (MapGridTest, operatorBrackets)
 TEST (MapGridTest, copyConstructor)
 TEST (MapGridTest, getIndex)
 TEST (MapGridTest, reset)
 TEST (VelocityIteratorTest, testsingle)
 TEST (VelocityIteratorTest, testsingle_pos)
 TEST (VelocityIteratorTest, testsingle_neg)
 TEST (VelocityIteratorTest, test1)
 TEST (MapGridTest, properGridConstruction)
 TEST (MapGridTest, sizeCheck)
 TEST (VelocityIteratorTest, test1_pos)
 TEST (MapGridTest, adjustPlanEmpty)
 TEST (VelocityIteratorTest, test1_neg)
 TEST (MapGridTest, adjustPlan)
 TEST (VelocityIteratorTest, test3)
 TEST (VelocityIteratorTest, test4)
 TEST (FootprintHelperTest, correctFootprint)
 TEST (MapGridTest, distancePropagation)
 TEST (FootprintHelperTest, correctLineCells)
 TEST (VelocityIteratorTest, test_shifted)
 TEST (VelocityIteratorTest, test_cranky)
 TEST (TrajectoryPlannerTest, footprintObstacles)
 TEST (TrajectoryPlannerTest, checkGoalDistance)
 TEST (TrajectoryPlannerTest, checkPathDistance)
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, selects only the (first) part of the plan that is within the costmap area.

Variables

TrajectoryPlannerTesttct = NULL

Enumeration Type Documentation

when scoring a trajectory according to the values in mapgrid, we can take return the value of the last point (if no of the earlier points were in return collision), the sum for all points, or the product of all (non-zero) points

Enumerator:
Last 
Sum 
Product 

Definition at line 53 of file map_grid_cost_function.h.


Function Documentation

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

Parameters:
global_poseThe pose of the robot in the global frame
goal_xThe desired x value for the goal
goal_yThe desired y value for the goal
Returns:
angular difference

Definition at line 45 of file goal_functions.cpp.

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.

Parameters:
tfA reference to a transform listener
global_planThe plan being followed
global_frameThe global frame of the local planner
goal_posethe pose to copy into
Returns:
True if achieved, false otherwise

Definition at line 176 of file goal_functions.cpp.

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

Parameters:
global_poseThe pose of the robot in the global frame
goal_xThe desired x value for the goal
goal_yThe desired y value for the goal
Returns:
distance to goal

Definition at line 41 of file goal_functions.cpp.

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.

Parameters:
tfA reference to a transform listener
global_planThe plan being followed
costmap_rosA reference to the costmap object being used by the planner
global_frameThe global frame of the local planner
base_odomThe current odometry information for the robot
rot_stopped_velThe rotational velocity below which the robot is considered stopped
trans_stopped_velThe translational velocity below which the robot is considered stopped
xy_goal_toleranceThe translational tolerance on reaching the goal
yaw_goal_toleranceThe rotational tolerance on reaching the goal
Returns:
True if achieved, false otherwise
bool base_local_planner::isGoalReached ( const tf::TransformListener tf,
const std::vector< geometry_msgs::PoseStamped > &  global_plan,
const costmap_2d::Costmap2D &costmap   __attribute__(unused),
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 
)

Definition at line 219 of file goal_functions.cpp.

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.

Parameters:
global_poseThe pose of the robot in the global frame
planThe plan to be pruned
global_planThe plan to be pruned in the frame of the planner

Definition at line 69 of file goal_functions.cpp.

void base_local_planner::publishPlan ( const std::vector< geometry_msgs::PoseStamped > &  path,
const ros::Publisher pub 
)

Publish a plan for visualization purposes.

Parameters:
pathThe plan to publish
pubThe published to use
r,g,b,aThe color and alpha value to use when publishing

Definition at line 50 of file goal_functions.cpp.

Definition at line 171 of file utest.cpp.

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.

Parameters:
base_odomThe current odometry information for the robot
rot_stopped_velocityThe rotational velocity below which the robot is considered stopped
trans_stopped_velocityThe translational velocity below which the robot is considered stopped
Returns:
True if the robot is stopped, false otherwise

Definition at line 249 of file goal_functions.cpp.

base_local_planner::TEST ( MapGridTest  ,
initNull   
)

Definition at line 18 of file map_grid_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
operatorBrackets   
)

Definition at line 24 of file map_grid_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
copyConstructor   
)

Definition at line 30 of file map_grid_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
getIndex   
)

Definition at line 38 of file map_grid_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
reset   
)

Definition at line 43 of file map_grid_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
testsingle   
)

Definition at line 45 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
testsingle_pos   
)

Definition at line 56 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
testsingle_neg   
)

Definition at line 67 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test1   
)

Definition at line 78 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
properGridConstruction   
)

Definition at line 78 of file map_grid_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
sizeCheck   
)

Definition at line 90 of file map_grid_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test1_pos   
)

Definition at line 92 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
adjustPlanEmpty   
)

Definition at line 104 of file map_grid_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test1_neg   
)

Definition at line 106 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
adjustPlan   
)

Definition at line 113 of file map_grid_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test3   
)

Definition at line 120 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test4   
)

Definition at line 134 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( FootprintHelperTest  ,
correctFootprint   
)

Definition at line 135 of file footprint_helper_test.cpp.

base_local_planner::TEST ( MapGridTest  ,
distancePropagation   
)

Definition at line 137 of file map_grid_test.cpp.

base_local_planner::TEST ( FootprintHelperTest  ,
correctLineCells   
)

Definition at line 140 of file footprint_helper_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test_shifted   
)

Definition at line 148 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( VelocityIteratorTest  ,
test_cranky   
)

Definition at line 163 of file velocity_iterator_test.cpp.

base_local_planner::TEST ( TrajectoryPlannerTest  ,
footprintObstacles   
)

Definition at line 198 of file utest.cpp.

base_local_planner::TEST ( TrajectoryPlannerTest  ,
checkGoalDistance   
)

Definition at line 204 of file utest.cpp.

base_local_planner::TEST ( TrajectoryPlannerTest  ,
checkPathDistance   
)

Definition at line 210 of file utest.cpp.

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.

Parameters:
tfA reference to a transform listener
global_planThe plan to be transformed
robot_poseThe pose of the robot in the global frame (same as costmap)
costmapA reference to the costmap being used so the window size for transforming can be computed
global_frameThe frame to transform the plan to
transformed_planPopulated with the transformed plan

Definition at line 88 of file goal_functions.cpp.


Variable Documentation

Definition at line 169 of file utest.cpp.



base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:38