| Classes | |
| class | DebugDWBLocalPlanner | 
| A version of DWBLocalPlanner with ROS services for the major components.  More... | |
| class | DWBLocalPlanner | 
| Plugin-based flexible local_planner.  More... | |
| class | DWBPublisher | 
| Consolidation of all the publishing logic for the DWB Local Planner.  More... | |
| class | GoalChecker | 
| Function-object for checking whether a goal has been reached.  More... | |
| class | IllegalTrajectoryTracker | 
| class | NoLegalTrajectoriesException | 
| Thrown when all the trajectories explored are illegal.  More... | |
| class | TrajectoryCritic | 
| Evaluates a Trajectory2D to produce a score.  More... | |
| class | TrajectoryGenerator | 
| Interface for iterating through possible velocities and creating trajectories.  More... | |
| Functions | |
| std::string | getBackwardsCompatibleDefaultGenerator (const ros::NodeHandle &nh) | 
| const geometry_msgs::Pose2D & | getClosestPose (const dwb_msgs::Trajectory2D &trajectory, const double time_offset) | 
| Helper function to find a pose in the trajectory with a particular time time_offset. | |
| double | getSquareDistance (const geometry_msgs::Pose2D &pose_a, const geometry_msgs::Pose2D &pose_b) | 
| void | loadBackwardsCompatibleParameters (const ros::NodeHandle &nh) | 
| Load parameters to emulate dwa_local_planner. | |
| geometry_msgs::Pose2D | projectPose (const dwb_msgs::Trajectory2D &trajectory, const double time_offset) | 
| Helper function to create a pose with an exact time_offset by linearly interpolating between existing poses. | |
| std::string dwb_local_planner::getBackwardsCompatibleDefaultGenerator | ( | const ros::NodeHandle & | nh | ) | 
Definition at line 44 of file backwards_compatibility.cpp.
| const geometry_msgs::Pose2D & dwb_local_planner::getClosestPose | ( | const dwb_msgs::Trajectory2D & | trajectory, | 
| const double | time_offset | ||
| ) | 
Helper function to find a pose in the trajectory with a particular time time_offset.
| trajectory | The trajectory to search | 
| time_offset | The desired time_offset | 
Linearly searches through the poses. Once the poses time_offset is greater than the desired time_offset, the search ends, since the poses have increasing time_offsets.
Definition at line 40 of file trajectory_utils.cpp.
| double dwb_local_planner::getSquareDistance | ( | const geometry_msgs::Pose2D & | pose_a, | 
| const geometry_msgs::Pose2D & | pose_b | ||
| ) | 
Definition at line 382 of file dwb_local_planner.cpp.
| void dwb_local_planner::loadBackwardsCompatibleParameters | ( | const ros::NodeHandle & | nh | ) | 
Load parameters to emulate dwa_local_planner.
If no critic parameters are specified, this function should be called to load/move parameters that will emulate the behavior of dwa_local_planner
| nh | NodeHandle to load parameters from | 
Definition at line 58 of file backwards_compatibility.cpp.
| geometry_msgs::Pose2D dwb_local_planner::projectPose | ( | const dwb_msgs::Trajectory2D & | trajectory, | 
| const double | time_offset | ||
| ) | 
Helper function to create a pose with an exact time_offset by linearly interpolating between existing poses.
| trajectory | The trajectory with pose and time offset information | 
| time_offset | The desired time_offset | 
Definition at line 66 of file trajectory_utils.cpp.