Classes | Functions
dwb_local_planner Namespace Reference

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.

Function Documentation

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.

Parameters:
trajectoryThe trajectory to search
time_offsetThe desired time_offset
Returns:
reference to the pose that is closest to the particular 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.

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

Parameters:
nhNodeHandle 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.

Parameters:
trajectoryThe trajectory with pose and time offset information
time_offsetThe desired time_offset
Returns:
New Pose2D with interpolated values
Note:
If the given time offset is outside the bounds of the trajectory, the return pose will be either the first or last pose.

Definition at line 66 of file trajectory_utils.cpp.



dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:09:38