40 #include <eigen3/Eigen/Core> 53 double ridge_factor = 0.0);
56 template <
typename Derived>
57 void getDerivative(Eigen::MatrixXd::ColXpr joint_trajectory, Eigen::MatrixBase<Derived>& derivative)
const;
63 double getCost(Eigen::MatrixXd::ColXpr joint_trajectory)
const;
75 Eigen::MatrixXd
getDiffMatrix(
int size,
const double* diff_rule)
const;
78 template <
typename Derived>
double getCost(Eigen::MatrixXd::ColXpr joint_trajectory) const
double getMaxQuadCostInvValue() const
const Eigen::MatrixXd & getQuadraticCostInverse() const
ChompCost(const ChompTrajectory &trajectory, int joint_number, const std::vector< double > &derivative_costs, double ridge_factor=0.0)
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
Represents the smoothness cost for CHOMP, for a single joint.
const Eigen::MatrixXd & getQuadraticCost() const
void getDerivative(Eigen::MatrixXd::ColXpr joint_trajectory, Eigen::MatrixBase< Derived > &derivative) const
Represents a discretized joint-space trajectory for CHOMP.
Eigen::MatrixXd getDiffMatrix(int size, const double *diff_rule) const
Eigen::MatrixXd quad_cost_inv_
Eigen::MatrixXd quad_cost_
Eigen::MatrixXd quad_cost_full_