teb_config.h
Go to the documentation of this file.
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     bool global_plan_overwrite_orientation; 
00076     double global_plan_viapoint_sep; 
00077     bool via_points_ordered; 
00078     double max_global_plan_lookahead_dist; 
00079     double force_reinit_new_goal_dist; 
00080     int feasibility_check_no_poses; 
00081     bool publish_feedback; 
00082     bool shrink_horizon_backup; 
00083   } trajectory; 
00084     
00086   struct Robot
00087   {
00088     double max_vel_x; 
00089     double max_vel_x_backwards; 
00090     double max_vel_theta; 
00091     double acc_lim_x; 
00092     double acc_lim_theta; 
00093     double min_turning_radius; 
00094     double wheelbase; 
00095     bool cmd_angle_instead_rotvel; 
00096   } robot; 
00097   
00099   struct GoalTolerance
00100   {
00101     double yaw_goal_tolerance; 
00102     double xy_goal_tolerance; 
00103     bool free_goal_vel; 
00104   } goal_tolerance; 
00105 
00107   struct Obstacles
00108   {
00109     double min_obstacle_dist; 
00110     double inflation_dist; 
00111     bool include_costmap_obstacles; 
00112     double costmap_obstacles_behind_robot_dist; 
00113     int obstacle_poses_affected; 
00114     std::string costmap_converter_plugin; 
00115     bool costmap_converter_spin_thread; 
00116     int costmap_converter_rate; 
00117   } obstacles; 
00118 
00119   
00121   struct Optimization
00122   {
00123     int no_inner_iterations; 
00124     int no_outer_iterations; 
00125     
00126     bool optimization_activate; 
00127     bool optimization_verbose; 
00128     
00129     double penalty_epsilon; 
00130     
00131     double weight_max_vel_x; 
00132     double weight_max_vel_theta; 
00133     double weight_acc_lim_x; 
00134     double weight_acc_lim_theta; 
00135     double weight_kinematics_nh; 
00136     double weight_kinematics_forward_drive; 
00137     double weight_kinematics_turning_radius; 
00138     double weight_optimaltime; 
00139     double weight_obstacle; 
00140     double weight_inflation; 
00141     double weight_dynamic_obstacle; 
00142     double weight_viapoint; 
00143   } optim; 
00144   
00145   
00146   struct HomotopyClasses
00147   {
00148     bool enable_homotopy_class_planning; 
00149     bool enable_multithreading; 
00150     bool simple_exploration; 
00151     int max_number_classes; 
00152     double selection_cost_hysteresis; 
00153     double selection_obst_cost_scale; 
00154     double selection_viapoint_cost_scale; 
00155     bool selection_alternative_time_cost; 
00156     
00157     int roadmap_graph_no_samples; 
00158     double roadmap_graph_area_width; 
00159     double h_signature_prescaler; 
00160     double h_signature_threshold; 
00161     
00162     double obstacle_keypoint_offset; 
00163     double obstacle_heading_threshold; 
00164     
00165     bool viapoints_all_candidates; 
00166     
00167     bool visualize_hc_graph; 
00168   } hcp;
00169   
00170 
00184   TebConfig()
00185   {
00186     
00187     odom_topic = "odom";
00188     map_frame = "odom"; 
00189     
00190     // Trajectory
00191     
00192     trajectory.teb_autosize = true;
00193     trajectory.dt_ref = 0.3;
00194     trajectory.dt_hysteresis = 0.1;
00195     trajectory.min_samples = 3;
00196     trajectory.global_plan_overwrite_orientation = true;
00197     trajectory.global_plan_viapoint_sep = -1;
00198     trajectory.via_points_ordered = false;
00199     trajectory.max_global_plan_lookahead_dist = 1;
00200     trajectory.force_reinit_new_goal_dist = 1;
00201     trajectory.feasibility_check_no_poses = 5;
00202     trajectory.publish_feedback = false;
00203     trajectory.shrink_horizon_backup = true;
00204     
00205     // Robot
00206          
00207     robot.max_vel_x = 0.4;
00208     robot.max_vel_x_backwards = 0.2;
00209     robot.max_vel_theta = 0.3;
00210     robot.acc_lim_x = 0.5;
00211     robot.acc_lim_theta = 0.5;
00212     robot.min_turning_radius = 0;
00213     robot.wheelbase = 1.0;
00214     robot.cmd_angle_instead_rotvel = false;
00215     
00216     // GoalTolerance
00217     
00218     goal_tolerance.xy_goal_tolerance = 0.2;
00219     goal_tolerance.yaw_goal_tolerance = 0.2;
00220     goal_tolerance.free_goal_vel = false;
00221     
00222     // Obstacles
00223     
00224     obstacles.min_obstacle_dist = 0.5;
00225     obstacles.inflation_dist = 0.0;
00226     obstacles.include_costmap_obstacles = true;
00227     obstacles.costmap_obstacles_behind_robot_dist = 0.5;
00228     obstacles.obstacle_poses_affected = 25;
00229     obstacles.costmap_converter_plugin = "";
00230     obstacles.costmap_converter_spin_thread = true;
00231     obstacles.costmap_converter_rate = 5;
00232     
00233     // Optimization
00234     
00235     optim.no_inner_iterations = 5;
00236     optim.no_outer_iterations = 4;
00237     optim.optimization_activate = true;
00238     optim.optimization_verbose = false;
00239     optim.penalty_epsilon = 0.1;
00240     optim.weight_max_vel_x = 2; //1
00241     optim.weight_max_vel_theta = 1;
00242     optim.weight_acc_lim_x = 1;
00243     optim.weight_acc_lim_theta = 1;
00244     optim.weight_kinematics_nh = 1000;
00245     optim.weight_kinematics_forward_drive = 1;
00246     optim.weight_kinematics_turning_radius = 1;
00247     optim.weight_optimaltime = 1;
00248     optim.weight_obstacle = 10;
00249     optim.weight_inflation = 0.1;
00250     optim.weight_dynamic_obstacle = 10;
00251     optim.weight_viapoint = 1;
00252     
00253     // Homotopy Class Planner
00254    
00255     hcp.enable_homotopy_class_planning = true;
00256     hcp.enable_multithreading = true;
00257     hcp.simple_exploration = false;
00258     hcp.max_number_classes = 5; 
00259     hcp.selection_cost_hysteresis = 1.0;
00260     hcp.selection_obst_cost_scale = 100.0;
00261     hcp.selection_viapoint_cost_scale = 1.0;
00262     hcp.selection_alternative_time_cost = false;
00263         
00264     hcp.obstacle_keypoint_offset = 0.1;
00265     hcp.obstacle_heading_threshold = 0.45; 
00266     hcp.roadmap_graph_no_samples = 15;
00267     hcp.roadmap_graph_area_width = 6; // [m]
00268     hcp.h_signature_prescaler = 1;
00269     hcp.h_signature_threshold = 0.1;
00270     
00271     hcp.viapoints_all_candidates = true;
00272     
00273     hcp.visualize_hc_graph = false;
00274 
00275 
00276   }
00277   
00282   void loadRosParamFromNodeHandle(const ros::NodeHandle& nh);
00283   
00292   void reconfigure(TebLocalPlannerReconfigureConfig& cfg);
00293   
00300   void checkParameters() const;
00301   
00306   void checkDeprecated(const ros::NodeHandle& nh) const;
00307   
00311   boost::mutex& configMutex() {return config_mutex_;}
00312   
00313 private:
00314   boost::mutex config_mutex_; 
00315   
00316 };
00317 
00318 
00319 } // namespace teb_local_planner
00320 
00321 #endif


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15