37 #ifndef DWA_LOCAL_PLANNER_DWA_PLANNER_H_ 38 #define DWA_LOCAL_PLANNER_DWA_PLANNER_H_ 44 #include <dwa_local_planner/DWAPlannerConfig.h> 63 #include <nav_msgs/Path.h> 93 const Eigen::Vector3f pos,
94 const Eigen::Vector3f vel,
95 const Eigen::Vector3f vel_samples);
105 const geometry_msgs::PoseStamped& global_pose,
106 const geometry_msgs::PoseStamped& global_vel,
107 geometry_msgs::PoseStamped& drive_velocities);
121 const std::vector<geometry_msgs::PoseStamped>& new_plan,
122 const std::vector<geometry_msgs::Point>& footprint_spec);
140 bool getCellCosts(
int cx,
int cy,
float &path_cost,
float &goal_cost,
float &occ_cost,
float &total_cost);
145 bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
void reconfigure(DWAPlannerConfig &cfg)
Reconfigures the trajectory planner.
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
base_local_planner::MapGridCostFunction goal_front_costs_
base_local_planner::MapGridCostFunction goal_costs_
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
base_local_planner::OscillationCostFunction oscillation_costs_
double goal_distance_bias_
base_local_planner::LocalPlannerUtil * planner_util_
bool publish_cost_grid_pc_
Whether or not to build and publish a PointCloud.
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.
base_local_planner::TwirlingCostFunction twirling_costs_
double getSimPeriod()
Get the period at which the local planner is expected to run.
std::vector< geometry_msgs::PoseStamped > global_plan_
base_local_planner::MapGridCostFunction alignment_costs_
DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util)
Constructor for the planner.
boost::mutex configuration_mutex_
base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_
Eigen::Vector3f vsamples_
A class implementing a local planner using the Dynamic Window Approach.
ros::Publisher traj_cloud_pub_
base_local_planner::ObstacleCostFunction obstacle_costs_
base_local_planner::MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
base_local_planner::MapGridCostFunction path_costs_
double path_distance_bias_
double forward_point_distance_
base_local_planner::Trajectory result_traj_
base_local_planner::SimpleTrajectoryGenerator generator_
double stop_time_buffer_
How long before hitting something we're going to enforce that the robot stop.
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.
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...
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.