moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
chomp::ChompCost Class Reference

Represents the smoothness cost for CHOMP, for a single joint. More...

#include <chomp_cost.h>

Public Member Functions

 ChompCost (const ChompTrajectory &trajectory, int joint_number, const std::vector< double > &derivative_costs, double ridge_factor=0.0)
 
virtual ~ChompCost ()
 
template<typename Derived >
void getDerivative (const Eigen::MatrixXd::ColXpr &joint_trajectory, Eigen::MatrixBase< Derived > &derivative) const
 
const Eigen::MatrixXd & getQuadraticCostInverse () const
 
const Eigen::MatrixXd & getQuadraticCost () const
 
double getCost (const Eigen::MatrixXd::ColXpr &joint_trajectory) const
 
double getMaxQuadCostInvValue () const
 
void scale (double scale)
 

Detailed Description

Represents the smoothness cost for CHOMP, for a single joint.

Definition at line 49 of file chomp_cost.h.

Constructor & Destructor Documentation

◆ ChompCost()

chomp::ChompCost::ChompCost ( const ChompTrajectory trajectory,
int  joint_number,
const std::vector< double > &  derivative_costs,
double  ridge_factor = 0.0 
)

Definition at line 47 of file chomp_cost.cpp.

Here is the call graph for this function:

◆ ~ChompCost()

chomp::ChompCost::~ChompCost ( )
virtualdefault

Member Function Documentation

◆ getCost()

double chomp::ChompCost::getCost ( const Eigen::MatrixXd::ColXpr &  joint_trajectory) const
inline

Definition at line 95 of file chomp_cost.h.

◆ getDerivative()

template<typename Derived >
void chomp::ChompCost::getDerivative ( const Eigen::MatrixXd::ColXpr &  joint_trajectory,
Eigen::MatrixBase< Derived > &  derivative 
) const

Definition at line 79 of file chomp_cost.h.

◆ getMaxQuadCostInvValue()

double chomp::ChompCost::getMaxQuadCostInvValue ( ) const

Definition at line 92 of file chomp_cost.cpp.

◆ getQuadraticCost()

const Eigen::MatrixXd & chomp::ChompCost::getQuadraticCost ( ) const
inline

Definition at line 90 of file chomp_cost.h.

◆ getQuadraticCostInverse()

const Eigen::MatrixXd & chomp::ChompCost::getQuadraticCostInverse ( ) const
inline

Definition at line 85 of file chomp_cost.h.

◆ scale()

void chomp::ChompCost::scale ( double  scale)

Definition at line 97 of file chomp_cost.cpp.


The documentation for this class was generated from the following files: