20 #include <boost/test/unit_test.hpp> 21 #include <boost/utility/binary.hpp> 31 #include <tsid/solvers/solver-HQP-factory.hxx> 37 #include <pinocchio/algorithm/joint-configuration.hpp> 38 #include <pinocchio/parsers/srdf.hpp> 49 #define REQUIRE_FINITE(A) BOOST_REQUIRE_MESSAGE(isFinite(A), #A << ": " << A) 50 #define CHECK_LESS_THAN(A, B) \ 51 BOOST_CHECK_MESSAGE(A < B, #A << ": " << A << ">" << B) 53 #define REQUIRE_TASK_FINITE(task) \ 54 REQUIRE_FINITE(task.getConstraint().matrix()); \ 55 REQUIRE_FINITE(task.getConstraint().vector()) 57 #define REQUIRE_CONTACT_FINITE(contact) \ 58 REQUIRE_FINITE(contact.getMotionConstraint().matrix()); \ 59 REQUIRE_FINITE(contact.getMotionConstraint().vector()); \ 60 REQUIRE_FINITE(contact.getForceConstraint().matrix()); \ 61 REQUIRE_FINITE(contact.getForceConstraint().lowerBound()); \ 62 REQUIRE_FINITE(contact.getForceConstraint().upperBound()); \ 63 REQUIRE_FINITE(contact.getForceRegularizationTask().matrix()); \ 64 REQUIRE_FINITE(contact.getForceRegularizationTask().vector()) 75 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
79 static const double lxp;
80 static const double lxn;
81 static const double lyp;
82 static const double lyn;
83 static const double lz;
84 static const double mu;
98 std::shared_ptr<RobotWrapper>
robot;
99 std::shared_ptr<InverseDynamicsFormulationAccForce>
tsid;
113 const string urdfFileName = package_dirs[0] +
"/urdf/romeo.urdf";
114 robot = std::make_shared<RobotWrapper>(urdfFileName, package_dirs,
117 const string srdfFileName = package_dirs[0] +
"/srdf/romeo_collision.srdf";
122 const unsigned int nv{
static_cast<unsigned int>(robot->nv())};
124 std::cout <<
"q: " << q.transpose() << std::endl;
126 v = Vector::Zero(
nv);
127 BOOST_REQUIRE(robot->model().existFrame(rf_frame_name));
128 BOOST_REQUIRE(robot->model().existFrame(lf_frame_name));
131 tsid = std::make_shared<InverseDynamicsFormulationAccForce>(
"tsid", *
robot);
132 tsid->computeProblemData(t, q, v);
137 contactPoints << -
lxn, -
lxn, +
lxp, +
lxp, -
lyn, +
lyp, -
lyn, +
lyp,
lz,
lz,
lz,
139 contactRF = std::make_shared<Contact6d>(
"contact_rfoot", *
robot,
142 contactRF->Kp(kp_contact * Vector::Ones(6));
143 contactRF->Kd(2.0 * contactRF->Kp().cwiseSqrt());
144 H_rf_ref = robot->position(data, robot->model().getJointId(rf_frame_name));
145 contactRF->setReference(H_rf_ref);
146 tsid->addRigidContact(*contactRF, w_forceReg);
148 contactLF = std::make_shared<Contact6d>(
"contact_lfoot", *
robot,
151 contactLF->Kp(kp_contact * Vector::Ones(6));
152 contactLF->Kd(2.0 * contactLF->Kp().cwiseSqrt());
153 H_lf_ref = robot->position(data, robot->model().getJointId(lf_frame_name));
154 contactLF->setReference(H_lf_ref);
155 tsid->addRigidContact(*contactLF, w_forceReg);
158 comTask = std::make_shared<TaskComEquality>(
"task-com", *
robot);
159 comTask->Kp(kp_com * Vector::Ones(3));
160 comTask->Kd(2.0 * comTask->Kp().cwiseSqrt());
161 tsid->addMotionTask(*comTask, w_com, 1);
164 postureTask = std::make_shared<TaskJointPosture>(
"task-posture", *
robot);
165 postureTask->Kp(kp_posture * Vector::Ones(
nv - 6));
166 postureTask->Kd(2.0 * postureTask->Kp().cwiseSqrt());
167 tsid->addMotionTask(*postureTask, w_posture, 1);
171 std::make_shared<TaskJointBounds>(
"task-joint-bounds", *
robot,
dt);
172 Vector dq_max = 10 * Vector::Ones(robot->na());
174 jointBoundsTask->setVelocityBounds(dq_min, dq_max);
175 tsid->addMotionTask(*jointBoundsTask, 1.0, 0);
198 cout <<
"\n*** test_invdyn_formulation_acc_force_remove_contact ***\n";
199 const double dt = 0.01;
200 const unsigned int PRINT_N = 10;
203 const double kp_RF = 100.0;
204 const double w_RF = 1e3;
232 std::make_shared<TrajectoryEuclidianConstant>(
"traj_com",
com_ref);
237 std::make_shared<TrajectoryEuclidianConstant>(
"traj_posture",
q_ref);
247 if (
i == REMOVE_CONTACT_N) {
248 cout <<
"Start breaking contact right foot\n";
252 sampleCom =
trajCom->computeNext();
278 if ((tau - tau_old).norm() > 2e1)
282 cout <<
"Time " <<
i << endl;
284 << tau.transpose() <<
"\ntauOld:\n" 285 << tau_old.transpose() <<
"\n";
297 if (
i % PRINT_N == 0) {
298 cout <<
"Time " <<
i << endl;
300 Eigen::Matrix<double, 12, 1>
f;
302 cout <<
" " << contactRF.
name()
306 cout <<
" " << contactLF.
name()
311 cout <<
"v=" << v.norm() <<
"\t dv=" << dv.norm() << endl;
326 cout <<
"\n### TEST FINISHED ###\n";
328 cout <<
"Final CoM position: " << robot.com(
tsid->data()).transpose()
330 cout <<
"Desired CoM position: " << com_ref.transpose() << endl;
334 cout <<
"\n*** test_invdyn_formulation_acc_force ***\n";
336 const double dt = 0.001;
337 const unsigned int PRINT_N = 100;
354 std::make_shared<TrajectoryEuclidianConstant>(
"traj_com",
com_ref);
359 std::make_shared<TrajectoryEuclidianConstant>(
"traj_posture",
q_ref);
367 cout <<
"nVar " <<
tsid->nVar() << endl;
368 cout <<
"nEq " <<
tsid->nEq() << endl;
369 cout <<
"nIn " <<
tsid->nIn() << endl;
370 cout <<
"Initial CoM position: " << robot.
com(
tsid->data()).transpose()
372 cout <<
"Initial RF position: " << romeo_inv_dyn.
H_rf_ref << endl;
373 cout <<
"Initial LF position: " << romeo_inv_dyn.
H_lf_ref << endl;
378 contacts.push_back(&contactRF);
379 contacts.push_back(&contactLF);
382 sampleCom =
trajCom->computeNext();
406 cout <<
"RF pos: " << rf_pos.transpose() << endl;
407 cout <<
"RF pos ref: " << rf_pos_ref.transpose() << endl;
410 if (
i % PRINT_N == 0) {
411 cout <<
"Time " <<
i << endl;
412 cout <<
" " << contactRF.
name()
415 cout << contactLF.
name()
420 cout << postureTask.
name()
422 cout <<
"v=" << v.norm() <<
"\t dv=" << dv.norm() << endl;
433 for (ConstraintLevel::const_iterator it = HQPData[0].begin();
434 it != HQPData[0].end(); it++) {
435 auto constr = it->second;
436 if (constr->checkConstraint(sol.
x) ==
false) {
437 if (constr->isEquality()) {
440 "Equality " + constr->name() +
" violated: " +
442 (constr->matrix() * sol.
x - constr->vector()).norm()));
443 }
else if (constr->isInequality()) {
446 "Inequality " + constr->name() +
" violated: " +
447 toString((constr->matrix() * sol.
x - constr->lowerBound())
450 toString((constr->upperBound() - constr->matrix() * sol.
x)
452 }
else if (constr->isBound()) {
454 false,
"Bound " + constr->name() +
" violated: " +
455 toString((sol.
x - constr->lowerBound()).minCoeff()) +
457 toString((constr->upperBound() - sol.
x).minCoeff()));
464 f_LF = sol.
x.segment<12>(nv + 12);
498 cout <<
"\n### TEST FINISHED ###\n";
500 cout <<
"Final CoM position: " << robot.
com(
tsid->data()).transpose()
502 cout <<
"Desired CoM position: " << com_ref.transpose() << endl;
506 cout <<
"\n*** test_contact_point_invdyn_formulation_acc_force ***\n";
508 const double mu = 0.3;
509 const double fMin = 0.0;
510 const double fMax = 10.0;
511 const std::string
frameName =
"base_link";
512 const double dt = 1e-3;
517 double w_forceReg = 1e-5;
523 string urdfFileName = package_dirs[0] +
"/urdf/quadruped.urdf";
531 const unsigned int nv = robot.
nv();
537 for (
int i = 0;
i < 4;
i++) {
544 std::make_shared<InverseDynamicsFormulationAccForce>(
"tsid",
robot);
545 tsid->computeProblemData(t, q, v);
552 q[2] -= fl_contact.translation()(2);
554 tsid->computeProblemData(t, q, v);
557 auto comTask = std::make_shared<TaskComEquality>(
"task-com",
robot);
558 comTask->Kp(kp_com * Vector::Ones(3));
564 std::make_shared<TrajectoryEuclidianConstant>(
"traj_com",
com_ref);
566 sampleCom =
trajCom->computeNext();
567 comTask->setReference(sampleCom);
570 std::string contactFrames[] = {
"BL_contact",
"BR_contact",
"FL_contact",
574 std::vector<std::shared_ptr<ContactPoint>>
contacts(4);
576 for (
int i = 0;
i < 4;
i++) {
577 auto cp = std::make_shared<ContactPoint>(
"contact_" + contactFrames[
i],
580 cp->Kp(kp_contact * Vector::Ones(3));
581 cp->Kd(2.0 * sqrt(kp_contact) * Vector::Ones(3));
583 robot.framePosition(data, robot.model().getFrameId(contactFrames[
i])));
584 cp->useLocalFrame(
false);
585 tsid->addRigidContact(*
cp, w_forceReg, 1.0, 1);
602 for (
unsigned int i = 0;
i < contacts.size();
i++) {
606 sol = &(solver->
solve(HQPData));
611 for (ConstraintLevel::const_iterator it = HQPData[0].begin();
612 it != HQPData[0].end(); it++) {
613 auto constr = it->second;
614 if (constr->checkConstraint(sol->
x) ==
false) {
615 if (constr->isEquality()) {
618 "Equality " + constr->name() +
" violated: " +
620 (constr->matrix() * sol->
x - constr->vector()).norm()));
621 }
else if (constr->isInequality()) {
624 "Inequality " + constr->name() +
" violated: " +
625 toString((constr->matrix() * sol->
x - constr->lowerBound())
628 toString((constr->upperBound() - constr->matrix() * sol->
x)
630 }
else if (constr->isBound()) {
632 false,
"Bound " + constr->name() +
" violated: " +
633 toString((sol->
x - constr->lowerBound()).minCoeff()) +
635 toString((constr->upperBound() - sol->
x).minCoeff()));
640 dv = sol->
x.head(nv);
653 for (
int i = 0;
i < 4;
i++) {
654 Eigen::Matrix<double, 3, 1>
f;
655 tsid->getContactForces(contacts[
i]->
name(), *sol, f);
656 cout << contacts[
i]->name() <<
" force:" << f.transpose() << endl;
661 cout <<
"\n### TEST FINISHED ###\n";
663 cout <<
"Final CoM position: " << robot.
com(
tsid->data()).transpose()
665 cout <<
"Desired CoM position: " << com_ref.transpose() << endl;
668 #define PROFILE_CONTROL_CYCLE "Control cycle" 669 #define PROFILE_PROBLEM_FORMULATION "Problem formulation" 670 #define PROFILE_HQP "HQP" 671 #define PROFILE_HQP_FAST "HQP_FAST" 672 #define PROFILE_HQP_RT "HQP_RT" 675 cout <<
"\n*** test_invdyn_formulation_acc_force_computation_time ***\n";
677 const double dt = 0.001;
692 std::make_shared<TrajectoryEuclidianConstant>(
"traj_com",
com_ref);
697 std::make_shared<TrajectoryEuclidianConstant>(
"traj_posture",
q_ref);
703 SolverHQPBase *solver_fast = SolverHQPFactory::createNewSolver(
705 SolverHQPBase *solver_rt = SolverHQPFactory::createNewSolver<61, 18, 71>(
706 SOLVER_HQP_EIQUADPROG_RT,
"eiquadprog-rt");
715 sampleCom =
trajCom->computeNext();
735 solver_rt->
solve(HQPData);
739 static_cast<double>(sol_fast.
activeSet.size()));
754 cout <<
"\n### TEST FINISHED ###\n";
759 BOOST_AUTO_TEST_SUITE_END()
void loadReferenceConfigurations(ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const bool verbose=false)
Stopwatch & getProfiler()
std::string HQPDataToString(const HQPData &data, bool printMatrices=false)
const Vector & position_error() const
std::shared_ptr< TaskJointBounds > jointBoundsTask
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
std::shared_ptr< TaskComEquality > comTask
std::string toString(const T &v)
std::shared_ptr< TaskJointPosture > postureTask
const std::string & name() const
void store(std::string name, const double &value)
bool existFrame(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
void stop(std::string perf_name)
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
void setReference(const TrajectorySample &ref)
std::shared_ptr< InverseDynamicsFormulationAccForce > tsid
const Model & model() const
Accessor to model.
static const double kp_com
static const double w_forceReg
std::shared_ptr< RobotWrapper > robot
void report_all(int precision=2, std::ostream &output=std::cout)
static const std::string lf_frame_name
void integrate(const LieGroupGenericTpl< LieGroupCollection > &lg, const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout)
static const std::string rf_frame_name
const Vector & position_error() const
SOLVER_HQP_EIQUADPROG_FAST
const Vector & position() const
Eigen::Matrix< Scalar, 3, 1 > Vector3
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
std::shared_ptr< Contact6d > contactRF
static const Vector3 contactNormal
FrameIndex getFrameId(const std::string &name, const FrameType &type=(FrameType)(JOINT|FIXED_JOINT|BODY|OP_FRAME|SENSOR)) const
static const double w_com
void com(const Data &data, RefVector com_pos, RefVector com_vel, RefVector com_acc) const
virtual void resize(unsigned int n, unsigned int neq, unsigned int nin)=0
static const double w_posture
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
const Vector & position_error() const
bool checkConstraint(ConstRefVector x, double tol=1e-6) const
Wrapper for a robot based on pinocchio.
std::shared_ptr< Contact6d > contactLF
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
void vectorToSE3(RefVector vec, pinocchio::SE3 &M)
static const double kp_posture
void setReference(const TrajectorySample &ref)
virtual const HQPOutput & solve(const HQPData &problemData)=0
void start(std::string perf_name)
const Vector & position_ref() const
JointModelFreeFlyerTpl< double > JointModelFreeFlyer
Statistics & getStatistics()
VectorXi activeSet
Lagrange multipliers.
int iterations
indexes of active inequalities
void report_all(int precision=2, std::ostream &output=std::cout)
StandardRomeoInvDynCtrl(double dt)
static const double kp_contact
Abstract interface for a Quadratic Program (HQP) solver.