crocoddyl 1.9.0
Contact RObot COntrol by Differential DYnamic programming Library (Crocoddyl)
 
Loading...
Searching...
No Matches
CostModelFrameTranslationTpl< _Scalar > Class Template Reference

Frame translation cost. More...

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

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

Public Types

typedef ActivationModelAbstractTpl< Scalar > ActivationModelAbstract
 
typedef CostModelResidualTpl< Scalar > Base
 
typedef FrameTranslationTpl< Scalar > FrameTranslation
 
typedef MathBaseTpl< Scalar > MathBase
 
typedef MathBase::Matrix3xs Matrix3xs
 
typedef ResidualModelFrameTranslationTpl< Scalar > ResidualModelFrameTranslation
 
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

 CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameTranslation &xref)
 Initialize the frame translation cost model. More...
 
 CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, boost::shared_ptr< ActivationModelAbstract > activation, const FrameTranslation &xref, const std::size_t nu)
 Initialize the frame translation cost model. More...
 
 CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, const FrameTranslation &xref)
 Initialize the frame translation cost model. More...
 
 CostModelFrameTranslationTpl (boost::shared_ptr< StateMultibody > state, const FrameTranslation &xref, const std::size_t nu)
 Initialize the frame translation 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. More...
 
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)
 
 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)
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr)
 
 CostModelAbstractTpl (boost::shared_ptr< StateAbstract > state, const std::size_t nr, const std::size_t nu)
 
virtual void calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the total cost value for nodes that depends only on the state. More...
 
virtual void calc (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x, const Eigen::Ref< const VectorXs > &u)=0
 Compute the cost value and its residual vector. More...
 
virtual void calcDiff (const boost::shared_ptr< CostDataAbstract > &data, const Eigen::Ref< const VectorXs > &x)
 Compute the Jacobian and Hessian of the cost functions 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)=0
 Compute the Jacobian and Hessian of cost and its residual vector. More...
 
virtual boost::shared_ptr< CostDataAbstractcreateData (DataCollectorAbstract *const data)
 Create the cost data. 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.
 
virtual void print (std::ostream &os) const
 Print relevant information of the cost model. More...
 
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 translation reference. More...
 
virtual void set_referenceImpl (const std::type_info &ti, const void *pv)
 Modify the frame translation reference. More...
 
virtual void get_referenceImpl (const std::type_info &, void *)
 Return the cost reference. More...
 
virtual void set_referenceImpl (const std::type_info &, const void *)
 Modify the cost reference. More...
 

Protected Attributes

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

Detailed Description

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

Frame translation cost.

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

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 42 of file frame-translation.hpp.

Member Typedef Documentation

◆ MathBase

typedef MathBaseTpl<Scalar> MathBase

Definition at line 47 of file frame-translation.hpp.

◆ Base

typedef CostModelResidualTpl<Scalar> Base

Definition at line 48 of file frame-translation.hpp.

◆ StateMultibody

Definition at line 49 of file frame-translation.hpp.

◆ ActivationModelAbstract

Definition at line 50 of file frame-translation.hpp.

◆ ResidualModelFrameTranslation

◆ FrameTranslation

Definition at line 52 of file frame-translation.hpp.

◆ VectorXs

typedef MathBase::VectorXs VectorXs

Definition at line 53 of file frame-translation.hpp.

◆ Matrix3xs

typedef MathBase::Matrix3xs Matrix3xs

Definition at line 54 of file frame-translation.hpp.

Constructor & Destructor Documentation

◆ CostModelFrameTranslationTpl() [1/4]

CostModelFrameTranslationTpl ( boost::shared_ptr< StateMultibody state,
boost::shared_ptr< ActivationModelAbstract activation,
const FrameTranslation xref,
const std::size_t  nu 
)

Initialize the frame translation cost model.

Parameters
[in]stateState of the multibody system
[in]activationActivation model
[in]xrefReference frame translation
[in]nuDimension of the control vector

◆ CostModelFrameTranslationTpl() [2/4]

CostModelFrameTranslationTpl ( boost::shared_ptr< StateMultibody state,
boost::shared_ptr< ActivationModelAbstract activation,
const FrameTranslation xref 
)

Initialize the frame translation cost model.

The default nu is equals to StateAbstractTpl::get_nv().

Parameters
[in]stateState of the multibody system
[in]activationActivation model
[in]xrefReference frame translation

◆ CostModelFrameTranslationTpl() [3/4]

CostModelFrameTranslationTpl ( boost::shared_ptr< StateMultibody state,
const FrameTranslation xref,
const std::size_t  nu 
)

Initialize the frame translation 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]xrefReference frame translation
[in]nuDimension of the control vector

◆ CostModelFrameTranslationTpl() [4/4]

CostModelFrameTranslationTpl ( boost::shared_ptr< StateMultibody state,
const FrameTranslation xref 
)

Initialize the frame translation cost model.

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

Parameters
[in]stateState of the multibody system
[in]xrefReference frame translation

Member Function Documentation

◆ get_referenceImpl()

virtual void get_referenceImpl ( const std::type_info &  ti,
void *  pv 
)
protectedvirtual

Return the frame translation reference.

Reimplemented from CostModelAbstractTpl< _Scalar >.

◆ set_referenceImpl()

virtual void set_referenceImpl ( const std::type_info &  ti,
const void *  pv 
)
protectedvirtual

Modify the frame translation reference.

Reimplemented from CostModelAbstractTpl< _Scalar >.

Member Data Documentation

◆ Scalar

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef _Scalar Scalar

Definition at line 46 of file frame-translation.hpp.

◆ activation_

boost::shared_ptr<ActivationModelAbstract> activation_
protected

Activation model.

Definition at line 128 of file cost-base.hpp.

◆ nu_

std::size_t nu_
protected

Control dimension.

Definition at line 129 of file cost-base.hpp.

◆ residual_

boost::shared_ptr<ResidualModelAbstract> residual_
protected

Residual model.

Definition at line 130 of file cost-base.hpp.

◆ state_

boost::shared_ptr<StateAbstract> state_
protected

State description.

Definition at line 131 of file cost-base.hpp.

◆ unone_

VectorXs unone_
protected

No control vector.

Definition at line 132 of file cost-base.hpp.


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