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. | |
DWAPlanner (std::string name, base_local_planner::LocalPlannerUtil *planner_util) | |
Constructor for the planner. | |
base_local_planner::Trajectory | findBestPath (tf::Stamped< tf::Pose > global_pose, tf::Stamped< tf::Pose > global_vel, tf::Stamped< tf::Pose > &drive_velocities, std::vector< geometry_msgs::Point > footprint_spec) |
Given the current position and velocity of the robot, find the best trajectory to exectue. | |
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. | |
double | getSimPeriod () |
Get the period at which the local planner is expected to run. | |
void | reconfigure (DWAPlannerConfig &cfg) |
Reconfigures the trajectory planner. | |
bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &orig_global_plan) |
void | updatePlanAndLocalCosts (tf::Stamped< tf::Pose > global_pose, const std::vector< geometry_msgs::PoseStamped > &new_plan) |
Take in a new global plan for the local planner to follow, and adjust local costmaps. | |
~DWAPlanner () | |
Destructor for the planner. | |
Private Attributes | |
base_local_planner::MapGridCostFunction | alignment_costs_ |
boost::mutex | configuration_mutex_ |
double | forward_point_distance_ |
double | gdist_scale_ |
base_local_planner::SimpleTrajectoryGenerator | generator_ |
std::vector < geometry_msgs::PoseStamped > | global_plan_ |
base_local_planner::MapGridCostFunction | goal_costs_ |
base_local_planner::MapGridCostFunction | goal_front_costs_ |
base_local_planner::MapGridVisualizer | map_viz_ |
The map grid visualizer for outputting the potential field generated by the cost function. | |
base_local_planner::ObstacleCostFunction | obstacle_costs_ |
double | occdist_scale_ |
base_local_planner::OscillationCostFunction | oscillation_costs_ |
base_local_planner::MapGridCostFunction | path_costs_ |
double | pdist_scale_ |
base_local_planner::LocalPlannerUtil * | planner_util_ |
bool | publish_cost_grid_pc_ |
Whether or not to build and publish a PointCloud. | |
base_local_planner::Trajectory | result_traj_ |
base_local_planner::SimpleScoredSamplingPlanner | scored_sampling_planner_ |
double | sim_period_ |
The number of seconds to use to compute max/min vels for dwa. | |
double | stop_time_buffer_ |
How long before hitting something we're going to enforce that the robot stop. | |
pcl::PointCloud < base_local_planner::MapGridCostPoint > | traj_cloud_ |
pcl_ros::Publisher < base_local_planner::MapGridCostPoint > | traj_cloud_pub_ |
Eigen::Vector3f | vsamples_ |
A class implementing a local planner using the Dynamic Window Approach.
Definition at line 68 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 112 of file dwa_planner.cpp.
dwa_local_planner::DWAPlanner::~DWAPlanner | ( | ) | [inline] |
Destructor for the planner.
Definition at line 81 of file dwa_planner.h.
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 200 of file dwa_planner.cpp.
base_local_planner::Trajectory dwa_local_planner::DWAPlanner::findBestPath | ( | tf::Stamped< tf::Pose > | global_pose, |
tf::Stamped< tf::Pose > | global_vel, | ||
tf::Stamped< tf::Pose > & | drive_velocities, | ||
std::vector< geometry_msgs::Point > | footprint_spec | ||
) |
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 278 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 172 of file dwa_planner.cpp.
double dwa_local_planner::DWAPlanner::getSimPeriod | ( | ) | [inline] |
Get the period at which the local planner is expected to run.
Definition at line 124 of file dwa_planner.h.
void dwa_local_planner::DWAPlanner::reconfigure | ( | DWAPlannerConfig & | cfg | ) |
Reconfigures the trajectory planner.
Definition at line 48 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 191 of file dwa_planner.cpp.
void dwa_local_planner::DWAPlanner::updatePlanAndLocalCosts | ( | tf::Stamped< tf::Pose > | global_pose, |
const std::vector< geometry_msgs::PoseStamped > & | new_plan | ||
) |
Take in a new global plan for the local planner to follow, and adjust local costmaps.
new_plan | The new global plan |
Definition at line 227 of file dwa_planner.cpp.
Definition at line 172 of file dwa_planner.h.
boost::mutex dwa_local_planner::DWAPlanner::configuration_mutex_ [private] |
Definition at line 158 of file dwa_planner.h.
double dwa_local_planner::DWAPlanner::forward_point_distance_ [private] |
Definition at line 154 of file dwa_planner.h.
double dwa_local_planner::DWAPlanner::gdist_scale_ [private] |
Definition at line 148 of file dwa_planner.h.
Definition at line 166 of file dwa_planner.h.
std::vector<geometry_msgs::PoseStamped> dwa_local_planner::DWAPlanner::global_plan_ [private] |
Definition at line 156 of file dwa_planner.h.
Definition at line 170 of file dwa_planner.h.
Definition at line 171 of file dwa_planner.h.
The map grid visualizer for outputting the potential field generated by the cost function.
Definition at line 163 of file dwa_planner.h.
Definition at line 168 of file dwa_planner.h.
double dwa_local_planner::DWAPlanner::occdist_scale_ [private] |
Definition at line 148 of file dwa_planner.h.
base_local_planner::OscillationCostFunction dwa_local_planner::DWAPlanner::oscillation_costs_ [private] |
Definition at line 167 of file dwa_planner.h.
Definition at line 169 of file dwa_planner.h.
double dwa_local_planner::DWAPlanner::pdist_scale_ [private] |
Definition at line 148 of file dwa_planner.h.
Definition at line 145 of file dwa_planner.h.
bool dwa_local_planner::DWAPlanner::publish_cost_grid_pc_ [private] |
Whether or not to build and publish a PointCloud.
Definition at line 161 of file dwa_planner.h.
Definition at line 152 of file dwa_planner.h.
base_local_planner::SimpleScoredSamplingPlanner dwa_local_planner::DWAPlanner::scored_sampling_planner_ [private] |
Definition at line 174 of file dwa_planner.h.
double dwa_local_planner::DWAPlanner::sim_period_ [private] |
The number of seconds to use to compute max/min vels for dwa.
Definition at line 151 of file dwa_planner.h.
double dwa_local_planner::DWAPlanner::stop_time_buffer_ [private] |
How long before hitting something we're going to enforce that the robot stop.
Definition at line 147 of file dwa_planner.h.
pcl::PointCloud<base_local_planner::MapGridCostPoint> dwa_local_planner::DWAPlanner::traj_cloud_ [private] |
Definition at line 159 of file dwa_planner.h.
pcl_ros::Publisher<base_local_planner::MapGridCostPoint> dwa_local_planner::DWAPlanner::traj_cloud_pub_ [private] |
Definition at line 160 of file dwa_planner.h.
Eigen::Vector3f dwa_local_planner::DWAPlanner::vsamples_ [private] |
Definition at line 149 of file dwa_planner.h.