Public Member Functions | Private Attributes
dwa_local_planner::DWAPlanner Class Reference

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

#include <dwa_planner.h>

List of all members.

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::LocalPlannerUtilplanner_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_

Detailed Description

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

Definition at line 68 of file dwa_planner.h.


Constructor & Destructor Documentation

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 112 of file dwa_planner.cpp.

Destructor for the planner.

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

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 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.

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 172 of file dwa_planner.cpp.

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

Returns:
The simulation period

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.

Parameters:
new_planThe new global plan

Definition at line 227 of file dwa_planner.cpp.


Member Data Documentation

Definition at line 172 of file dwa_planner.h.

Definition at line 158 of file dwa_planner.h.

Definition at line 154 of file dwa_planner.h.

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.

Definition at line 148 of file dwa_planner.h.

Definition at line 167 of file dwa_planner.h.

Definition at line 169 of file dwa_planner.h.

Definition at line 148 of file dwa_planner.h.

Definition at line 145 of file dwa_planner.h.

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.

Definition at line 174 of file dwa_planner.h.

The number of seconds to use to compute max/min vels for dwa.

Definition at line 151 of file dwa_planner.h.

How long before hitting something we're going to enforce that the robot stop.

Definition at line 147 of file dwa_planner.h.

Definition at line 159 of file dwa_planner.h.

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.


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


dwa_local_planner
Author(s): Eitan Marder-Eppstein
autogenerated on Mon Oct 6 2014 02:47:33