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