40 #include <eigen3/Eigen/LU> 
   42 using namespace Eigen;
 
   48                      const std::vector<double>& derivative_costs, 
double ridge_factor)
 
   51   int num_vars_free = num_vars_all - 2 * (DIFF_RULE_LENGTH - 1);
 
   52   MatrixXd diff_matrix = MatrixXd::Zero(num_vars_all, num_vars_all);
 
   53   quad_cost_full_ = MatrixXd::Zero(num_vars_all, num_vars_all);
 
   56   double multiplier = 1.0;
 
   57   for (
unsigned int i = 0; i < derivative_costs.size(); ++i)
 
   60     diff_matrix = getDiffMatrix(num_vars_all, &DIFF_RULES[i][0]);
 
   61     quad_cost_full_ += (derivative_costs[i] * multiplier) * (diff_matrix.transpose() * diff_matrix);
 
   63   quad_cost_full_ += MatrixXd::Identity(num_vars_all, num_vars_all) * ridge_factor;
 
   66   quad_cost_ = quad_cost_full_.block(DIFF_RULE_LENGTH - 1, DIFF_RULE_LENGTH - 1, num_vars_free, num_vars_free);
 
   69   quad_cost_inv_ = quad_cost_.inverse();
 
   74 Eigen::MatrixXd ChompCost::getDiffMatrix(
int size, 
const double* diff_rule)
 const 
   76   MatrixXd matrix = MatrixXd::Zero(size, size);
 
   77   for (
int i = 0; i < size; ++i)
 
   79     for (
int j = -DIFF_RULE_LENGTH / 2; j <= DIFF_RULE_LENGTH / 2; ++j)
 
   86       matrix(i, index) = diff_rule[j + DIFF_RULE_LENGTH / 2];
 
   92 double ChompCost::getMaxQuadCostInvValue()
 const 
   94   return quad_cost_inv_.maxCoeff();
 
   97 void ChompCost::scale(
double scale)
 
   99   double inv_scale = 1.0 / scale;
 
  100   quad_cost_inv_ *= inv_scale;
 
  102   quad_cost_full_ *= scale;
 
  105 ChompCost::~ChompCost() = 
default;
 
Represents a discretized joint-space trajectory for CHOMP.
 
double getDiscretization() const
Gets the discretization time interval of the trajectory.
 
size_t getNumPoints() const
Gets the number of points in the trajectory.