-
Notifications
You must be signed in to change notification settings - Fork 1.5k
Expand file tree
/
Copy pathengine_sensor.c
More file actions
991 lines (831 loc) · 30.9 KB
/
engine_sensor.c
File metadata and controls
991 lines (831 loc) · 30.9 KB
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
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
// Copyright 2021 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "engine/engine_sensor.h"
#include <stddef.h>
#include <mujoco/mjdata.h>
#include <mujoco/mjmodel.h>
#include <mujoco/mjplugin.h>
#include "engine/engine_callback.h"
#include "engine/engine_core_smooth.h"
#include "engine/engine_crossplatform.h"
#include "engine/engine_io.h"
#include "engine/engine_plugin.h"
#include "engine/engine_ray.h"
#include "engine/engine_support.h"
#include "engine/engine_util_blas.h"
#include "engine/engine_util_errmem.h"
#include "engine/engine_util_misc.h"
#include "engine/engine_util_spatial.h"
//-------------------------------- utility ---------------------------------------------------------
// add sensor noise after each stage
static void add_noise(const mjModel* m, mjData* d, mjtStage stage) {
int adr, dim;
mjtNum rnd[4], noise, quat[4], res[4];
// process sensors matching stage and having positive noise
for (int i=0; i < m->nsensor; i++) {
if (m->sensor_needstage[i] == stage && m->sensor_noise[i] > 0) {
// get sensor info
adr = m->sensor_adr[i];
dim = m->sensor_dim[i];
noise = m->sensor_noise[i];
// real or positive: add noise directly, with clamp for positive
if (m->sensor_datatype[i] == mjDATATYPE_REAL ||
m->sensor_datatype[i] == mjDATATYPE_POSITIVE) {
for (int j=0; j < dim; j++) {
// get random numbers; use only the first one
rnd[0] = mju_standardNormal(rnd+1);
// positive
if (m->sensor_datatype[i] == mjDATATYPE_POSITIVE) {
// add noise only if positive, keep it positive
if (d->sensordata[adr+j] > 0) {
d->sensordata[adr+j] = mju_max(0, d->sensordata[adr+j]+rnd[0]*noise);
}
}
// real
else {
d->sensordata[adr+j] += rnd[0]*noise;
}
}
}
// axis or quat: rotate around random axis by random angle
else {
// get four random numbers
rnd[0] = mju_standardNormal(rnd+1);
rnd[2] = mju_standardNormal(rnd+3);
// scale angle, normalize axis, make quaternion
rnd[0] *= noise;
mju_normalize3(rnd+1);
mju_axisAngle2Quat(quat, rnd+1, rnd[0]);
// axis
if (m->sensor_datatype[i] == mjDATATYPE_AXIS) {
// apply quaternion rotation to axis, assign
mju_rotVecQuat(res, d->sensordata+adr, quat);
mju_copy3(d->sensordata+adr, res);
}
// quaternion
else if (m->sensor_datatype[i] == mjDATATYPE_QUATERNION) {
// apply quaternion rotation to quaternion, assign
mju_mulQuat(d->sensordata+adr, d->sensordata+adr, quat);
}
// unknown datatype
else {
mjERROR("unknown datatype in sensor %d", i);
}
}
}
}
}
// apply cutoff after each stage
static void apply_cutoff(const mjModel* m, mjData* d, mjtStage stage) {
// process sensors matching stage and having positive cutoff
for (int i=0; i < m->nsensor; i++) {
if (m->sensor_needstage[i] == stage && m->sensor_cutoff[i] > 0) {
// get sensor info
int adr = m->sensor_adr[i];
int dim = m->sensor_dim[i];
mjtNum cutoff = m->sensor_cutoff[i];
// process all dimensions
for (int j=0; j < dim; j++) {
// real: apply on both sides
if (m->sensor_datatype[i] == mjDATATYPE_REAL) {
d->sensordata[adr+j] = mju_clip(d->sensordata[adr+j], -cutoff, cutoff);
}
// positive: apply on positive side only
else if (m->sensor_datatype[i] == mjDATATYPE_POSITIVE) {
d->sensordata[adr+j] = mju_min(cutoff, d->sensordata[adr+j]);
}
}
}
}
}
// get xpos and xmat pointers to an object in mjData
static void get_xpos_xmat(const mjData* d, mjtObj type, int id, int sensor_id,
mjtNum **xpos, mjtNum **xmat) {
switch (type) {
case mjOBJ_XBODY:
*xpos = d->xpos + 3*id;
*xmat = d->xmat + 9*id;
break;
case mjOBJ_BODY:
*xpos = d->xipos + 3*id;
*xmat = d->ximat + 9*id;
break;
case mjOBJ_GEOM:
*xpos = d->geom_xpos + 3*id;
*xmat = d->geom_xmat + 9*id;
break;
case mjOBJ_SITE:
*xpos = d->site_xpos + 3*id;
*xmat = d->site_xmat + 9*id;
break;
case mjOBJ_CAMERA:
*xpos = d->cam_xpos + 3*id;
*xmat = d->cam_xmat + 9*id;
break;
default:
mjERROR("invalid object type in sensor %d", sensor_id);
}
}
// get global quaternion of an object in mjData
static void get_xquat(const mjModel* m, const mjData* d, mjtObj type, int id, int sensor_id,
mjtNum *quat) {
switch (type) {
case mjOBJ_XBODY:
mju_copy4(quat, d->xquat+4*id);
break;
case mjOBJ_BODY:
mju_mulQuat(quat, d->xquat+4*id, m->body_iquat+4*id);
break;
case mjOBJ_GEOM:
mju_mulQuat(quat, d->xquat+4*m->geom_bodyid[id], m->geom_quat+4*id);
break;
case mjOBJ_SITE:
mju_mulQuat(quat, d->xquat+4*m->site_bodyid[id], m->site_quat+4*id);
break;
case mjOBJ_CAMERA:
mju_mulQuat(quat, d->xquat+4*m->cam_bodyid[id], m->cam_quat+4*id);
break;
default:
mjERROR("invalid object type in sensor %d", sensor_id);
}
}
static void cam_project(mjtNum sensordata[2], const mjtNum target_xpos[3],
const mjtNum cam_xpos[3], const mjtNum cam_xmat[9],
const int cam_res[2], mjtNum cam_fovy,
const float cam_intrinsic[4], const float cam_sensorsize[2]) {
mjtNum fx, fy;
// translation matrix (4x4)
mjtNum translation[4][4] = {0};
translation[0][0] = 1;
translation[1][1] = 1;
translation[2][2] = 1;
translation[3][3] = 1;
translation[0][3] = -cam_xpos[0];
translation[1][3] = -cam_xpos[1];
translation[2][3] = -cam_xpos[2];
// rotation matrix (4x4)
mjtNum rotation[4][4] = {0};
rotation[0][0] = 1;
rotation[1][1] = 1;
rotation[2][2] = 1;
rotation[3][3] = 1;
for (int i=0; i < 3; i++) {
for (int j=0; j < 3; j++) {
rotation[i][j] = cam_xmat[j*3+i];
}
}
// focal transformation matrix (3x4)
if (cam_sensorsize[0] && cam_sensorsize[1]) {
fx = cam_intrinsic[0] / cam_sensorsize[0] * cam_res[0];
fy = cam_intrinsic[1] / cam_sensorsize[1] * cam_res[1];
} else {
fx = fy = .5 / mju_tan(cam_fovy * mjPI / 360.) * cam_res[1];
}
mjtNum focal[3][4] = {0};
focal[0][0] = -fx;
focal[1][1] = fy;
focal[2][2] = 1.0;
// image matrix (3x3)
mjtNum image[3][3] = {0};
image[0][0] = 1;
image[1][1] = 1;
image[2][2] = 1;
image[0][2] = (mjtNum)cam_res[0] / 2.0;
image[1][2] = (mjtNum)cam_res[1] / 2.0;
// projection matrix (3x4): product of all 4 matrices
mjtNum proj[3][4] = {0};
for (int i=0; i < 3; i++) {
for (int j=0; j < 3; j++) {
for (int k=0; k < 4; k++) {
for (int l=0; l < 4; l++) {
for (int n=0; n < 4; n++) {
proj[i][n] += image[i][j] * focal[j][k] * rotation[k][l] * translation[l][n];
}
}
}
}
}
// projection matrix multiplies homogenous [x, y, z, 1] vectors
mjtNum pos_hom[4] = {0, 0, 0, 1};
mju_copy3(pos_hom, target_xpos);
// project world coordinates into pixel space, see:
// https://en.wikipedia.org/wiki/3D_projection#Mathematical_formula
mjtNum pixel_coord_hom[3] = {0};
for (int i=0; i < 3; i++) {
for (int j=0; j < 4; j++) {
pixel_coord_hom[i] += proj[i][j] * pos_hom[j];
}
}
// avoid dividing by tiny numbers
mjtNum denom = pixel_coord_hom[2];
if (mju_abs(denom) < mjMINVAL) {
if (denom < 0) {
denom = mju_min(denom, -mjMINVAL);
} else {
denom = mju_max(denom, mjMINVAL);
}
}
// compute projection
sensordata[0] = pixel_coord_hom[0] / denom;
sensordata[1] = pixel_coord_hom[1] / denom;
}
//-------------------------------- sensor ----------------------------------------------------------
// position-dependent sensors
void mj_sensorPos(const mjModel* m, mjData* d) {
int rgeomid, objtype, objid, reftype, refid, adr, offset, nusersensor = 0;
int ne = d->ne, nf = d->nf, nefc = d->nefc;
mjtNum rvec[3], *xpos, *xmat, *xpos_ref, *xmat_ref;
// disabled sensors: return
if (mjDISABLED(mjDSBL_SENSOR)) {
return;
}
// process sensors matching stage
for (int i=0; i < m->nsensor; i++) {
// skip sensor plugins -- these are handled after builtin sensor types
if (m->sensor_type[i] == mjSENS_PLUGIN) {
continue;
}
if (m->sensor_needstage[i] == mjSTAGE_POS) {
// get sensor info
objtype = m->sensor_objtype[i];
objid = m->sensor_objid[i];
refid = m->sensor_refid[i];
reftype = m->sensor_reftype[i];
adr = m->sensor_adr[i];
// process according to type
switch ((mjtSensor) m->sensor_type[i]) {
case mjSENS_MAGNETOMETER: // magnetometer
mju_mulMatTVec(d->sensordata+adr, d->site_xmat+9*objid, m->opt.magnetic, 3, 3);
break;
case mjSENS_CAMPROJECTION: // camera projection
cam_project(d->sensordata+adr, d->site_xpos+3*objid, d->cam_xpos+3*refid,
d->cam_xmat+9*refid, m->cam_resolution+2*refid, m->cam_fovy[refid],
m->cam_intrinsic+4*refid, m->cam_sensorsize+2*refid);
break;
case mjSENS_RANGEFINDER: // rangefinder
rvec[0] = d->site_xmat[9*objid+2];
rvec[1] = d->site_xmat[9*objid+5];
rvec[2] = d->site_xmat[9*objid+8];
d->sensordata[adr] = mj_ray(m, d, d->site_xpos+3*objid, rvec, NULL, 1,
m->site_bodyid[objid], &rgeomid);
break;
case mjSENS_JOINTPOS: // jointpos
d->sensordata[adr] = d->qpos[m->jnt_qposadr[objid]];
break;
case mjSENS_TENDONPOS: // tendonpos
d->sensordata[adr] = d->ten_length[objid];
break;
case mjSENS_ACTUATORPOS: // actuatorpos
d->sensordata[adr] = d->actuator_length[objid];
break;
case mjSENS_BALLQUAT: // ballquat
mju_copy4(d->sensordata+adr, d->qpos+m->jnt_qposadr[objid]);
break;
case mjSENS_JOINTLIMITPOS: // jointlimitpos
d->sensordata[adr] = 0;
for (int j=ne+nf; j < nefc; j++) {
if (d->efc_type[j] == mjCNSTR_LIMIT_JOINT && d->efc_id[j] == objid) {
d->sensordata[adr] = d->efc_pos[j] - d->efc_margin[j];
break;
}
}
break;
case mjSENS_TENDONLIMITPOS: // tendonlimitpos
d->sensordata[adr] = 0;
for (int j=ne+nf; j < nefc; j++) {
if (d->efc_type[j] == mjCNSTR_LIMIT_TENDON && d->efc_id[j] == objid) {
d->sensordata[adr] = d->efc_pos[j] - d->efc_margin[j];
break;
}
}
break;
case mjSENS_FRAMEPOS: // framepos
case mjSENS_FRAMEXAXIS: // framexaxis
case mjSENS_FRAMEYAXIS: // frameyaxis
case mjSENS_FRAMEZAXIS: // framezaxis
// get xpos and xmat pointers for object frame
get_xpos_xmat(d, objtype, objid, i, &xpos, &xmat);
// reference frame unspecified: global frame
if (refid == -1) {
if (m->sensor_type[i] == mjSENS_FRAMEPOS) {
mju_copy3(d->sensordata+adr, xpos);
} else {
// offset = (0 or 1 or 2) for (x or y or z)-axis sensors, respectively
offset = m->sensor_type[i] - mjSENS_FRAMEXAXIS;
d->sensordata[adr] = xmat[offset];
d->sensordata[adr+1] = xmat[offset+3];
d->sensordata[adr+2] = xmat[offset+6];
}
}
// reference frame specified
else {
get_xpos_xmat(d, reftype, refid, i, &xpos_ref, &xmat_ref);
if (m->sensor_type[i] == mjSENS_FRAMEPOS) {
mju_sub3(rvec, xpos, xpos_ref);
mju_rotVecMatT(d->sensordata+adr, rvec, xmat_ref);
} else {
// offset = (0 or 1 or 2) for (x or y or z)-axis sensors, respectively
offset = m->sensor_type[i] - mjSENS_FRAMEXAXIS;
mjtNum axis[3] = {xmat[offset], xmat[offset+3], xmat[offset+6]};
mju_rotVecMatT(d->sensordata+adr, axis, xmat_ref);
}
}
break;
case mjSENS_FRAMEQUAT: // framequat
{
// get global object quaternion
mjtNum objquat[4];
get_xquat(m, d, objtype, objid, i, objquat);
// reference frame unspecified: copy object quaternion
if (refid == -1) {
mju_copy4(d->sensordata+adr, objquat);
} else {
// reference frame specified, get global reference quaternion
mjtNum refquat[4];
get_xquat(m, d, reftype, refid, i, refquat);
// relative quaternion
mju_negQuat(refquat, refquat);
mju_mulQuat(d->sensordata+adr, refquat, objquat);
}
}
break;
case mjSENS_SUBTREECOM: // subtreecom
mju_copy3(d->sensordata+adr, d->subtree_com+3*objid);
break;
case mjSENS_CLOCK: // clock
d->sensordata[adr] = d->time;
break;
case mjSENS_USER: // user
nusersensor++;
break;
default:
mjERROR("invalid sensor type in POS stage, sensor %d", i);
}
}
}
// fill in user sensors if detected
if (nusersensor && mjcb_sensor) {
mjcb_sensor(m, d, mjSTAGE_POS);
}
// add noise if enabled
if (mjENABLED(mjENBL_SENSORNOISE)) {
add_noise(m, d, mjSTAGE_POS);
}
// compute plugin sensor values
if (m->nplugin) {
const int nslot = mjp_pluginCount();
for (int i=0; i < m->nplugin; i++) {
const int slot = m->plugin[i];
const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot);
if (!plugin) {
mjERROR("invalid plugin slot: %d", slot);
}
if ((plugin->capabilityflags & mjPLUGIN_SENSOR) &&
(plugin->needstage == mjSTAGE_POS || plugin->needstage == mjSTAGE_NONE)) {
if (!plugin->compute) {
mjERROR("`compute` is a null function pointer for plugin at slot %d", slot);
}
plugin->compute(m, d, i, mjPLUGIN_SENSOR);
}
}
}
// cutoff
apply_cutoff(m, d, mjSTAGE_POS);
}
// velocity-dependent sensors
void mj_sensorVel(const mjModel* m, mjData* d) {
int objtype, objid, reftype, refid, adr, nusersensor = 0;
int ne = d->ne, nf = d->nf, nefc = d->nefc;
mjtNum xvel[6];
// disabled sensors: return
if (mjDISABLED(mjDSBL_SENSOR)) {
return;
}
// process sensors matching stage
int subtreeVel = 0;
for (int i=0; i < m->nsensor; i++) {
// skip sensor plugins -- these are handled after builtin sensor types
if (m->sensor_type[i] == mjSENS_PLUGIN) {
continue;
}
if (m->sensor_needstage[i] == mjSTAGE_VEL) {
// get sensor info
mjtSensor type = m->sensor_type[i];
objtype = m->sensor_objtype[i];
objid = m->sensor_objid[i];
refid = m->sensor_refid[i];
reftype = m->sensor_reftype[i];
adr = m->sensor_adr[i];
// call mj_subtreeVel when first relevant sensor is encountered
if (subtreeVel == 0 &&
(type == mjSENS_SUBTREELINVEL ||
type == mjSENS_SUBTREEANGMOM ||
type == mjSENS_USER)) {
// compute subtree_linvel, subtree_angmom
mj_subtreeVel(m, d);
// mark computed
subtreeVel = 1;
}
// process according to type
switch (type) {
case mjSENS_VELOCIMETER: // velocimeter
// xvel = site velocity, in site frame
mj_objectVelocity(m, d, mjOBJ_SITE, objid, xvel, 1);
// assign linear velocity
mju_copy3(d->sensordata+adr, xvel+3);
break;
case mjSENS_GYRO: // gyro
// xvel = site velocity, in site frame
mj_objectVelocity(m, d, mjOBJ_SITE, objid, xvel, 1);
// assign angular velocity
mju_copy3(d->sensordata+adr, xvel);
break;
case mjSENS_JOINTVEL: // jointvel
d->sensordata[adr] = d->qvel[m->jnt_dofadr[objid]];
break;
case mjSENS_TENDONVEL: // tendonvel
d->sensordata[adr] = d->ten_velocity[objid];
break;
case mjSENS_ACTUATORVEL: // actuatorvel
d->sensordata[adr] = d->actuator_velocity[objid];
break;
case mjSENS_BALLANGVEL: // ballangvel
mju_copy3(d->sensordata+adr, d->qvel+m->jnt_dofadr[objid]);
break;
case mjSENS_JOINTLIMITVEL: // jointlimitvel
d->sensordata[adr] = 0;
for (int j=ne+nf; j < nefc; j++) {
if (d->efc_type[j] == mjCNSTR_LIMIT_JOINT && d->efc_id[j] == objid) {
d->sensordata[adr] = d->efc_vel[j];
break;
}
}
break;
case mjSENS_TENDONLIMITVEL: // tendonlimitvel
d->sensordata[adr] = 0;
for (int j=ne+nf; j < nefc; j++) {
if (d->efc_type[j] == mjCNSTR_LIMIT_TENDON && d->efc_id[j] == objid) {
d->sensordata[adr] = d->efc_vel[j];
break;
}
}
break;
case mjSENS_FRAMELINVEL: // framelinvel
case mjSENS_FRAMEANGVEL: // frameangvel
// xvel = 6D object velocity, in global frame
mj_objectVelocity(m, d, objtype, objid, xvel, 0);
if (refid > -1) { // reference frame specified
mjtNum *xpos, *xmat, *xpos_ref, *xmat_ref, xvel_ref[6], rel_vel[6], cross[3], rvec[3];
// in global frame: object and reference position, reference orientation and velocity
get_xpos_xmat(d, objtype, objid, i, &xpos, &xmat);
get_xpos_xmat(d, reftype, refid, i, &xpos_ref, &xmat_ref);
mj_objectVelocity(m, d, reftype, refid, xvel_ref, 0);
// subtract velocities
mju_sub(rel_vel, xvel, xvel_ref, 6);
// linear velocity: add correction due to rotating reference frame
mju_sub3(rvec, xpos, xpos_ref);
mju_cross(cross, rvec, xvel_ref);
mju_addTo3(rel_vel+3, cross);
// project into reference frame
mju_rotVecMatT(xvel, rel_vel, xmat_ref);
mju_rotVecMatT(xvel+3, rel_vel+3, xmat_ref);
}
// copy linear or angular component
if (m->sensor_type[i] == mjSENS_FRAMELINVEL) {
mju_copy3(d->sensordata+adr, xvel+3);
} else {
mju_copy3(d->sensordata+adr, xvel);
}
break;
case mjSENS_SUBTREELINVEL: // subtreelinvel
mju_copy3(d->sensordata+adr, d->subtree_linvel+3*objid);
break;
case mjSENS_SUBTREEANGMOM: // subtreeangmom
mju_copy3(d->sensordata+adr, d->subtree_angmom+3*objid);
break;
case mjSENS_USER: // user
nusersensor++;
break;
default:
mjERROR("invalid type in VEL stage, sensor %d", i);
}
}
}
// fill in user sensors if detected
if (nusersensor && mjcb_sensor) {
mjcb_sensor(m, d, mjSTAGE_VEL);
}
// add noise if enabled
if (mjENABLED(mjENBL_SENSORNOISE)) {
add_noise(m, d, mjSTAGE_VEL);
}
// trigger computation of plugins
if (m->nplugin) {
const int nslot = mjp_pluginCount();
for (int i=0; i < m->nplugin; i++) {
const int slot = m->plugin[i];
const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot);
if (!plugin) {
mjERROR("invalid plugin slot: %d", slot);
}
if ((plugin->capabilityflags & mjPLUGIN_SENSOR) && plugin->needstage == mjSTAGE_VEL) {
if (!plugin->compute) {
mjERROR("`compute` is null for plugin at slot %d", slot);
}
if (subtreeVel == 0) {
// compute subtree_linvel, subtree_angmom
// TODO(b/247107630): add a flag to allow plugin to specify whether it actually needs this
mj_subtreeVel(m, d);
// mark computed
subtreeVel = 1;
}
plugin->compute(m, d, i, mjPLUGIN_SENSOR);
}
}
}
// cutoff
apply_cutoff(m, d, mjSTAGE_VEL);
}
// acceleration/force-dependent sensors
void mj_sensorAcc(const mjModel* m, mjData* d) {
int rootid, bodyid, objtype, objid, adr, nusersensor = 0;
int ne = d->ne, nf = d->nf, nefc = d->nefc;
mjtNum tmp[6], conforce[6], conray[3];
mjContact* con;
// disabled sensors: return
if (mjDISABLED(mjDSBL_SENSOR)) {
return;
}
// process sensors matching stage
int rnePost = 0;
for (int i=0; i < m->nsensor; i++) {
// skip sensor plugins -- these are handled after builtin sensor types
if (m->sensor_type[i] == mjSENS_PLUGIN) {
continue;
}
if (m->sensor_needstage[i] == mjSTAGE_ACC) {
// get sensor info
mjtSensor type = m->sensor_type[i];
objtype = m->sensor_objtype[i];
objid = m->sensor_objid[i];
adr = m->sensor_adr[i];
// call mj_rnePostConstraint when first relevant sensor is encountered
if (rnePost == 0 && (type == mjSENS_ACCELEROMETER ||
type == mjSENS_FORCE ||
type == mjSENS_TORQUE ||
type == mjSENS_FRAMELINACC ||
type == mjSENS_FRAMEANGACC ||
type == mjSENS_USER)) {
// compute cacc, cfrc_int, cfrc_ext
mj_rnePostConstraint(m, d);
// mark computed
rnePost = 1;
}
// process according to type
switch (type) {
case mjSENS_TOUCH: // touch
// extract body data
bodyid = m->site_bodyid[objid];
rootid = m->body_rootid[bodyid];
// clear result
d->sensordata[adr] = 0;
// find contacts in sensor zone, add normal forces
for (int j=0; j < d->ncon; j++) {
// contact pointer, contacting bodies (-1 for flex)
con = d->contact + j;
int conbody[2];
for (int k=0; k < 2; k++) {
conbody[k] = (con->geom[k] >= 0) ? m->geom_bodyid[con->geom[k]] : -1;
}
// select contacts involving sensorized body
if (con->efc_address >= 0 && (bodyid == conbody[0] || bodyid == conbody[1])) {
// get contact force:torque in contact frame
mj_contactForce(m, d, j, conforce);
// nothing to do if normal is zero
if (conforce[0] <= 0) {
continue;
}
// convert contact normal force to global frame, normalize
mju_scl3(conray, con->frame, conforce[0]);
mju_normalize3(conray);
// flip ray direction if sensor is on body2
if (bodyid == conbody[1]) {
mju_scl3(conray, conray, -1);
}
// add if ray-zone intersection (always true when con->pos inside zone)
if (mju_rayGeom(d->site_xpos+3*objid, d->site_xmat+9*objid,
m->site_size+3*objid, con->pos, conray,
m->site_type[objid]) >= 0) {
d->sensordata[adr] += conforce[0];
}
}
}
break;
case mjSENS_ACCELEROMETER: // accelerometer
// tmp = site acceleration, in site frame
mj_objectAcceleration(m, d, mjOBJ_SITE, objid, tmp, 1);
// assign linear acceleration
mju_copy3(d->sensordata+adr, tmp+3);
break;
case mjSENS_FORCE: // force
// extract body data
bodyid = m->site_bodyid[objid];
rootid = m->body_rootid[bodyid];
// tmp = interaction force between body and parent, in site frame
mju_transformSpatial(tmp, d->cfrc_int+6*bodyid, 1,
d->site_xpos+3*objid, d->subtree_com+3*rootid, d->site_xmat+9*objid);
// assign force
mju_copy3(d->sensordata+adr, tmp+3);
break;
case mjSENS_TORQUE: // torque
// extract body data
bodyid = m->site_bodyid[objid];
rootid = m->body_rootid[bodyid];
// tmp = interaction force between body and parent, in site frame
mju_transformSpatial(tmp, d->cfrc_int+6*bodyid, 1,
d->site_xpos+3*objid, d->subtree_com+3*rootid, d->site_xmat+9*objid);
// assign torque
mju_copy3(d->sensordata+adr, tmp);
break;
case mjSENS_ACTUATORFRC: // actuatorfrc
d->sensordata[adr] = d->actuator_force[objid];
break;
case mjSENS_JOINTACTFRC: // jointactfrc
d->sensordata[adr] = d->qfrc_actuator[m->jnt_dofadr[objid]];
break;
case mjSENS_JOINTLIMITFRC: // jointlimitfrc
d->sensordata[adr] = 0;
for (int j=ne+nf; j < nefc; j++) {
if (d->efc_type[j] == mjCNSTR_LIMIT_JOINT && d->efc_id[j] == objid) {
d->sensordata[adr] = d->efc_force[j];
break;
}
}
break;
case mjSENS_TENDONLIMITFRC: // tendonlimitfrc
d->sensordata[adr] = 0;
for (int j=ne+nf; j < nefc; j++) {
if (d->efc_type[j] == mjCNSTR_LIMIT_TENDON && d->efc_id[j] == objid) {
d->sensordata[adr] = d->efc_force[j];
break;
}
}
break;
case mjSENS_FRAMELINACC: // framelinacc
case mjSENS_FRAMEANGACC: // frameangacc
// get 6D object acceleration, in global frame
mj_objectAcceleration(m, d, objtype, objid, tmp, 0);
// copy linear or angular component
if (m->sensor_type[i] == mjSENS_FRAMELINACC) {
mju_copy3(d->sensordata+adr, tmp+3);
} else {
mju_copy3(d->sensordata+adr, tmp);
}
break;
case mjSENS_USER: // user
nusersensor++;
break;
default:
mjERROR("invalid type in ACC stage, sensor %d", i);
}
}
}
// fill in user sensors if detected
if (nusersensor && mjcb_sensor) {
mjcb_sensor(m, d, mjSTAGE_ACC);
}
// add noise if enabled
if (mjENABLED(mjENBL_SENSORNOISE)) {
add_noise(m, d, mjSTAGE_ACC);
}
// trigger computation of plugins
if (m->nplugin) {
const int nslot = mjp_pluginCount();
for (int i=0; i < m->nplugin; i++) {
const int slot = m->plugin[i];
const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot);
if (!plugin) {
mjERROR("invalid plugin slot: %d", slot);
}
if ((plugin->capabilityflags & mjPLUGIN_SENSOR) && plugin->needstage == mjSTAGE_ACC) {
if (!plugin->compute) {
mjERROR("`compute` is null for plugin at slot %d", slot);
}
if (rnePost == 0) {
// compute cacc, cfrc_int, cfrc_ext
// TODO(b/247107630): add a flag to allow plugin to specify whether it actually needs this
mj_rnePostConstraint(m, d);
// mark computed
rnePost = 1;
}
plugin->compute(m, d, i, mjPLUGIN_SENSOR);
}
}
}
// cutoff
apply_cutoff(m, d, mjSTAGE_ACC);
}
//-------------------------------- energy ----------------------------------------------------------
// position-dependent energy (potential)
void mj_energyPos(const mjModel* m, mjData* d) {
int padr;
mjtNum dif[3], stiffness;
// disabled: clear and return
if (!mjENABLED(mjENBL_ENERGY)) {
d->energy[0] = d->energy[1] = 0;
return;
}
// init potential energy: -sum_i body(i).mass * mju_dot(body(i).pos, gravity)
d->energy[0] = 0;
if (!mjDISABLED(mjDSBL_GRAVITY)) {
for (int i=1; i < m->nbody; i++) {
d->energy[0] -= m->body_mass[i] * mju_dot3(m->opt.gravity, d->xipos+3*i);
}
}
// add joint-level springs
if (!mjDISABLED(mjDSBL_PASSIVE)) {
for (int i=0; i < m->njnt; i++) {
stiffness = m->jnt_stiffness[i];
padr = m->jnt_qposadr[i];
switch ((mjtJoint) m->jnt_type[i]) {
case mjJNT_FREE:
mju_sub3(dif, d->qpos+padr, m->qpos_spring+padr);
d->energy[0] += 0.5*stiffness*mju_dot3(dif, dif);
// continue with rotations
padr += 3;
mjFALLTHROUGH;
case mjJNT_BALL:
// covert quatertion difference into angular "velocity"
mju_subQuat(dif, d->qpos + padr, m->qpos_spring + padr);
d->energy[0] += 0.5*stiffness*mju_dot3(dif, dif);
break;
case mjJNT_SLIDE:
case mjJNT_HINGE:
d->energy[0] += 0.5*stiffness*
(d->qpos[padr] - m->qpos_spring[padr])*
(d->qpos[padr] - m->qpos_spring[padr]);
break;
}
}
}
// add tendon-level springs
if (!mjDISABLED(mjDSBL_PASSIVE)) {
for (int i=0; i < m->ntendon; i++) {
stiffness = m->tendon_stiffness[i];
mjtNum length = d->ten_length[i];
mjtNum displacement = 0;
// compute spring displacement
mjtNum lower = m->tendon_lengthspring[2*i];
mjtNum upper = m->tendon_lengthspring[2*i+1];
if (length > upper) {
displacement = upper - length;
} else if (length < lower) {
displacement = lower - length;
}
d->energy[0] += 0.5*stiffness*displacement*displacement;
}
}
// add flex-level springs for dim=1 (dim>1 requires plugins)
if (!mjDISABLED(mjDSBL_PASSIVE)) {
for (int i=0; i < m->nflex; i++) {
stiffness = m->flex_edgestiffness[i];
if (m->flex_rigid[i] || stiffness == 0 || m->flex_dim[i] > 1) {
continue;
}
// process non-rigid edges of this flex
int flex_edgeadr = m->flex_edgeadr[i];
int flex_edgenum = m->flex_edgenum[i];
for (int e=flex_edgeadr; e < flex_edgeadr+flex_edgenum; e++) {
if (!m->flexedge_rigid[e]) {
mjtNum displacement = m->flexedge_length0[e] - d->flexedge_length[e];
d->energy[0] += 0.5*stiffness*displacement*displacement;
};
}
}
}
}
// velocity-dependent energy (kinetic)
void mj_energyVel(const mjModel* m, mjData* d) {
mjtNum *vec;
// return if disabled (already cleared in potential)
if (!mjENABLED(mjENBL_ENERGY)) {
return;
}
mj_markStack(d);
vec = mj_stackAllocNum(d, m->nv);
// kinetic energy: 0.5 * qvel' * M * qvel
mj_mulM(m, d, vec, d->qvel);
d->energy[1] = 0.5*mju_dot(vec, d->qvel, m->nv);
mj_freeStack(d);
}