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


chomp_motion_planner
Author(s): Gil Jones
autogenerated on Mon Oct 6 2014 11:12:26