00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2016, 00006 * TU Dortmund - Institute of Control Theory and Systems Engineering. 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of the institute nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 * Author: Christoph Rösmann 00037 *********************************************************************/ 00038 00039 #ifndef TEB_CONFIG_H_ 00040 #define TEB_CONFIG_H_ 00041 00042 #include <ros/console.h> 00043 #include <ros/ros.h> 00044 #include <Eigen/Core> 00045 #include <Eigen/StdVector> 00046 00047 #include <teb_local_planner/TebLocalPlannerReconfigureConfig.h> 00048 00049 00050 // Definitions 00051 #define USE_ANALYTIC_JACOBI // if available for a specific edge, use analytic jacobi 00052 00053 00054 namespace teb_local_planner 00055 { 00056 00061 class TebConfig 00062 { 00063 public: 00064 00065 std::string odom_topic; 00066 std::string map_frame; 00067 00069 struct Trajectory 00070 { 00071 double teb_autosize; 00072 double dt_ref; 00073 double dt_hysteresis; 00074 int min_samples; 00075 int max_samples; 00076 bool global_plan_overwrite_orientation; 00077 bool allow_init_with_backwards_motion; 00078 double global_plan_viapoint_sep; 00079 bool via_points_ordered; 00080 double max_global_plan_lookahead_dist; 00081 bool exact_arc_length; 00082 double force_reinit_new_goal_dist; 00083 int feasibility_check_no_poses; 00084 bool publish_feedback; 00085 bool shrink_horizon_backup; 00086 double shrink_horizon_min_duration; 00087 } trajectory; 00088 00090 struct Robot 00091 { 00092 double max_vel_x; 00093 double max_vel_x_backwards; 00094 double max_vel_y; 00095 double max_vel_theta; 00096 double acc_lim_x; 00097 double acc_lim_y; 00098 double acc_lim_theta; 00099 double min_turning_radius; 00100 double wheelbase; 00101 bool cmd_angle_instead_rotvel; 00102 } robot; 00103 00105 struct GoalTolerance 00106 { 00107 double yaw_goal_tolerance; 00108 double xy_goal_tolerance; 00109 bool free_goal_vel; 00110 } goal_tolerance; 00111 00113 struct Obstacles 00114 { 00115 double min_obstacle_dist; 00116 double inflation_dist; 00117 bool include_costmap_obstacles; 00118 double costmap_obstacles_behind_robot_dist; 00119 int obstacle_poses_affected; 00120 bool legacy_obstacle_association; 00121 double obstacle_association_force_inclusion_factor; 00122 double obstacle_association_cutoff_factor; 00123 std::string costmap_converter_plugin; 00124 bool costmap_converter_spin_thread; 00125 int costmap_converter_rate; 00126 } obstacles; 00127 00128 00130 struct Optimization 00131 { 00132 int no_inner_iterations; 00133 int no_outer_iterations; 00134 00135 bool optimization_activate; 00136 bool optimization_verbose; 00137 00138 double penalty_epsilon; 00139 00140 double weight_max_vel_x; 00141 double weight_max_vel_y; 00142 double weight_max_vel_theta; 00143 double weight_acc_lim_x; 00144 double weight_acc_lim_y; 00145 double weight_acc_lim_theta; 00146 double weight_kinematics_nh; 00147 double weight_kinematics_forward_drive; 00148 double weight_kinematics_turning_radius; 00149 double weight_optimaltime; 00150 double weight_obstacle; 00151 double weight_inflation; 00152 double weight_dynamic_obstacle; 00153 double weight_viapoint; 00154 00155 double weight_adapt_factor; 00156 } optim; 00157 00158 00159 struct HomotopyClasses 00160 { 00161 bool enable_homotopy_class_planning; 00162 bool enable_multithreading; 00163 bool simple_exploration; 00164 int max_number_classes; 00165 double selection_cost_hysteresis; 00166 double selection_prefer_initial_plan; 00167 double selection_obst_cost_scale; 00168 double selection_viapoint_cost_scale; 00169 bool selection_alternative_time_cost; 00170 00171 int roadmap_graph_no_samples; 00172 double roadmap_graph_area_width; 00173 double roadmap_graph_area_length_scale; 00174 double h_signature_prescaler; 00175 double h_signature_threshold; 00176 00177 double obstacle_keypoint_offset; 00178 double obstacle_heading_threshold; 00179 00180 bool viapoints_all_candidates; 00181 00182 bool visualize_hc_graph; 00183 } hcp; 00184 00185 00199 TebConfig() 00200 { 00201 00202 odom_topic = "odom"; 00203 map_frame = "odom"; 00204 00205 // Trajectory 00206 00207 trajectory.teb_autosize = true; 00208 trajectory.dt_ref = 0.3; 00209 trajectory.dt_hysteresis = 0.1; 00210 trajectory.min_samples = 3; 00211 trajectory.max_samples = 500; 00212 trajectory.global_plan_overwrite_orientation = true; 00213 trajectory.allow_init_with_backwards_motion = false; 00214 trajectory.global_plan_viapoint_sep = -1; 00215 trajectory.via_points_ordered = false; 00216 trajectory.max_global_plan_lookahead_dist = 1; 00217 trajectory.exact_arc_length = false; 00218 trajectory.force_reinit_new_goal_dist = 1; 00219 trajectory.feasibility_check_no_poses = 5; 00220 trajectory.publish_feedback = false; 00221 trajectory.shrink_horizon_backup = true; 00222 trajectory.shrink_horizon_min_duration = 10; 00223 00224 // Robot 00225 00226 robot.max_vel_x = 0.4; 00227 robot.max_vel_x_backwards = 0.2; 00228 robot.max_vel_y = 0.0; 00229 robot.max_vel_theta = 0.3; 00230 robot.acc_lim_x = 0.5; 00231 robot.acc_lim_y = 0.5; 00232 robot.acc_lim_theta = 0.5; 00233 robot.min_turning_radius = 0; 00234 robot.wheelbase = 1.0; 00235 robot.cmd_angle_instead_rotvel = false; 00236 00237 // GoalTolerance 00238 00239 goal_tolerance.xy_goal_tolerance = 0.2; 00240 goal_tolerance.yaw_goal_tolerance = 0.2; 00241 goal_tolerance.free_goal_vel = false; 00242 00243 // Obstacles 00244 00245 obstacles.min_obstacle_dist = 0.5; 00246 obstacles.inflation_dist = 0.0; 00247 obstacles.include_costmap_obstacles = true; 00248 obstacles.costmap_obstacles_behind_robot_dist = 1.5; 00249 obstacles.obstacle_poses_affected = 25; 00250 obstacles.legacy_obstacle_association = false; 00251 obstacles.obstacle_association_force_inclusion_factor = 1.5; 00252 obstacles.obstacle_association_cutoff_factor = 5; 00253 obstacles.costmap_converter_plugin = ""; 00254 obstacles.costmap_converter_spin_thread = true; 00255 obstacles.costmap_converter_rate = 5; 00256 00257 // Optimization 00258 00259 optim.no_inner_iterations = 5; 00260 optim.no_outer_iterations = 4; 00261 optim.optimization_activate = true; 00262 optim.optimization_verbose = false; 00263 optim.penalty_epsilon = 0.1; 00264 optim.weight_max_vel_x = 2; //1 00265 optim.weight_max_vel_y = 2; 00266 optim.weight_max_vel_theta = 1; 00267 optim.weight_acc_lim_x = 1; 00268 optim.weight_acc_lim_y = 1; 00269 optim.weight_acc_lim_theta = 1; 00270 optim.weight_kinematics_nh = 1000; 00271 optim.weight_kinematics_forward_drive = 1; 00272 optim.weight_kinematics_turning_radius = 1; 00273 optim.weight_optimaltime = 1; 00274 optim.weight_obstacle = 10; 00275 optim.weight_inflation = 0.1; 00276 optim.weight_dynamic_obstacle = 10; 00277 optim.weight_viapoint = 1; 00278 00279 optim.weight_adapt_factor = 2.0; 00280 00281 // Homotopy Class Planner 00282 00283 hcp.enable_homotopy_class_planning = true; 00284 hcp.enable_multithreading = true; 00285 hcp.simple_exploration = false; 00286 hcp.max_number_classes = 5; 00287 hcp.selection_cost_hysteresis = 1.0; 00288 hcp.selection_prefer_initial_plan = 0.95; 00289 hcp.selection_obst_cost_scale = 100.0; 00290 hcp.selection_viapoint_cost_scale = 1.0; 00291 hcp.selection_alternative_time_cost = false; 00292 00293 hcp.obstacle_keypoint_offset = 0.1; 00294 hcp.obstacle_heading_threshold = 0.45; 00295 hcp.roadmap_graph_no_samples = 15; 00296 hcp.roadmap_graph_area_width = 6; // [m] 00297 hcp.roadmap_graph_area_length_scale = 1.0; 00298 hcp.h_signature_prescaler = 1; 00299 hcp.h_signature_threshold = 0.1; 00300 00301 hcp.viapoints_all_candidates = true; 00302 00303 hcp.visualize_hc_graph = false; 00304 00305 00306 } 00307 00312 void loadRosParamFromNodeHandle(const ros::NodeHandle& nh); 00313 00322 void reconfigure(TebLocalPlannerReconfigureConfig& cfg); 00323 00330 void checkParameters() const; 00331 00336 void checkDeprecated(const ros::NodeHandle& nh) const; 00337 00341 boost::mutex& configMutex() {return config_mutex_;} 00342 00343 private: 00344 boost::mutex config_mutex_; 00345 00346 }; 00347 00348 00349 } // namespace teb_local_planner 00350 00351 #endif