File: btMultiBodyTreeCreator.cpp

package info (click to toggle)
bullet 2.87%2Bdfsg-3
  • links: PTS, VCS
  • area: main
  • in suites: buster
  • size: 14,272 kB
  • sloc: cpp: 204,241; ansic: 12,100; lisp: 12,017; python: 593; makefile: 136; sh: 8
file content (270 lines) | stat: -rw-r--r-- 12,284 bytes parent folder | download
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
#include "btMultiBodyTreeCreator.hpp"

namespace btInverseDynamics {

btMultiBodyTreeCreator::btMultiBodyTreeCreator() : m_initialized(false) {}

int btMultiBodyTreeCreator::createFromBtMultiBody(const btMultiBody *btmb, const bool verbose) {
    if (0x0 == btmb) {
        error_message("cannot create MultiBodyTree from null pointer\n");
        return -1;
    }

    // in case this is a second call, discard old data
    m_data.clear();
    m_initialized = false;

    // btMultiBody treats base link separately
    m_data.resize(1 + btmb->getNumLinks());

    // add base link data
    {
        LinkData &link = m_data[0];

        link.parent_index = -1;
        if (btmb->hasFixedBase()) {
            link.joint_type = FIXED;
        } else {
            link.joint_type = FLOATING;
        }
        btTransform transform(btmb->getBaseWorldTransform());

        link.parent_r_parent_body_ref(0) = transform.getOrigin()[0];
        link.parent_r_parent_body_ref(1) = transform.getOrigin()[1];
        link.parent_r_parent_body_ref(2) = transform.getOrigin()[2];

        link.body_T_parent_ref(0, 0) = transform.getBasis()[0][0];
        link.body_T_parent_ref(0, 1) = transform.getBasis()[0][1];
        link.body_T_parent_ref(0, 2) = transform.getBasis()[0][2];

        link.body_T_parent_ref(1, 0) = transform.getBasis()[1][0];
        link.body_T_parent_ref(1, 1) = transform.getBasis()[1][1];
        link.body_T_parent_ref(1, 2) = transform.getBasis()[1][2];

        link.body_T_parent_ref(2, 0) = transform.getBasis()[2][0];
        link.body_T_parent_ref(2, 1) = transform.getBasis()[2][1];
        link.body_T_parent_ref(2, 2) = transform.getBasis()[2][2];

        // random unit vector. value not used for fixed or floating joints.
        link.body_axis_of_motion(0) = 0;
        link.body_axis_of_motion(1) = 0;
        link.body_axis_of_motion(2) = 1;

        link.mass = btmb->getBaseMass();
        // link frame in the center of mass
        link.body_r_body_com(0) = 0;
        link.body_r_body_com(1) = 0;
        link.body_r_body_com(2) = 0;
        // BulletDynamics uses body-fixed frame in the cog, aligned with principal axes
        link.body_I_body(0, 0) = btmb->getBaseInertia()[0];
        link.body_I_body(0, 1) = 0.0;
        link.body_I_body(0, 2) = 0.0;
        link.body_I_body(1, 0) = 0.0;
        link.body_I_body(1, 1) = btmb->getBaseInertia()[1];
        link.body_I_body(1, 2) = 0.0;
        link.body_I_body(2, 0) = 0.0;
        link.body_I_body(2, 1) = 0.0;
        link.body_I_body(2, 2) = btmb->getBaseInertia()[2];
        // shift reference point to link origin (in joint axis)
        mat33 tilde_r_com = tildeOperator(link.body_r_body_com);
        link.body_I_body = link.body_I_body - link.mass * tilde_r_com * tilde_r_com;
        if (verbose) {
            id_printf("base: mass= %f, bt_inertia= [%f %f %f]\n"
                      "Io= [%f %f %f;\n"
                      "    %f %f %f;\n"
                      "    %f %f %f]\n",
                      link.mass, btmb->getBaseInertia()[0], btmb->getBaseInertia()[1],
                      btmb->getBaseInertia()[2], link.body_I_body(0, 0), link.body_I_body(0, 1),
                      link.body_I_body(0, 2), link.body_I_body(1, 0), link.body_I_body(1, 1),
                      link.body_I_body(1, 2), link.body_I_body(2, 0), link.body_I_body(2, 1),
                      link.body_I_body(2, 2));
        }
    }

    for (int bt_index = 0; bt_index < btmb->getNumLinks(); bt_index++) {
        if (verbose) {
            id_printf("bt->id: converting link %d\n", bt_index);
        }
        const btMultibodyLink &bt_link = btmb->getLink(bt_index);
        LinkData &link = m_data[bt_index + 1];

        link.parent_index = bt_link.m_parent + 1;

        link.mass = bt_link.m_mass;
        if (verbose) {
            id_printf("mass= %f\n", link.mass);
        }
        // from this body's pivot to this body's com in this body's frame
        link.body_r_body_com[0] = bt_link.m_dVector[0];
        link.body_r_body_com[1] = bt_link.m_dVector[1];
        link.body_r_body_com[2] = bt_link.m_dVector[2];
        if (verbose) {
            id_printf("com= %f %f %f\n", link.body_r_body_com[0], link.body_r_body_com[1],
                      link.body_r_body_com[2]);
        }
        // BulletDynamics uses a body-fixed frame in the CoM, aligned with principal axes
        link.body_I_body(0, 0) = bt_link.m_inertiaLocal[0];
        link.body_I_body(0, 1) = 0.0;
        link.body_I_body(0, 2) = 0.0;
        link.body_I_body(1, 0) = 0.0;
        link.body_I_body(1, 1) = bt_link.m_inertiaLocal[1];
        link.body_I_body(1, 2) = 0.0;
        link.body_I_body(2, 0) = 0.0;
        link.body_I_body(2, 1) = 0.0;
        link.body_I_body(2, 2) = bt_link.m_inertiaLocal[2];
        // shift reference point to link origin (in joint axis)
        mat33 tilde_r_com = tildeOperator(link.body_r_body_com);
        link.body_I_body = link.body_I_body - link.mass * tilde_r_com * tilde_r_com;

        if (verbose) {
            id_printf("link %d: mass= %f, bt_inertia= [%f %f %f]\n"
                      "Io= [%f %f %f;\n"
                      "    %f %f %f;\n"
                      "    %f %f %f]\n",
                      bt_index, link.mass, bt_link.m_inertiaLocal[0], bt_link.m_inertiaLocal[1],
                      bt_link.m_inertiaLocal[2], link.body_I_body(0, 0), link.body_I_body(0, 1),
                      link.body_I_body(0, 2), link.body_I_body(1, 0), link.body_I_body(1, 1),
                      link.body_I_body(1, 2), link.body_I_body(2, 0), link.body_I_body(2, 1),
                      link.body_I_body(2, 2));
        }
        // transform for vectors written in parent frame to this link's body-fixed frame
        btMatrix3x3 basis = btTransform(bt_link.m_zeroRotParentToThis).getBasis();
        link.body_T_parent_ref(0, 0) = basis[0][0];
        link.body_T_parent_ref(0, 1) = basis[0][1];
        link.body_T_parent_ref(0, 2) = basis[0][2];
        link.body_T_parent_ref(1, 0) = basis[1][0];
        link.body_T_parent_ref(1, 1) = basis[1][1];
        link.body_T_parent_ref(1, 2) = basis[1][2];
        link.body_T_parent_ref(2, 0) = basis[2][0];
        link.body_T_parent_ref(2, 1) = basis[2][1];
        link.body_T_parent_ref(2, 2) = basis[2][2];
        if (verbose) {
            id_printf("body_T_parent_ref= %f %f %f\n"
                      "                   %f %f %f\n"
                      "                   %f %f %f\n",
                      basis[0][0], basis[0][1], basis[0][2], basis[1][0], basis[1][1], basis[1][2],
                      basis[2][0], basis[2][1], basis[2][2]);
        }
        switch (bt_link.m_jointType) {
            case btMultibodyLink::eRevolute:
                link.joint_type = REVOLUTE;
                if (verbose) {
                    id_printf("type= revolute\n");
                }
                link.body_axis_of_motion(0) = bt_link.m_axes[0].m_topVec[0];
                link.body_axis_of_motion(1) = bt_link.m_axes[0].m_topVec[1];
                link.body_axis_of_motion(2) = bt_link.m_axes[0].m_topVec[2];

                // for revolute joints, m_eVector = parentComToThisPivotOffset
                //                      m_dVector = thisPivotToThisComOffset
                // from parent com to pivot, in parent frame
                link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
                link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
                link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
                break;
            case btMultibodyLink::ePrismatic:
                link.joint_type = PRISMATIC;
                if (verbose) {
                    id_printf("type= prismatic\n");
                }
                link.body_axis_of_motion(0) = bt_link.m_axes[0].m_bottomVec[0];
                link.body_axis_of_motion(1) = bt_link.m_axes[0].m_bottomVec[1];
                link.body_axis_of_motion(2) = bt_link.m_axes[0].m_bottomVec[2];

                // for prismatic joints, eVector
                //                                according to documentation :
                //                                parentComToThisComOffset
                //                                but seems to be: from parent's com to parent's
                //                                pivot ??
                //                       m_dVector = thisPivotToThisComOffset
                link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
                link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
                link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
                break;
            case btMultibodyLink::eSpherical:
                error_message("spherical joints not implemented\n");
                return -1;
            case btMultibodyLink::ePlanar:
                error_message("planar joints not implemented\n");
                return -1;
            case btMultibodyLink::eFixed:
                link.joint_type = FIXED;
                // random unit vector
                link.body_axis_of_motion(0) = 0;
                link.body_axis_of_motion(1) = 0;
                link.body_axis_of_motion(2) = 1;

                // for fixed joints, m_dVector = thisPivotToThisComOffset;
                //                   m_eVector = parentComToThisPivotOffset;
                link.parent_r_parent_body_ref(0) = bt_link.m_eVector[0];
                link.parent_r_parent_body_ref(1) = bt_link.m_eVector[1];
                link.parent_r_parent_body_ref(2) = bt_link.m_eVector[2];
                break;
            default:
                error_message("unknown btMultiBody::eFeatherstoneJointType %d\n",
                              bt_link.m_jointType);
                return -1;
        }
        if (link.parent_index > 0) {  // parent body isn't the root
            const btMultibodyLink &bt_parent_link = btmb->getLink(link.parent_index - 1);
            // from parent pivot to parent com, in parent frame
            link.parent_r_parent_body_ref(0) += bt_parent_link.m_dVector[0];
            link.parent_r_parent_body_ref(1) += bt_parent_link.m_dVector[1];
            link.parent_r_parent_body_ref(2) += bt_parent_link.m_dVector[2];
        } else {
            // parent is root body. btMultiBody only knows 6-DoF or 0-DoF root bodies,
            // whose link frame is in the CoM (ie, no notion of a pivot point)
        }

        if (verbose) {
            id_printf("parent_r_parent_body_ref= %f %f %f\n", link.parent_r_parent_body_ref[0],
                      link.parent_r_parent_body_ref[1], link.parent_r_parent_body_ref[2]);
        }
    }

    m_initialized = true;

    return 0;
}

int btMultiBodyTreeCreator::getNumBodies(int *num_bodies) const {
    if (false == m_initialized) {
        error_message("btMultiBody not converted yet\n");
        return -1;
    }

    *num_bodies = static_cast<int>(m_data.size());
    return 0;
}

int btMultiBodyTreeCreator::getBody(const int body_index, int *parent_index, JointType *joint_type,
                                    vec3 *parent_r_parent_body_ref, mat33 *body_T_parent_ref,
                                    vec3 *body_axis_of_motion, idScalar *mass,
                                    vec3 *body_r_body_com, mat33 *body_I_body, int *user_int,
                                    void **user_ptr) const {
    if (false == m_initialized) {
        error_message("MultiBodyTree not created yet\n");
        return -1;
    }

    if (body_index < 0 || body_index >= static_cast<int>(m_data.size())) {
        error_message("index out of range (got %d but only %zu bodies)\n", body_index,
                      m_data.size());
        return -1;
    }

    *parent_index = m_data[body_index].parent_index;
    *joint_type = m_data[body_index].joint_type;
    *parent_r_parent_body_ref = m_data[body_index].parent_r_parent_body_ref;
    *body_T_parent_ref = m_data[body_index].body_T_parent_ref;
    *body_axis_of_motion = m_data[body_index].body_axis_of_motion;
    *mass = m_data[body_index].mass;
    *body_r_body_com = m_data[body_index].body_r_body_com;
    *body_I_body = m_data[body_index].body_I_body;

    *user_int = -1;
    *user_ptr = 0x0;

    return 0;
}
}