chomp_parameters.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, 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 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 /* Author: Mrinal Kalakrishnan */
00036 
00037 #ifndef CHOMP_PARAMETERS_H_
00038 #define CHOMP_PARAMETERS_H_
00039 
00040 #include <ros/ros.h>
00041 
00042 namespace chomp
00043 {
00044 class ChompParameters
00045 {
00046 public:
00047   ChompParameters();
00048   virtual ~ChompParameters();
00049 
00050   double getPlanningTimeLimit() const;
00051   void setPlanningTimeLimit(double planning_time_limit);
00052   int getMaxIterations() const;
00053   int getMaxIterationsAfterCollisionFree() const;
00054   double getSmoothnessCostWeight() const;
00055   double getObstacleCostWeight() const;
00056   bool getAnimatePath() const;
00057   double getLearningRate() const;
00058   double getSmoothnessCostVelocity() const;
00059   double getSmoothnessCostAcceleration() const;
00060   double getSmoothnessCostJerk() const;
00061   bool getAddRandomness() const;
00062   bool getUseHamiltonianMonteCarlo() const;
00063   double getHmcDiscretization() const;
00064   double getHmcStochasticity() const;
00065   double getHmcAnnealingFactor() const;
00066   double getRidgeFactor() const;
00067   bool getUsePseudoInverse() const;
00068   double getPseudoInverseRidgeFactor() const;
00069   bool getAnimateEndeffector() const;
00070   std::string getAnimateEndeffectorSegment() const;
00071   double getJointUpdateLimit() const;
00072   double getMinClearence() const;
00073   double getCollisionThreshold() const;
00074   bool getFilterMode() const;
00075   void setFilterMode(bool mode);
00076   double getRandomJumpAmount() const;
00077   void setRandomJumpAmount(double amount);
00078   bool getUseStochasticDescent() const;
00079 
00080 public:
00081   double planning_time_limit_;
00082   int max_iterations_;
00083   int max_iterations_after_collision_free_;
00084   double smoothness_cost_weight_;
00085   double obstacle_cost_weight_;
00086   double learning_rate_;
00087   bool animate_path_;
00088   double smoothness_cost_velocity_;
00089   double smoothness_cost_acceleration_;
00090   double smoothness_cost_jerk_;
00091   bool add_randomness_;
00092   bool use_hamiltonian_monte_carlo_;
00093   bool use_stochastic_descent_;
00094   double hmc_stochasticity_;
00095   double hmc_discretization_;
00096   double hmc_annealing_factor_;
00097   double ridge_factor_;
00098   bool use_pseudo_inverse_;
00099   double pseudo_inverse_ridge_factor_;
00100   bool animate_endeffector_;
00101   std::string animate_endeffector_segment_;
00102   double joint_update_limit_;
00103   double min_clearence_;
00104   double collision_threshold_;
00105   bool filter_mode_;
00106   double random_jump_amount_;
00107 };
00108 
00110 
00111 inline double ChompParameters::getRandomJumpAmount() const
00112 {
00113   return random_jump_amount_;
00114 }
00115 
00116 inline void ChompParameters::setRandomJumpAmount(double amount)
00117 {
00118   random_jump_amount_ = amount;
00119 }
00120 
00121 inline double ChompParameters::getCollisionThreshold() const
00122 {
00123   return collision_threshold_;
00124 }
00125 
00126 inline bool ChompParameters::getFilterMode() const
00127 {
00128   return filter_mode_;
00129 }
00130 
00131 inline void ChompParameters::setFilterMode(bool mode)
00132 {
00133   filter_mode_ = mode;
00134 }
00135 
00136 inline double ChompParameters::getMinClearence() const
00137 {
00138   return min_clearence_;
00139 }
00140 
00141 inline double ChompParameters::getJointUpdateLimit() const
00142 {
00143   return joint_update_limit_;
00144 }
00145 
00146 inline double ChompParameters::getPlanningTimeLimit() const
00147 {
00148   return planning_time_limit_;
00149 }
00150 
00151 inline void ChompParameters::setPlanningTimeLimit(double planning_time_limit)
00152 {
00153   planning_time_limit_ = planning_time_limit;
00154 }
00155 
00156 inline int ChompParameters::getMaxIterations() const
00157 {
00158   return max_iterations_;
00159 }
00160 
00161 inline int ChompParameters::getMaxIterationsAfterCollisionFree() const
00162 {
00163   return max_iterations_after_collision_free_;
00164 }
00165 
00166 inline double ChompParameters::getSmoothnessCostWeight() const
00167 {
00168   return smoothness_cost_weight_;
00169 }
00170 
00171 inline double ChompParameters::getObstacleCostWeight() const
00172 {
00173   return obstacle_cost_weight_;
00174 }
00175 
00176 inline double ChompParameters::getLearningRate() const
00177 {
00178   return learning_rate_;
00179 }
00180 
00181 inline bool ChompParameters::getAnimatePath() const
00182 {
00183   return animate_path_;
00184 }
00185 
00186 inline bool ChompParameters::getAddRandomness() const
00187 {
00188   return add_randomness_;
00189 }
00190 
00191 inline double ChompParameters::getSmoothnessCostVelocity() const
00192 {
00193   return smoothness_cost_velocity_;
00194 }
00195 
00196 inline double ChompParameters::getSmoothnessCostAcceleration() const
00197 {
00198   return smoothness_cost_acceleration_;
00199 }
00200 
00201 inline double ChompParameters::getSmoothnessCostJerk() const
00202 {
00203   return smoothness_cost_jerk_;
00204 }
00205 
00206 inline double ChompParameters::getHmcDiscretization() const
00207 {
00208   return hmc_discretization_;
00209 }
00210 
00211 inline double ChompParameters::getHmcStochasticity() const
00212 {
00213   return hmc_stochasticity_;
00214 }
00215 
00216 inline double ChompParameters::getHmcAnnealingFactor() const
00217 {
00218   return hmc_annealing_factor_;
00219 }
00220 
00221 inline bool ChompParameters::getUseHamiltonianMonteCarlo() const
00222 {
00223   return use_hamiltonian_monte_carlo_;
00224 }
00225 
00226 inline double ChompParameters::getRidgeFactor() const
00227 {
00228   return ridge_factor_;
00229 }
00230 
00231 inline bool ChompParameters::getUsePseudoInverse() const
00232 {
00233   return use_pseudo_inverse_;
00234 }
00235 
00236 inline double ChompParameters::getPseudoInverseRidgeFactor() const
00237 {
00238   return pseudo_inverse_ridge_factor_;
00239 }
00240 
00241 inline bool ChompParameters::getAnimateEndeffector() const
00242 {
00243   return animate_endeffector_;
00244 }
00245 
00246 inline bool ChompParameters::getUseStochasticDescent() const
00247 {
00248   return use_stochastic_descent_;
00249 }
00250 
00251 inline std::string ChompParameters::getAnimateEndeffectorSegment() const
00252 {
00253   return animate_endeffector_segment_;
00254 }
00255 
00256 }  // namespace chomp
00257 
00258 #endif /* CHOMP_PARAMETERS_H_ */


chomp_motion_planner
Author(s): Gil Jones
autogenerated on Mon Jul 24 2017 02:21:07