Public Member Functions | Private Attributes | List of all members
dwa_local_planner::DWAPlanner Class Reference

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 (tf::Stamped< tf::Pose > global_pose, tf::Stamped< tf::Pose > global_vel, tf::Stamped< tf::Pose > &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 (tf::Stamped< tf::Pose > 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...
 
 ~DWAPlanner ()
 Destructor for the planner. More...
 

Private Attributes

base_local_planner::MapGridCostFunction alignment_costs_
 
double cheat_factor_
 
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. More...
 
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::LocalPlannerUtilplanner_util_
 
bool publish_cost_grid_pc_
 Whether or not to build and publish a PointCloud. More...
 
bool publish_traj_pc_
 
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. More...
 
double stop_time_buffer_
 How long before hitting something we're going to enforce that the robot stop. More...
 
pcl::PointCloud< base_local_planner::MapGridCostPoint > * traj_cloud_
 
pcl_ros::Publisher< base_local_planner::MapGridCostPointtraj_cloud_pub_
 
base_local_planner::TwirlingCostFunction twirling_costs_
 
Eigen::Vector3f vsamples_
 

Detailed Description

A class implementing a local planner using the Dynamic Window Approach.

Definition at line 71 of file dwa_planner.h.

Constructor & Destructor Documentation

dwa_local_planner::DWAPlanner::DWAPlanner ( std::string  name,
base_local_planner::LocalPlannerUtil planner_util 
)

Constructor for the planner.

Parameters
nameThe name of the planner
costmap_rosA pointer to the costmap instance the planner should use
global_framethe frame id of the tf frame to use

Definition at line 118 of file dwa_planner.cpp.

dwa_local_planner::DWAPlanner::~DWAPlanner ( )
inline

Destructor for the planner.

Definition at line 84 of file dwa_planner.h.

Member Function Documentation

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.

Parameters
posThe robot's position
velThe robot's velocity
vel_samplesThe desired velocity
Returns
True if the trajectory is valid, false otherwise

This function is used when other strategies are to be applied, but the cost functions for obstacles are to be reused.

Definition at line 216 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 
)

Given the current position and velocity of the robot, find the best trajectory to exectue.

Parameters
global_poseThe current position of the robot
global_velThe current velocity of the robot
drive_velocitiesThe velocities to send to the robot base
Returns
The highest scoring trajectory. A cost >= 0 means the trajectory is legal to execute.

Definition at line 298 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.

Parameters
cxThe x coordinate of the cell in the map grid
cyThe y coordinate of the cell in the map grid
path_costWill be set to the path distance component of the cost function
goal_costWill be set to the goal distance component of the cost function
occ_costWill be set to the costmap value of the cell
total_costWill be set to the value of the overall cost function, taking into account the scaling parameters
Returns
True if the cell is traversible and therefore a legal location for the robot to move to

Definition at line 188 of file dwa_planner.cpp.

double dwa_local_planner::DWAPlanner::getSimPeriod ( )
inline

Get the period at which the local planner is expected to run.

Returns
The simulation period

Definition at line 134 of file dwa_planner.h.

void dwa_local_planner::DWAPlanner::reconfigure ( DWAPlannerConfig &  cfg)

Reconfigures the trajectory planner.

Definition at line 52 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 207 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,
const std::vector< geometry_msgs::Point > &  footprint_spec 
)

Update the cost functions before planning.

Parameters
global_poseThe robot's current pose
new_planThe new global plan
footprint_specThe 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 243 of file dwa_planner.cpp.

Member Data Documentation

base_local_planner::MapGridCostFunction dwa_local_planner::DWAPlanner::alignment_costs_
private

Definition at line 185 of file dwa_planner.h.

double dwa_local_planner::DWAPlanner::cheat_factor_
private

Definition at line 174 of file dwa_planner.h.

boost::mutex dwa_local_planner::DWAPlanner::configuration_mutex_
private

Definition at line 168 of file dwa_planner.h.

double dwa_local_planner::DWAPlanner::forward_point_distance_
private

Definition at line 164 of file dwa_planner.h.

double dwa_local_planner::DWAPlanner::gdist_scale_
private

Definition at line 158 of file dwa_planner.h.

base_local_planner::SimpleTrajectoryGenerator dwa_local_planner::DWAPlanner::generator_
private

Definition at line 179 of file dwa_planner.h.

std::vector<geometry_msgs::PoseStamped> dwa_local_planner::DWAPlanner::global_plan_
private

Definition at line 166 of file dwa_planner.h.

base_local_planner::MapGridCostFunction dwa_local_planner::DWAPlanner::goal_costs_
private

Definition at line 183 of file dwa_planner.h.

base_local_planner::MapGridCostFunction dwa_local_planner::DWAPlanner::goal_front_costs_
private

Definition at line 184 of file dwa_planner.h.

base_local_planner::MapGridVisualizer dwa_local_planner::DWAPlanner::map_viz_
private

The map grid visualizer for outputting the potential field generated by the cost function.

Definition at line 176 of file dwa_planner.h.

base_local_planner::ObstacleCostFunction dwa_local_planner::DWAPlanner::obstacle_costs_
private

Definition at line 181 of file dwa_planner.h.

double dwa_local_planner::DWAPlanner::occdist_scale_
private

Definition at line 158 of file dwa_planner.h.

base_local_planner::OscillationCostFunction dwa_local_planner::DWAPlanner::oscillation_costs_
private

Definition at line 180 of file dwa_planner.h.

base_local_planner::MapGridCostFunction dwa_local_planner::DWAPlanner::path_costs_
private

Definition at line 182 of file dwa_planner.h.

double dwa_local_planner::DWAPlanner::pdist_scale_
private

Definition at line 158 of file dwa_planner.h.

base_local_planner::LocalPlannerUtil* dwa_local_planner::DWAPlanner::planner_util_
private

Definition at line 155 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 171 of file dwa_planner.h.

bool dwa_local_planner::DWAPlanner::publish_traj_pc_
private

Definition at line 172 of file dwa_planner.h.

base_local_planner::Trajectory dwa_local_planner::DWAPlanner::result_traj_
private

Definition at line 162 of file dwa_planner.h.

base_local_planner::SimpleScoredSamplingPlanner dwa_local_planner::DWAPlanner::scored_sampling_planner_
private

Definition at line 188 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 161 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 157 of file dwa_planner.h.

pcl::PointCloud<base_local_planner::MapGridCostPoint>* dwa_local_planner::DWAPlanner::traj_cloud_
private

Definition at line 169 of file dwa_planner.h.

pcl_ros::Publisher<base_local_planner::MapGridCostPoint> dwa_local_planner::DWAPlanner::traj_cloud_pub_
private

Definition at line 170 of file dwa_planner.h.

base_local_planner::TwirlingCostFunction dwa_local_planner::DWAPlanner::twirling_costs_
private

Definition at line 186 of file dwa_planner.h.

Eigen::Vector3f dwa_local_planner::DWAPlanner::vsamples_
private

Definition at line 159 of file dwa_planner.h.


The documentation for this class was generated from the following files:


dwa_local_planner
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:35