dwa_planner.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2009, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #ifndef DWA_LOCAL_PLANNER_DWA_PLANNER_H_
00038 #define DWA_LOCAL_PLANNER_DWA_PLANNER_H_
00039 
00040 #include <vector>
00041 #include <Eigen/Core>
00042 
00043 
00044 #include <dwa_local_planner/DWAPlannerConfig.h>
00045 
00046 //for creating a local cost grid
00047 #include <base_local_planner/map_grid_visualizer.h>
00048 #include <pcl_ros/publisher.h>
00049 
00050 //for obstacle data access
00051 #include <costmap_2d/costmap_2d.h>
00052 
00053 #include <base_local_planner/trajectory.h>
00054 #include <base_local_planner/local_planner_limits.h>
00055 #include <base_local_planner/local_planner_util.h>
00056 #include <base_local_planner/simple_trajectory_generator.h>
00057 
00058 #include <base_local_planner/oscillation_cost_function.h>
00059 #include <base_local_planner/map_grid_cost_function.h>
00060 #include <base_local_planner/obstacle_cost_function.h>
00061 #include <base_local_planner/simple_scored_sampling_planner.h>
00062 
00063 namespace dwa_local_planner {
00068   class DWAPlanner {
00069     public:
00076       DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util);
00077 
00081       ~DWAPlanner() {}
00082 
00086       void reconfigure(DWAPlannerConfig &cfg);
00087 
00095       bool checkTrajectory(
00096           const Eigen::Vector3f pos,
00097           const Eigen::Vector3f vel,
00098           const Eigen::Vector3f vel_samples);
00099 
00107       base_local_planner::Trajectory findBestPath(
00108           tf::Stamped<tf::Pose> global_pose,
00109           tf::Stamped<tf::Pose> global_vel,
00110           tf::Stamped<tf::Pose>& drive_velocities,
00111           std::vector<geometry_msgs::Point> footprint_spec);
00112 
00117       void updatePlanAndLocalCosts(tf::Stamped<tf::Pose> global_pose,
00118           const std::vector<geometry_msgs::PoseStamped>& new_plan);
00119 
00124       double getSimPeriod() { return sim_period_; }
00125 
00136       bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
00137 
00141       bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
00142 
00143     private:
00144 
00145       base_local_planner::LocalPlannerUtil *planner_util_;
00146 
00147       double stop_time_buffer_; 
00148       double pdist_scale_, gdist_scale_, occdist_scale_;
00149       Eigen::Vector3f vsamples_;
00150 
00151       double sim_period_;
00152       base_local_planner::Trajectory result_traj_;
00153 
00154       double forward_point_distance_;
00155 
00156       std::vector<geometry_msgs::PoseStamped> global_plan_;
00157 
00158       boost::mutex configuration_mutex_;
00159       pcl::PointCloud<base_local_planner::MapGridCostPoint> traj_cloud_;
00160       pcl_ros::Publisher<base_local_planner::MapGridCostPoint> traj_cloud_pub_;
00161       bool publish_cost_grid_pc_; 
00162 
00163       base_local_planner::MapGridVisualizer map_viz_; 
00164 
00165       // see constructor body for explanations
00166       base_local_planner::SimpleTrajectoryGenerator generator_;
00167       base_local_planner::OscillationCostFunction oscillation_costs_;
00168       base_local_planner::ObstacleCostFunction obstacle_costs_;
00169       base_local_planner::MapGridCostFunction path_costs_;
00170       base_local_planner::MapGridCostFunction goal_costs_;
00171       base_local_planner::MapGridCostFunction goal_front_costs_;
00172       base_local_planner::MapGridCostFunction alignment_costs_;
00173 
00174       base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_;
00175   };
00176 };
00177 #endif


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