Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <chomp_motion_planner/chomp_cost.h>
00038 #include <chomp_motion_planner/chomp_utils.h>
00039 #include <eigen3/Eigen/LU>
00040
00041 using namespace Eigen;
00042 using namespace std;
00043
00044 namespace chomp
00045 {
00046 ChompCost::ChompCost(const ChompTrajectory& trajectory, int joint_number, const std::vector<double>& derivative_costs,
00047 double ridge_factor)
00048 {
00049 int num_vars_all = trajectory.getNumPoints();
00050 int num_vars_free = num_vars_all - 2 * (DIFF_RULE_LENGTH - 1);
00051 MatrixXd diff_matrix = MatrixXd::Zero(num_vars_all, num_vars_all);
00052 quad_cost_full_ = MatrixXd::Zero(num_vars_all, num_vars_all);
00053
00054
00055 double multiplier = 1.0;
00056 for (unsigned int i = 0; i < derivative_costs.size(); i++)
00057 {
00058 multiplier *= trajectory.getDiscretization();
00059 diff_matrix = getDiffMatrix(num_vars_all, &DIFF_RULES[i][0]);
00060 quad_cost_full_ += (derivative_costs[i] * multiplier) * (diff_matrix.transpose() * diff_matrix);
00061 }
00062 quad_cost_full_ += MatrixXd::Identity(num_vars_all, num_vars_all) * ridge_factor;
00063
00064
00065 quad_cost_ = quad_cost_full_.block(DIFF_RULE_LENGTH - 1, DIFF_RULE_LENGTH - 1, num_vars_free, num_vars_free);
00066
00067
00068 quad_cost_inv_ = quad_cost_.inverse();
00069
00070
00071 }
00072
00073 Eigen::MatrixXd ChompCost::getDiffMatrix(int size, const double* diff_rule) const
00074 {
00075 MatrixXd matrix = MatrixXd::Zero(size, size);
00076 for (int i = 0; i < size; i++)
00077 {
00078 for (int j = -DIFF_RULE_LENGTH / 2; j <= DIFF_RULE_LENGTH / 2; j++)
00079 {
00080 int index = i + j;
00081 if (index < 0)
00082 continue;
00083 if (index >= size)
00084 continue;
00085 matrix(i, index) = diff_rule[j + DIFF_RULE_LENGTH / 2];
00086 }
00087 }
00088 return matrix;
00089 }
00090
00091 double ChompCost::getMaxQuadCostInvValue() const
00092 {
00093 return quad_cost_inv_.maxCoeff();
00094 }
00095
00096 void ChompCost::scale(double scale)
00097 {
00098 double inv_scale = 1.0 / scale;
00099 quad_cost_inv_ *= inv_scale;
00100 quad_cost_ *= scale;
00101 quad_cost_full_ *= scale;
00102 }
00103
00104 ChompCost::~ChompCost()
00105 {
00106 }
00107 }