39 #include <eigen3/Eigen/LU> 41 using namespace Eigen;
46 ChompCost::ChompCost(
const ChompTrajectory& trajectory,
int joint_number,
const std::vector<double>& derivative_costs,
51 MatrixXd diff_matrix = MatrixXd::Zero(num_vars_all, num_vars_all);
52 quad_cost_full_ = MatrixXd::Zero(num_vars_all, num_vars_all);
55 double multiplier = 1.0;
56 for (
unsigned int i = 0; i < derivative_costs.size(); i++)
59 diff_matrix = getDiffMatrix(num_vars_all, &
DIFF_RULES[i][0]);
60 quad_cost_full_ += (derivative_costs[i] * multiplier) * (diff_matrix.transpose() * diff_matrix);
62 quad_cost_full_ += MatrixXd::Identity(num_vars_all, num_vars_all) * ridge_factor;
68 quad_cost_inv_ = quad_cost_.inverse();
73 Eigen::MatrixXd ChompCost::getDiffMatrix(
int size,
const double* diff_rule)
const 75 MatrixXd matrix = MatrixXd::Zero(size, size);
76 for (
int i = 0; i < size; i++)
91 double ChompCost::getMaxQuadCostInvValue()
const 93 return quad_cost_inv_.maxCoeff();
96 void ChompCost::scale(
double scale)
98 double inv_scale = 1.0 / scale;
99 quad_cost_inv_ *= inv_scale;
101 quad_cost_full_ *= scale;
104 ChompCost::~ChompCost()
static const int DIFF_RULE_LENGTH
int getNumPoints() const
Gets the number of points in the trajectory.
static const double DIFF_RULES[3][DIFF_RULE_LENGTH]
Represents a discretized joint-space trajectory for CHOMP.
double getDiscretization() const
Gets the discretization time interval of the trajectory.