#include <quadruped-walkgen/quadruped_time.hpp>
Public Types | |
typedef _Scalar | Scalar |
typedef crocoddyl::ActionDataAbstractTpl< Scalar > | ActionDataAbstract |
typedef crocoddyl::ActionModelAbstractTpl< Scalar > | Base |
typedef crocoddyl::MathBaseTpl< Scalar > | MathBase |
Public Member Functions | |
ActionModelQuadrupedTimeTpl () | |
~ActionModelQuadrupedTimeTpl () | |
virtual void | calc (const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const typename MathBase::VectorXs > &x, const Eigen::Ref< const typename MathBase::VectorXs > &u) |
virtual void | calcDiff (const boost::shared_ptr< ActionDataAbstract > &data, const Eigen::Ref< const typename MathBase::VectorXs > &x, const Eigen::Ref< const typename MathBase::VectorXs > &u) |
virtual boost::shared_ptr< ActionDataAbstract > | createData () |
const Eigen::Matrix< Scalar, 12, 1 > & | get_state_weights () const |
void | set_state_weights (const typename MathBase::VectorXs &weights) |
const Eigen::Matrix< Scalar, 8, 1 > & | get_heuristic_weights () const |
void | set_heuristic_weights (const typename MathBase::VectorXs &weights) |
void | update_model (const Eigen::Ref< const typename MathBase::MatrixXs > &l_feet, const Eigen::Ref< const typename MathBase::MatrixXs > &xref, const Eigen::Ref< const typename MathBase::VectorXs > &S) |
const bool & | get_symmetry_term () const |
void | set_symmetry_term (const bool &sym_term) |
const bool & | get_centrifugal_term () const |
void | set_centrifugal_term (const bool ¢_term) |
const Scalar & | get_T_gait () const |
void | set_T_gait (const Scalar &T_gait_) |
const Scalar & | get_dt_ref () const |
void | set_dt_ref (const Scalar &dt) |
const Scalar & | get_dt_min () const |
void | set_dt_min (const Scalar &dt) |
const Scalar & | get_dt_max () const |
void | set_dt_max (const Scalar &dt) |
const Scalar & | get_dt_weight_cmd () const |
void | set_dt_weight_cmd (const Scalar &weight_) |
const Scalar & | get_dt_bound_weight_cmd () const |
void | set_dt_bound_weight_cmd (const Scalar &weight_) |
const Eigen::Matrix< Scalar, 7, 1 > & | get_cost () const |
typedef crocoddyl::ActionDataAbstractTpl<Scalar> quadruped_walkgen::ActionModelQuadrupedTimeTpl< _Scalar >::ActionDataAbstract |
typedef crocoddyl::ActionModelAbstractTpl<Scalar> quadruped_walkgen::ActionModelQuadrupedTimeTpl< _Scalar >::Base |
typedef crocoddyl::MathBaseTpl<Scalar> quadruped_walkgen::ActionModelQuadrupedTimeTpl< _Scalar >::MathBase |
typedef _Scalar quadruped_walkgen::ActionModelQuadrupedTimeTpl< _Scalar >::Scalar |
quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::ActionModelQuadrupedTimeTpl |
quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::~ActionModelQuadrupedTimeTpl |
|
virtual |
|
virtual |
|
virtual |
const bool & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_centrifugal_term |
const Eigen::Matrix< Scalar, 7, 1 > & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_cost |
const Scalar & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_dt_bound_weight_cmd |
const Scalar & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_dt_max |
const Scalar & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_dt_min |
const Scalar & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_dt_ref |
const Scalar & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_dt_weight_cmd |
const Eigen::Matrix< Scalar, 8, 1 > & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_heuristic_weights |
const Eigen::Matrix< Scalar, 12, 1 > & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_state_weights |
const bool & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_symmetry_term |
const Scalar & quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::get_T_gait |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_centrifugal_term | ( | const bool & | cent_term | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_dt_bound_weight_cmd | ( | const Scalar & | weight_ | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_dt_max | ( | const Scalar & | dt | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_dt_min | ( | const Scalar & | dt | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_dt_ref | ( | const Scalar & | dt | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_dt_weight_cmd | ( | const Scalar & | weight_ | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_heuristic_weights | ( | const typename MathBase::VectorXs & | weights | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_state_weights | ( | const typename MathBase::VectorXs & | weights | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_symmetry_term | ( | const bool & | sym_term | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::set_T_gait | ( | const Scalar & | T_gait_ | ) |
void quadruped_walkgen::ActionModelQuadrupedTimeTpl< Scalar >::update_model | ( | const Eigen::Ref< const typename MathBase::MatrixXs > & | l_feet, |
const Eigen::Ref< const typename MathBase::MatrixXs > & | xref, | ||
const Eigen::Ref< const typename MathBase::VectorXs > & | S | ||
) |