19 #ifndef HPP_RBPRM_DYNAMIC_VALIDATION_HH 20 #define HPP_RBPRM_DYNAMIC_VALIDATION_HH 22 #include <hpp/core/config-validation.hh> 23 #include <hpp/centroidal-dynamics/centroidal_dynamics.hh> 37 virtual std::ostream&
print(std::ostream& os)
const {
38 os <<
"Acceleration " << acc_.transpose() <<
" invalid with current contacts.";
50 static DynamicValidationPtr_t create(
bool rectangularContact,
double sizeFootX,
double sizeFootY,
double mass,
51 double mu, core::DevicePtr_t robot);
61 virtual bool validate(
const core::Configuration_t& config, core::ValidationReportPtr_t& validationReport);
63 void setInitialReport(core::ValidationReportPtr_t initialReport);
66 DynamicValidation(
bool rectangularContact,
double sizeFootX,
double sizeFootY,
double mass,
double mu,
67 core::DevicePtr_t robot);
70 bool rectangularContact_;
76 centroidal_dynamics::Equilibrium* sEq_;
79 core::Configuration_t lastAcc_;
88 #endif // HPP_RBPRM_DYNAMIC_VALIDATION_HH Eigen::Matrix< pinocchio::value_type, 3, 1 > Vector3
Definition: rbprm-limb.hh:48
std::shared_ptr< RbPrmDevice > RbPrmDevicePtr_t
Definition: dynamic-validation.hh:27
Definition: algorithm.hh:27
centroidal_dynamics::Vector3 acc_
Definition: dynamic-validation.hh:42
std::shared_ptr< DynamicValidation > DynamicValidationPtr_t
Definition: dynamic-validation.hh:46
centroidal_dynamics::Matrix63 Matrix63
Definition: rbprm-node.hh:20
HPP_PREDEF_CLASS(RbPrmDevice)
std::shared_ptr< RbprmValidationReport > RbprmValidationReportPtr_t
Definition: rbprm-validation-report.hh:29
Definition: rbprm-device.hh:44
DynamicValidationReport(centroidal_dynamics::Vector3 acc)
Definition: dynamic-validation.hh:35
Definition: dynamic-validation.hh:48
virtual std::ostream & print(std::ostream &os) const
Print report in a stream.
Definition: dynamic-validation.hh:37
centroidal_dynamics::Vector6 Vector6
Definition: rbprm-node.hh:21
Exception thrown when a configuration is not within the bounds.
Definition: dynamic-validation.hh:33