$search
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_OPTIMIZER_H_ 00038 #define CHOMP_OPTIMIZER_H_ 00039 00040 #include <chomp_motion_planner/chomp_parameters.h> 00041 #include <chomp_motion_planner/chomp_trajectory.h> 00042 #include <chomp_motion_planner/chomp_cost.h> 00043 #include <chomp_motion_planner/multivariate_gaussian.h> 00044 #include <planning_models/kinematic_model.h> 00045 #include <collision_proximity/collision_proximity_space.h> 00046 00047 #include <eigen3/Eigen/Core> 00048 00049 #include <vector> 00050 00051 namespace chomp 00052 { 00053 00054 class ChompOptimizer 00055 { 00056 public: 00057 ChompOptimizer(ChompTrajectory *trajectory, planning_models::KinematicModel *robot_model, 00058 const std::string& planning_group, const ChompParameters *parameters, 00059 const ros::Publisher& vis_marker_array_publisher, 00060 const ros::Publisher& vis_marker_publisher, 00061 collision_proximity::CollisionProximitySpace *collision_space); 00062 virtual ~ChompOptimizer(); 00063 00064 void optimize(); 00065 00066 inline void destroy() 00067 { 00068 //Nothing for now. 00069 } 00070 private: 00071 00072 inline double getPotential(double field_distance, double radius, double clearence) 00073 { 00074 double d = field_distance - radius; 00075 double potential = 0.0; 00076 00077 // three cases below: 00078 if (d >= clearence) 00079 { 00080 potential = 0.0; 00081 } 00082 else if (d >= 0.0) 00083 { 00084 double diff = (d - clearence); 00085 double gradient_magnitude = diff * clearence; // (diff / clearance) 00086 potential = 0.5*gradient_magnitude*diff; 00087 } 00088 else // if d < 0.0 00089 { 00090 potential = -d + 0.5 * clearence; 00091 } 00092 00093 return potential; 00094 } 00095 template<typename Derived> 00096 void getJacobian(int trajectoryPoint,Eigen::Vector3d& collision_point_pos, std::string& jointName, Eigen::MatrixBase<Derived>& jacobian) const; 00097 00098 void getRandomState(const planning_models::KinematicState* currentState, const std::string& groupName, 00099 Eigen::VectorXd& state_vec); 00100 00101 void setRobotStateFromPoint(ChompTrajectory& group_trajectory, int i); 00102 00103 bool checkCurrentIterValidity(); 00104 00105 int num_joints_; 00106 int num_vars_free_; 00107 int num_vars_all_; 00108 int num_collision_points_; 00109 int free_vars_start_; 00110 int free_vars_end_; 00111 int iteration_; 00112 int collision_free_iteration_; 00113 ChompTrajectory *full_trajectory_; 00114 planning_models::KinematicModel *robot_model_; 00115 planning_models::KinematicState *robot_state_; 00116 const std::string& planning_group_; 00117 const ChompParameters *parameters_; 00118 collision_proximity::CollisionProximitySpace *collision_space_; 00119 ChompTrajectory group_trajectory_; 00120 std::vector<ChompCost> joint_costs_; 00121 00122 std::vector<std::vector<std::string> > collision_point_joint_names_; 00123 std::vector<std::vector<Eigen::Vector3d > > collision_point_pos_eigen_; 00124 std::vector<std::vector<Eigen::Vector3d > > collision_point_vel_eigen_; 00125 std::vector<std::vector<Eigen::Vector3d > > collision_point_acc_eigen_; 00126 std::vector<std::vector<double> > collision_point_potential_; 00127 std::vector<std::vector<double> > collision_point_vel_mag_; 00128 std::vector<std::vector<Eigen::Vector3d> > collision_point_potential_gradient_; 00129 std::vector<std::vector<btVector3> > joint_axes_; 00130 std::vector<std::vector<btVector3> > joint_positions_; 00131 Eigen::MatrixXd group_trajectory_backup_; 00132 Eigen::MatrixXd best_group_trajectory_; 00133 double best_group_trajectory_cost_; 00134 int last_improvement_iteration_; 00135 00136 // HMC stuff: 00137 Eigen::MatrixXd momentum_; 00138 Eigen::MatrixXd random_momentum_; 00139 Eigen::VectorXd random_joint_momentum_; //temporary variable 00140 std::vector<MultivariateGaussian> multivariate_gaussian_; 00141 double stochasticity_factor_; 00142 00143 std::vector<int> state_is_in_collision_; 00144 std::vector<std::vector<int> > point_is_in_collision_; 00145 bool is_collision_free_; 00146 double worst_collision_cost_state_; 00147 00148 Eigen::MatrixXd smoothness_increments_; 00149 Eigen::MatrixXd collision_increments_; 00150 Eigen::MatrixXd final_increments_; 00151 00152 // temporary variables for all functions: 00153 Eigen::VectorXd smoothness_derivative_; 00154 Eigen::MatrixXd jacobian_; 00155 Eigen::MatrixXd jacobian_pseudo_inverse_; 00156 Eigen::MatrixXd jacobian_jacobian_tranpose_; 00157 Eigen::VectorXd random_state_; 00158 Eigen::VectorXd joint_state_velocities_; 00159 00160 ros::Publisher vis_marker_array_pub_; 00161 ros::Publisher vis_marker_pub_; 00162 00163 std::vector<std::string> joint_names_; 00164 std::map<std::string, std::map<std::string, bool> > joint_parent_map_; 00165 00166 inline bool isParent(const std::string& childLink, const std::string& parentLink) const 00167 { 00168 if(childLink == parentLink) 00169 { 00170 return true; 00171 } 00172 00173 if(joint_parent_map_.find(childLink) == joint_parent_map_.end()) 00174 { 00175 ROS_ERROR("%s was not in joint parent map!", childLink.c_str()); 00176 return false; 00177 } 00178 const std::map<std::string, bool>& parents = joint_parent_map_.at(childLink); 00179 return (parents.find(parentLink) != parents.end() && parents.at(parentLink)); 00180 } 00181 00182 void registerParents(const planning_models::KinematicModel::JointModel* model); 00183 void initialize(); 00184 void calculateSmoothnessIncrements(); 00185 void calculateCollisionIncrements(); 00186 void calculateTotalIncrements(); 00187 void performForwardKinematics(); 00188 void addIncrementsToTrajectory(); 00189 void updateFullTrajectory(); 00190 void debugCost(); 00191 void handleJointLimits(); 00192 void animatePath(); 00193 void animateEndeffector(); 00194 void visualizeState(int index); 00195 double getTrajectoryCost(); 00196 double getSmoothnessCost(); 00197 double getCollisionCost(); 00198 void perturbTrajectory(); 00199 void getRandomMomentum(); 00200 void updateMomentum(); 00201 void updatePositionFromMomentum(); 00202 void calculatePseudoInverse(); 00203 void computeJointProperties(int trajectoryPoint); 00204 00205 }; 00206 00207 } 00208 00209 #endif /* CHOMP_OPTIMIZER_H_ */