crocoddyl  1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
CostModelFramePlacementTpl< _Scalar > Class Template Reference

Frame placement cost. More...

#include <crocoddyl/multibody/costs/frame-placement.hpp>

Inheritance diagram for CostModelFramePlacementTpl< _Scalar >:
Collaboration diagram for CostModelFramePlacementTpl< _Scalar >:

Public Types

typedef ActivationModelAbstractTpl< Scalar > ActivationModelAbstract
 
typedef CostModelResidualTpl< Scalar > Base
 
typedef FramePlacementTpl< Scalar > FramePlacement
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::Matrix6xs Matrix6xs
 
typedef ResidualModelFramePlacementTpl< Scalar > ResidualModelFramePlacement
 
typedef StateMultibodyTpl< Scalar > StateMultibody
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from CostModelResidualTpl< _Scalar >
typedef ActivationModelAbstractTpl< Scalar > ActivationModelAbstract
 
typedef CostModelAbstractTpl< Scalar > Base
 
typedef CostDataAbstractTpl< Scalar > CostDataAbstract
 
typedef CostDataResidualTpl< Scalar > Data
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualModelAbstractTpl< Scalar > ResidualModelAbstract
 
typedef MathBase::VectorXs VectorXs
 
- Public Types inherited from CostModelAbstractTpl< _Scalar >
typedef ActivationModelAbstractTpl< Scalar > ActivationModelAbstract
 
typedef ActivationModelQuadTpl< Scalar > ActivationModelQuad
 
typedef CostDataAbstractTpl< Scalar > CostDataAbstract
 
typedef DataCollectorAbstractTpl< Scalar > DataCollectorAbstract
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::MatrixXs MatrixXs
 
typedef ResidualModelAbstractTpl< Scalar > ResidualModelAbstract
 
typedef StateAbstractTpl< Scalar > StateAbstract
 
typedef MathBase::VectorXs VectorXs
 

Public Member Functions

 CostModelFramePlacementTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FramePlacement &Fref)
 Initialize the frame placement cost model. More...
 
 CostModelFramePlacementTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FramePlacement &Fref, const std::size_t nu)
 Initialize the frame placement cost model. More...
 
 CostModelFramePlacementTpl (boost::shared_ptr< StateMultibody > state, const FramePlacement &Fref)
 Initialize the frame placement cost model. More...
 
 CostModelFramePlacementTpl (boost::shared_ptr< StateMultibody > state, const FramePlacement &Fref, const std::size_t nu)
 Initialize the frame placement cost model. More...
 
- Public Member Functions inherited from CostModelResidualTpl< _Scalar >
 CostModelResidualTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, boost::shared_ptr< ResidualModelAbstract > residual)
 Initialize the residual cost model. More...
 
 CostModelResidualTpl (boost::shared_ptr< typename Base::StateAbstract > state, boost::shared_ptr< ResidualModelAbstract > residual)
 Initialize the residual cost model. More...
 
virtual void calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the residual cost based on state only. More...
 
virtual void calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the residual cost. More...
 
virtual void calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the derivatives of the residual cost with respect to the state only. More...
 
virtual void calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)
 Compute the derivatives of the residual cost. More...
 
virtual boost::shared_ptr< CostDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the residual cost data.
 
virtual void print (std::ostream &os) const
 Print relevant information of the cost-residual model. More...
 
- Public Member Functions inherited from CostModelAbstractTpl< _Scalar >
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation)
 Initialize the cost model. More...
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, boost::shared_ptr< ResidualModelAbstract > residual)
 Initialize the cost model. More...
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ActivationModelAbstract > activation, const std::size_t nu)
 Initialize the cost model. More...
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, boost::shared_ptr< ResidualModelAbstract > residual)
 Initialize the cost model. More...
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr)
 Initialize the cost model. More...
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const std::size_t nu)
 Initialize the cost model. More...
 
const boost::shared_ptr< ActivationModelAbstract > & get_activation () const
 Return the activation model.
 
std::size_t get_nu () const
 Return the dimension of the control input.
 
template<class ReferenceType >
ReferenceType get_reference ()
 Return the cost reference.
 
const boost::shared_ptr< ResidualModelAbstract > & get_residual () const
 Return the residual model.
 
const boost::shared_ptr< StateAbstract > & get_state () const
 Return the state.
 
template<class ReferenceType >
void set_reference (ReferenceType ref)
 Modify the cost reference.
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 
- Public Attributes inherited from CostModelResidualTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 
- Public Attributes inherited from CostModelAbstractTpl< _Scalar >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar
 

Protected Member Functions

virtual void get_referenceImpl (const std::type_info &ti, void *pv)
 Return the frame placement reference.
 
virtual void set_referenceImpl (const std::type_info &ti, const void *pv)
 Modify the frame placement reference.
 

Protected Attributes

boost::shared_ptr< ActivationModelAbstractactivation_
 Activation model.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< ResidualModelAbstractresidual_
 Residual model.
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
VectorXs unone_
 No control vector.
 
- Protected Attributes inherited from CostModelResidualTpl< _Scalar >
boost::shared_ptr< ActivationModelAbstractactivation_
 Activation model.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< ResidualModelAbstractresidual_
 Residual model.
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
VectorXs unone_
 No control vector.
 
- Protected Attributes inherited from CostModelAbstractTpl< _Scalar >
boost::shared_ptr< ActivationModelAbstractactivation_
 Activation model.
 
std::size_t nu_
 Control dimension.
 
boost::shared_ptr< ResidualModelAbstractresidual_
 Residual model.
 
boost::shared_ptr< StateAbstractstate_
 State description.
 
VectorXs unone_
 No control vector.
 

Detailed Description

template<typename _Scalar>
class crocoddyl::CostModelFramePlacementTpl< _Scalar >

Frame placement cost.

This cost function defines a residual vector as \(\mathbf{r}=\mathbf{p}\ominus\mathbf{p}^*\), where \(\mathbf{p},\mathbf{p}^*\in~\mathbb{SE(3)}\) are the current and reference frame placements, respectively. Note that the dimension of the residual vector is 6.

Both cost and residual derivatives are computed analytically. For the computation of the cost Hessian, we use the Gauss-Newton approximation, e.g. \(\mathbf{l_{xu}} = \mathbf{l_{x}}^T \mathbf{l_{u}} \).

As described in CostModelResidualTpl(), the cost value and its derivatives are calculated by calc and calcDiff, respectively.

See also
CostModelResidualTpl, calc(), calcDiff(), createData()

Definition at line 41 of file frame-placement.hpp.

Constructor & Destructor Documentation

◆ CostModelFramePlacementTpl() [1/4]

CostModelFramePlacementTpl ( boost::shared_ptr< StateMultibody state,
boost::shared_ptr< ActivationModelAbstract activation,
const FramePlacement Fref,
const std::size_t  nu 
)

Initialize the frame placement cost model.

Parameters
[in]stateState of the multibody system
[in]activationActivation model
[in]FrefReference frame placement
[in]nuDimension of the control vector

◆ CostModelFramePlacementTpl() [2/4]

CostModelFramePlacementTpl ( boost::shared_ptr< StateMultibody state,
boost::shared_ptr< ActivationModelAbstract activation,
const FramePlacement Fref 
)

Initialize the frame placement cost model.

The default nu is obtained from StateAbstractTpl::get_nv().

Parameters
[in]stateState of the multibody system
[in]activationActivation model
[in]FrefReference frame placement

◆ CostModelFramePlacementTpl() [3/4]

CostModelFramePlacementTpl ( boost::shared_ptr< StateMultibody state,
const FramePlacement Fref,
const std::size_t  nu 
)

Initialize the frame placement cost model.

We use ActivationModelQuadTpl as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)).

Parameters
[in]stateState of the multibody system
[in]FrefReference frame placement
[in]nuDimension of the control vector

◆ CostModelFramePlacementTpl() [4/4]

CostModelFramePlacementTpl ( boost::shared_ptr< StateMultibody state,
const FramePlacement Fref 
)

Initialize the frame placement cost model.

We use ActivationModelQuadTpl as a default activation model (i.e. \(a=\frac{1}{2}\|\mathbf{r}\|^2\)). Furthermore, the default nu is obtained from StateAbstractTpl::get_nv()

Parameters
[in]stateState of the multibody system
[in]activationActivation model
[in]FrefReference frame placement

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