41 #include <eigen3/Eigen/Core>
53 double ridge_factor = 0.0);
56 template <
typename Derived>
57 void getDerivative(
const Eigen::MatrixXd::ColXpr& joint_trajectory, Eigen::MatrixBase<Derived>& derivative)
const;
63 double getCost(
const Eigen::MatrixXd::ColXpr& joint_trajectory)
const;
70 Eigen::MatrixXd quad_cost_full_;
71 Eigen::MatrixXd quad_cost_;
73 Eigen::MatrixXd quad_cost_inv_;
75 Eigen::MatrixXd getDiffMatrix(
int size,
const double* diff_rule)
const;
78 template <
typename Derived>
80 Eigen::MatrixBase<Derived>& derivative)
const
82 derivative = (quad_cost_full_ * (2.0 * joint_trajectory));
87 return quad_cost_inv_;
97 return joint_trajectory.dot(quad_cost_full_ * joint_trajectory);
Represents the smoothness cost for CHOMP, for a single joint.
void getDerivative(const Eigen::MatrixXd::ColXpr &joint_trajectory, Eigen::MatrixBase< Derived > &derivative) const
ChompCost(const ChompTrajectory &trajectory, int joint_number, const std::vector< double > &derivative_costs, double ridge_factor=0.0)
const Eigen::MatrixXd & getQuadraticCostInverse() const
const Eigen::MatrixXd & getQuadraticCost() const
double getMaxQuadCostInvValue() const
double getCost(const Eigen::MatrixXd::ColXpr &joint_trajectory) const
Represents a discretized joint-space trajectory for CHOMP.