Directory: | ./ |
---|---|
File: | unittest/utils/model-generator.hpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 41 | 41 | 100.0% |
Branches: | 90 | 180 | 50.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2015-2020 CNRS INRIA | ||
3 | // | ||
4 | |||
5 | #include "pinocchio/multibody/model.hpp" | ||
6 | |||
7 | namespace pinocchio | ||
8 | { | ||
9 | |||
10 | template<typename D> | ||
11 | 286 | void addJointAndBody( | |
12 | Model & model, | ||
13 | const JointModelBase<D> & jmodel, | ||
14 | const Model::JointIndex parent_id, | ||
15 | const SE3 & joint_placement, | ||
16 | const std::string & name, | ||
17 | const Inertia & Y) | ||
18 | { | ||
19 | Model::JointIndex idx; | ||
20 | typedef typename D::TangentVector_t TV; | ||
21 | typedef typename D::ConfigVector_t CV; | ||
22 | |||
23 |
17/34✓ Branch 1 taken 143 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 143 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 143 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 143 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 143 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 143 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 143 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 143 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 143 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 143 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 143 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 143 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 143 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 143 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 143 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 143 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 143 times.
✗ Branch 50 not taken.
|
1144 | idx = model.addJoint( |
24 | parent_id, jmodel, joint_placement, name + "_joint", TV::Zero(), | ||
25 |
2/4✓ Branch 1 taken 143 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 143 times.
✗ Branch 5 not taken.
|
858 | 1e3 * (TV::Random() + TV::Constant(1)), 1e3 * (CV::Random() - CV::Constant(1)), |
26 |
1/2✓ Branch 1 taken 143 times.
✗ Branch 2 not taken.
|
286 | 1e3 * (CV::Random() + CV::Constant(1))); |
27 | |||
28 |
1/2✓ Branch 2 taken 143 times.
✗ Branch 3 not taken.
|
286 | model.appendBodyToJoint(idx, Y, SE3::Identity()); |
29 | 286 | } | |
30 | |||
31 | 13 | void buildAllJointsModel(Model & model) | |
32 | { | ||
33 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
34 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelFreeFlyer(), model.getJointId("universe"), SE3::Identity(), "freeflyer", |
35 | 13 | Inertia::Random()); | |
36 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
37 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelSpherical(), model.getJointId("freeflyer_joint"), SE3::Identity(), |
38 | 13 | "spherical", Inertia::Random()); | |
39 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
40 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelPlanar(), model.getJointId("spherical_joint"), SE3::Identity(), "planar", |
41 | 13 | Inertia::Random()); | |
42 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
43 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelRX(), model.getJointId("planar_joint"), SE3::Identity(), "rx", |
44 | 13 | Inertia::Random()); | |
45 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
46 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelPX(), model.getJointId("rx_joint"), SE3::Identity(), "px", |
47 | 13 | Inertia::Random()); | |
48 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
49 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelHX(1.0), model.getJointId("px_joint"), SE3::Identity(), "hx", |
50 | 13 | Inertia::Random()); | |
51 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
52 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
26 | model, JointModelPrismaticUnaligned(SE3::Vector3(1, 0, 0)), model.getJointId("hx_joint"), |
53 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
39 | SE3::Identity(), "pu", Inertia::Random()); |
54 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
55 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
26 | model, JointModelRevoluteUnaligned(SE3::Vector3(0, 0, 1)), model.getJointId("pu_joint"), |
56 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
39 | SE3::Identity(), "ru", Inertia::Random()); |
57 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
58 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
26 | model, JointModelHelicalUnaligned(SE3::Vector3(0, 0, 1), 1.0), model.getJointId("ru_joint"), |
59 |
1/2✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
|
39 | SE3::Identity(), "hu", Inertia::Random()); |
60 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
61 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelSphericalZYX(), model.getJointId("hu_joint"), SE3::Identity(), |
62 | 13 | "sphericalZYX", Inertia::Random()); | |
63 |
4/8✓ Branch 2 taken 13 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 13 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 13 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 13 times.
✗ Branch 13 not taken.
|
65 | addJointAndBody( |
64 |
2/4✓ Branch 1 taken 13 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 13 times.
✗ Branch 5 not taken.
|
52 | model, JointModelTranslation(), model.getJointId("sphericalZYX_joint"), SE3::Identity(), |
65 | 13 | "translation", Inertia::Random()); | |
66 | 13 | } | |
67 | |||
68 | } // namespace pinocchio | ||
69 |