contacts.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 CNRS
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid is distributed in the hope that it will be
10 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see
15 // <http://www.gnu.org/licenses/>.
16 //
17 
18 #include <iostream>
19 
20 #include <boost/test/unit_test.hpp>
21 #include <boost/utility/binary.hpp>
22 
24 
27 
28 using namespace tsid;
29 using namespace trajectories;
30 using namespace math;
31 using namespace contacts;
32 using namespace tsid::robots;
33 using namespace std;
34 
35 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
36 
37 #define REQUIRE_FINITE(A) BOOST_REQUIRE_MESSAGE(isFinite(A), #A << ": " << A)
38 
39 const string romeo_model_path = TSID_SOURCE_DIR "/models/romeo";
40 
41 BOOST_AUTO_TEST_CASE(test_contact_6d) {
42  const double lx = 0.07;
43  const double ly = 0.12;
44  const double lz = 0.105;
45  const double mu = 0.3;
46  const double fMin = 10.0;
47  const double fMax = 1000.0;
48  const std::string frameName = "r_sole_joint";
49 
50  vector<string> package_dirs;
51  package_dirs.push_back(romeo_model_path);
52  string urdfFileName = package_dirs[0] + "/urdf/romeo.urdf";
53  RobotWrapper robot(urdfFileName, package_dirs,
55 
56  BOOST_REQUIRE(robot.model().existFrame(frameName));
57 
58  Vector3 contactNormal = Vector3::UnitZ();
59  Matrix3x contactPoints(3, 4);
60  contactPoints << -lx, -lx, +lx, +lx, -ly, +ly, -ly, +ly, lz, lz, lz, lz;
61  Contact6d contact("contact6d", robot, frameName, contactPoints, contactNormal,
62  mu, fMin, fMax);
63 
64  BOOST_CHECK(contact.n_motion() == 6);
65  BOOST_CHECK(contact.n_force() == 12);
66 
67  Vector Kp = Vector::Ones(6);
68  Vector Kd = 2 * Vector::Ones(6);
69  contact.Kp(Kp);
70  contact.Kd(Kd);
71  BOOST_CHECK(contact.Kp().isApprox(Kp));
72  BOOST_CHECK(contact.Kd().isApprox(Kd));
73 
74  Vector q = neutral(robot.model());
75  Vector v = Vector::Zero(robot.nv());
76  pinocchio::Data data(robot.model());
77  robot.computeAllTerms(data, q, v);
78 
80  robot.position(data, robot.model().getFrameId(frameName));
81  contact.setReference(H_ref);
82 
83  double t = 0.0;
84  contact.computeMotionTask(t, q, v, data);
85 
86  const ConstraintInequality& forceIneq =
87  contact.computeForceTask(t, q, v, data);
88  Vector3 f3;
89  Vector f(12);
90  f3 << 0.0, 0.0, 100.0;
91  f << f3, f3, f3, f3;
92  BOOST_CHECK(forceIneq.checkConstraint(f));
93  BOOST_CHECK(
94  ((forceIneq.matrix() * f).array() <= forceIneq.upperBound().array())
95  .all());
96  BOOST_CHECK(
97  ((forceIneq.matrix() * f).array() >= forceIneq.lowerBound().array())
98  .all());
99  f(0) = f(2) * mu * 1.1;
100  BOOST_CHECK(forceIneq.checkConstraint(f) == false);
101 
102  const Matrix& forceGenMat = contact.getForceGeneratorMatrix();
103  BOOST_CHECK(forceGenMat.rows() == 6 && forceGenMat.cols() == 12);
104 
105  contact.computeForceRegularizationTask(t, q, v, data);
106 }
107 
108 BOOST_AUTO_TEST_SUITE_END()
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_contact_6d)
Definition: contacts.cpp:41
romeo_model_path
const string romeo_model_path
Definition: contacts.cpp:39
demo_quadruped.v
v
Definition: demo_quadruped.py:80
test_Contact.forceGenMat
forceGenMat
Definition: test_Contact.py:71
demo_quadruped.fMax
float fMax
Definition: demo_quadruped.py:27
pinocchio::DataTpl
ex_4_conf.lz
float lz
Definition: ex_4_conf.py:29
pinocchio::SE3
context::SE3 SE3
test_Contact.forceIneq
forceIneq
Definition: test_Contact.py:61
setup.data
data
Definition: setup.in.py:48
tsid::robots
Definition: robots/fwd.hpp:22
demo_quadruped.robot
robot
Definition: demo_quadruped.py:51
tsid::math::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
test_Contact.Kp
Kp
Definition: test_Contact.py:44
pinocchio::JointModelFreeFlyerTpl
f
f
test_Contact.f3
f3
Definition: test_Contact.py:62
test_Contact.contact
contact
Definition: test_Contact.py:37
demo_quadruped.q
q
Definition: demo_quadruped.py:74
robot-wrapper.hpp
package_dirs
package_dirs
tsid::math::Matrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
Definition: math/fwd.hpp:36
demo_quadruped.contacts
int contacts
Definition: demo_quadruped.py:98
test_Contact.lx
float lx
Definition: test_Contact.py:23
demo_quadruped.mu
float mu
Definition: demo_quadruped.py:25
tsid::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
joint-configuration.hpp
test_Contact.ly
float ly
Definition: test_Contact.py:24
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
contact-6d.hpp
test_Contact.H_ref
H_ref
Definition: test_Contact.py:56
std
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
demo_quadruped.fMin
float fMin
Definition: demo_quadruped.py:26
test_Contact.Kd
int Kd
Definition: test_Contact.py:45
neutral
void neutral(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ReturnType > &qout)
t
Transform3f t
test_Contact.frameName
string frameName
Definition: test_Contact.py:29
demo_quadruped.contactNormal
contactNormal
Definition: demo_quadruped.py:29
tsid::math::Vector3
Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition: math/fwd.hpp:40


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:15