A class implementing a local planner using the Dynamic Window Approach. More...
#include <dwa_planner.h>
Public Member Functions | |
bool | checkTrajectory (const Eigen::Vector3f pos, const Eigen::Vector3f vel, const Eigen::Vector3f vel_samples) |
Check if a trajectory is legal for a position/velocity pair. More... | |
DWAPlanner (std::string name, base_local_planner::LocalPlannerUtil *planner_util) | |
Constructor for the planner. More... | |
base_local_planner::Trajectory | findBestPath (const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &global_vel, geometry_msgs::PoseStamped &drive_velocities) |
Given the current position and velocity of the robot, find the best trajectory to exectue. More... | |
bool | getCellCosts (int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) |
Compute the components and total cost for a map grid cell. More... | |
double | getSimPeriod () |
Get the period at which the local planner is expected to run. More... | |
void | reconfigure (DWAPlannerConfig &cfg) |
Reconfigures the trajectory planner. More... | |
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
void | updatePlanAndLocalCosts (const geometry_msgs::PoseStamped &global_pose, const std::vector< geometry_msgs::PoseStamped > &new_plan, const std::vector< geometry_msgs::Point > &footprint_spec) |
Update the cost functions before planning. More... | |
A class implementing a local planner using the Dynamic Window Approach.
Definition at line 105 of file dwa_planner.h.
dwa_local_planner::DWAPlanner::DWAPlanner | ( | std::string | name, |
base_local_planner::LocalPlannerUtil * | planner_util | ||
) |
Constructor for the planner.
name | The name of the planner |
costmap_ros | A pointer to the costmap instance the planner should use |
global_frame | the frame id of the tf frame to use |
Definition at line 153 of file dwa_planner.cpp.
bool dwa_local_planner::DWAPlanner::checkTrajectory | ( | const Eigen::Vector3f | pos, |
const Eigen::Vector3f | vel, | ||
const Eigen::Vector3f | vel_samples | ||
) |
Check if a trajectory is legal for a position/velocity pair.
pos | The robot's position |
vel | The robot's velocity |
vel_samples | The desired velocity |
This function is used when other strategies are to be applied, but the cost functions for obstacles are to be reused.
Definition at line 251 of file dwa_planner.cpp.
base_local_planner::Trajectory dwa_local_planner::DWAPlanner::findBestPath | ( | const geometry_msgs::PoseStamped & | global_pose, |
const geometry_msgs::PoseStamped & | global_vel, | ||
geometry_msgs::PoseStamped & | drive_velocities | ||
) |
Given the current position and velocity of the robot, find the best trajectory to exectue.
global_pose | The current position of the robot |
global_vel | The current velocity of the robot |
drive_velocities | The velocities to send to the robot base |
Definition at line 332 of file dwa_planner.cpp.
bool dwa_local_planner::DWAPlanner::getCellCosts | ( | int | cx, |
int | cy, | ||
float & | path_cost, | ||
float & | goal_cost, | ||
float & | occ_cost, | ||
float & | total_cost | ||
) |
Compute the components and total cost for a map grid cell.
cx | The x coordinate of the cell in the map grid |
cy | The y coordinate of the cell in the map grid |
path_cost | Will be set to the path distance component of the cost function |
goal_cost | Will be set to the goal distance component of the cost function |
occ_cost | Will be set to the costmap value of the cell |
total_cost | Will be set to the value of the overall cost function, taking into account the scaling parameters |
Definition at line 224 of file dwa_planner.cpp.
|
inline |
Get the period at which the local planner is expected to run.
Definition at line 163 of file dwa_planner.h.
void dwa_local_planner::DWAPlanner::reconfigure | ( | DWAPlannerConfig & | cfg | ) |
Reconfigures the trajectory planner.
Definition at line 87 of file dwa_planner.cpp.
bool dwa_local_planner::DWAPlanner::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | orig_global_plan | ) |
sets new plan and resets state
Definition at line 242 of file dwa_planner.cpp.
void dwa_local_planner::DWAPlanner::updatePlanAndLocalCosts | ( | const geometry_msgs::PoseStamped & | global_pose, |
const std::vector< geometry_msgs::PoseStamped > & | new_plan, | ||
const std::vector< geometry_msgs::Point > & | footprint_spec | ||
) |
Update the cost functions before planning.
global_pose | The robot's current pose |
new_plan | The new global plan |
footprint_spec | The robot's footprint |
The obstacle cost function gets the footprint. The path and goal cost functions get the global_plan The alignment cost functions get a version of the global plan that is modified based on the global_pose
Definition at line 278 of file dwa_planner.cpp.
|
private |
Definition at line 214 of file dwa_planner.h.
|
private |
Definition at line 203 of file dwa_planner.h.
|
private |
Definition at line 197 of file dwa_planner.h.
|
private |
Definition at line 193 of file dwa_planner.h.
|
private |
Definition at line 198 of file dwa_planner.h.
|
private |
Definition at line 208 of file dwa_planner.h.
|
private |
Definition at line 195 of file dwa_planner.h.
|
private |
Definition at line 212 of file dwa_planner.h.
|
private |
Definition at line 187 of file dwa_planner.h.
|
private |
Definition at line 213 of file dwa_planner.h.
|
private |
The map grid visualizer for outputting the potential field generated by the cost function.
Definition at line 205 of file dwa_planner.h.
|
private |
Definition at line 210 of file dwa_planner.h.
|
private |
Definition at line 187 of file dwa_planner.h.
|
private |
Definition at line 209 of file dwa_planner.h.
|
private |
Definition at line 211 of file dwa_planner.h.
|
private |
Definition at line 187 of file dwa_planner.h.
|
private |
Definition at line 184 of file dwa_planner.h.
|
private |
Whether or not to build and publish a PointCloud.
Definition at line 200 of file dwa_planner.h.
|
private |
Definition at line 201 of file dwa_planner.h.
|
private |
Definition at line 191 of file dwa_planner.h.
|
private |
Definition at line 217 of file dwa_planner.h.
|
private |
The number of seconds to use to compute max/min vels for dwa.
Definition at line 190 of file dwa_planner.h.
|
private |
How long before hitting something we're going to enforce that the robot stop.
Definition at line 186 of file dwa_planner.h.
|
private |
Definition at line 199 of file dwa_planner.h.
|
private |
Definition at line 215 of file dwa_planner.h.
|
private |
Definition at line 188 of file dwa_planner.h.