local_planner_limits.h
Go to the documentation of this file.
00001 /***********************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  ***********************************************************/
00034 
00035 
00036 #ifndef __base_local_planner__LOCALPLANNERLIMITS_H__
00037 #define __base_local_planner__LOCALPLANNERLIMITS_H__
00038 
00039 #include <Eigen/Core>
00040 
00041 namespace base_local_planner
00042 {
00043 class LocalPlannerLimits
00044 {
00045 public:
00046 
00047   double max_trans_vel;
00048   double min_trans_vel;
00049   double max_vel_x;
00050   double min_vel_x;
00051   double max_vel_y;
00052   double min_vel_y;
00053   double max_rot_vel;
00054   double min_rot_vel;
00055   double acc_lim_x;
00056   double acc_lim_y;
00057   double acc_lim_theta;
00058   double acc_limit_trans;
00059 //  double jerk_lim_trans;
00060 //  double jerk_lim_rot;
00061   bool   prune_plan;
00062   double xy_goal_tolerance;
00063   double yaw_goal_tolerance;
00064   double trans_stopped_vel;
00065   double rot_stopped_vel;
00066   bool   restore_defaults;
00067 
00068   LocalPlannerLimits() {}
00069 
00070   LocalPlannerLimits(
00071       double nmax_trans_vel,
00072       double nmin_trans_vel,
00073       double nmax_vel_x,
00074       double nmin_vel_x,
00075       double nmax_vel_y,
00076       double nmin_vel_y,
00077       double nmax_rot_vel,
00078       double nmin_rot_vel,
00079       double nacc_lim_x,
00080       double nacc_lim_y,
00081       double nacc_lim_theta,
00082       double nacc_limit_trans,
00083       double nxy_goal_tolerance,
00084       double nyaw_goal_tolerance,
00085 //      double njerk_lim_trans = -1,
00086 //      double njerk_lim_rot = -1,
00087       bool   nprune_plan = true,
00088       double ntrans_stopped_vel = 0.1,
00089       double nrot_stopped_vel = 0.1):
00090         max_trans_vel(nmax_trans_vel),
00091         min_trans_vel(nmin_trans_vel),
00092         max_vel_x(nmax_vel_x),
00093         min_vel_x(nmin_vel_x),
00094         max_vel_y(nmax_vel_y),
00095         min_vel_y(nmin_vel_y),
00096         max_rot_vel(nmax_rot_vel),
00097         min_rot_vel(nmin_rot_vel),
00098         acc_lim_x(nacc_lim_x),
00099         acc_lim_y(nacc_lim_y),
00100         acc_lim_theta(nacc_lim_theta),
00101         acc_limit_trans(nacc_limit_trans),
00102 //        jerk_lim_trans(njerk_lim_trans),
00103 //        jerk_lim_rot(njerk_lim_rot),
00104         prune_plan(nprune_plan),
00105         xy_goal_tolerance(nxy_goal_tolerance),
00106         yaw_goal_tolerance(nyaw_goal_tolerance),
00107         trans_stopped_vel(ntrans_stopped_vel),
00108         rot_stopped_vel(nrot_stopped_vel) {}
00109 
00110   ~LocalPlannerLimits() {}
00111 
00116   Eigen::Vector3f getAccLimits() {
00117     Eigen::Vector3f acc_limits;
00118     acc_limits[0] = acc_lim_x;
00119     acc_limits[1] = acc_lim_y;
00120     acc_limits[2] = acc_lim_theta;
00121     return acc_limits;
00122   }
00123 
00124 };
00125 
00126 }
00127 #endif // __LOCALPLANNERLIMITS_H__


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:07:08