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


chomp_motion_planner
Author(s): Mrinal Kalakrishnan / mail@mrinal.net
autogenerated on Thu Dec 12 2013 11:08:58