Skip to content

Commit edbdb51

Browse files
yuvaltassacopybara-github
authored andcommitted
Change MuJoCo engine source code function-spacing convention from 3 blank lines to 2
PiperOrigin-RevId: 813754244 Change-Id: I6836e41c3b021cb727e922c25c60f629b9814c93
1 parent c439628 commit edbdb51

36 files changed

+8
-651
lines changed

STYLEGUIDE.md

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,8 @@ possible in your code contributions.
66

77
### Scope of this guide
88

9-
Most of this guide involves C/C++ code. For Python, jump to the section [below](#python-code). For MuJoCo C/C++, code has three main categories:
9+
Most of this guide involves C/C++ code. For Python, jump to the section
10+
[below](#python-code). For MuJoCo C/C++, code has three main categories:
1011

1112
1. **C code:** MuJoCo's core codebase. It consists of public headers under
1213
`include/` and C source files and internal headers under `src/`. This style
@@ -144,7 +145,7 @@ assignments:
144145
variable initialisation in `for` loops. For example, inspect the
145146
`mju_transpose` implementation above.
146147
147-
- Three blank lines are required between function implementations in source files.
148+
- Two blank lines are required between function implementations in source files.
148149
149150
#### Variable declarations
150151
@@ -161,4 +162,7 @@ helping us to complete the migration are very welcome.
161162
162163
### [Python code](#python-code)
163164
164-
For Python code, run `pyink foo.py` to adhere to Google's [Python style guide](https://google.github.io/styleguide/pyguide.html). For sorting and cleaning imports, run `isort foo.py`. Both `pyink` and `isort` can be pip installed via `pip install pyink isort`.
165+
For Python code, run `pyink foo.py` to adhere to Google's
166+
[Python style guide](https://google.github.io/styleguide/pyguide.html). For
167+
sorting and cleaning imports, run `isort foo.py`. Both `pyink` and `isort` can
168+
be pip installed via `pip install pyink isort`.

src/engine/engine_collision_box.c

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,6 @@ int mjraw_SphereBox(mjContact* con, mjtNum margin,
9191
}
9292

9393

94-
9594
// sphere : box
9695
int mjc_SphereBox(const mjModel* m, const mjData* d, mjContact* con,
9796
int g1, int g2, mjtNum margin)
@@ -102,7 +101,6 @@ int mjc_SphereBox(const mjModel* m, const mjData* d, mjContact* con,
102101
}
103102

104103

105-
106104
/* GENERAL THEORY OF OPERATION
107105
the following code is mostly for finding (line segment)/(box) collision
108106
after which box-sphere is called
@@ -601,7 +599,6 @@ int mjc_CapsuleBox(const mjModel* m, const mjData* d, mjContact* con,
601599
}
602600

603601

604-
605602
// box : box
606603
int mjc_BoxBox(const mjModel* M, const mjData* D, mjContact* con, int g1, int g2, mjtNum margin)
607604
{

src/engine/engine_collision_convex.c

Lines changed: 0 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,6 @@ static int mjc_penetration(const mjModel* m, mjCCDObj* obj1, mjCCDObj* obj2,
8484
}
8585

8686

87-
8887
// ccd center function
8988
void mjccd_center(const void *obj, ccd_vec3_t *center) {
9089
mjc_center(center->v, (const mjCCDObj*) obj);
@@ -114,7 +113,6 @@ void mjc_center(mjtNum res[3], const mjCCDObj *obj) {
114113
}
115114

116115

117-
118116
// prism center function
119117
static void mjc_prism_center(mjtNum res[3], const mjCCDObj* obj) {
120118
// compute mean
@@ -126,7 +124,6 @@ static void mjc_prism_center(mjtNum res[3], const mjCCDObj* obj) {
126124
}
127125

128126

129-
130127
// ccd prism center function
131128
static void mjccd_prism_center(const void *obj, ccd_vec3_t *center) {
132129
mjc_prism_center(center->v, (const mjCCDObj*) obj);
@@ -143,7 +140,6 @@ static inline void mulMatTVec3(mjtNum res[3], const mjtNum mat[9], const mjtNum
143140
}
144141

145142

146-
147143
// transform a vector from local to global frame
148144
static inline void localToGlobal(mjtNum res[3], const mjtNum mat[9], const mjtNum dir[3],
149145
const mjtNum pos[3]) {
@@ -157,7 +153,6 @@ static inline void localToGlobal(mjtNum res[3], const mjtNum mat[9], const mjtNu
157153
}
158154

159155

160-
161156
// point support function
162157
void mjc_pointSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
163158
const mjtNum* pos = obj->data->geom_xpos + 3*obj->geom;
@@ -167,7 +162,6 @@ void mjc_pointSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
167162
}
168163

169164

170-
171165
// sphere support function
172166
static void mjc_sphereSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
173167
const mjModel* m = obj->model;
@@ -183,7 +177,6 @@ static void mjc_sphereSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3])
183177
}
184178

185179

186-
187180
// line support function (capsule)
188181
void mjc_lineSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
189182
const mjModel* m = obj->model;
@@ -208,7 +201,6 @@ void mjc_lineSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
208201
}
209202

210203

211-
212204
// capsule support function
213205
static void mjc_capsuleSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
214206
const mjModel* m = obj->model;
@@ -238,7 +230,6 @@ static void mjc_capsuleSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]
238230
}
239231

240232

241-
242233
// ellipsoid support function
243234
static void mjc_ellipsoidSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
244235
const mjModel* m = obj->model;
@@ -278,7 +269,6 @@ static void mjc_ellipsoidSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[
278269
}
279270

280271

281-
282272
// cylinder support function
283273
static void mjc_cylinderSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
284274
const mjModel* m = obj->model;
@@ -311,7 +301,6 @@ static void mjc_cylinderSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3
311301
}
312302

313303

314-
315304
// box support function
316305
static void mjc_boxSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
317306
const mjModel* m = obj->model;
@@ -343,14 +332,12 @@ static void mjc_boxSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
343332
}
344333

345334

346-
347335
// dot product between mjtNum and float
348336
static inline mjtNum dot3f(const mjtNum a[3], const float b[3]) {
349337
return a[0]*(mjtNum)b[0] + a[1]*(mjtNum)b[1] + a[2]*(mjtNum)b[2];
350338
}
351339

352340

353-
354341
// mesh support function via exhaustive search
355342
static void mjc_meshSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
356343
const mjModel* m = obj->model;
@@ -398,7 +385,6 @@ static void mjc_meshSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
398385
}
399386

400387

401-
402388
// mesh support function via hill climbing
403389
static void mjc_hillclimbSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
404390
const mjModel* m = obj->model;
@@ -449,7 +435,6 @@ static void mjc_hillclimbSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[
449435
}
450436

451437

452-
453438
// prism support function
454439
static void mjc_prism_support(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
455440
int istart, ibest;
@@ -471,7 +456,6 @@ static void mjc_prism_support(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3])
471456
}
472457

473458

474-
475459
// flex support function
476460
static void mjc_flexSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
477461
const mjModel* m = obj->model;
@@ -512,7 +496,6 @@ static void mjc_flexSupport(mjtNum res[3], mjCCDObj* obj, const mjtNum dir[3]) {
512496
}
513497

514498

515-
516499
// libccd support function
517500
void mjccd_support(const void *_obj, const ccd_vec3_t *_dir, ccd_vec3_t *vec) {
518501
mjCCDObj *obj = (mjCCDObj *)_obj;
@@ -720,7 +703,6 @@ void mjccd_support(const void *_obj, const ccd_vec3_t *_dir, ccd_vec3_t *vec) {
720703
}
721704

722705

723-
724706
// libccd prism support function
725707
static void mjccd_prism_support(const void *obj, const ccd_vec3_t *dir, ccd_vec3_t *vec) {
726708
mjc_prism_support(vec->v, (mjCCDObj*) obj, dir->v);
@@ -784,7 +766,6 @@ void mjc_initCCDObj(mjCCDObj* obj, const mjModel* m, const mjData* d, int g, mjt
784766
}
785767

786768

787-
788769
// set flex data for CCD object
789770
static void mjc_setCCDObjFlex(mjCCDObj* obj, int flex, int elem, int vert) {
790771
obj->flex = flex;
@@ -793,7 +774,6 @@ static void mjc_setCCDObjFlex(mjCCDObj* obj, int flex, int elem, int vert) {
793774
}
794775

795776

796-
797777
// initialize CCD structure
798778
static void mjc_initCCD(ccd_t* ccd, const mjModel* m) {
799779
CCD_INIT(ccd);
@@ -803,7 +783,6 @@ static void mjc_initCCD(ccd_t* ccd, const mjModel* m) {
803783
}
804784

805785

806-
807786
// find convex-convex collision
808787
static int mjc_CCDIteration(const mjModel* m, const mjData* d, mjCCDObj* obj1, mjCCDObj* obj2,
809788
mjContact* con, int max_contacts, mjtNum margin) {
@@ -873,7 +852,6 @@ static int mjc_CCDIteration(const mjModel* m, const mjData* d, mjCCDObj* obj1, m
873852
}
874853

875854

876-
877855
// compare new contact to previous contacts, return 1 if it is far from all of them
878856
static int mjc_isDistinctContact(mjContact* con, int ncon, mjtNum tolerance) {
879857
for (int i=0; i < ncon-1; i++) {
@@ -885,7 +863,6 @@ static int mjc_isDistinctContact(mjContact* con, int ncon, mjtNum tolerance) {
885863
}
886864

887865

888-
889866
// in-place rotation of spatial frame around given point of origin
890867
static void mju_rotateFrame(const mjtNum origin[3], const mjtNum rot[9],
891868
mjtNum xmat[9], mjtNum xpos[3]) {
@@ -907,7 +884,6 @@ static void mju_rotateFrame(const mjtNum origin[3], const mjtNum rot[9],
907884
}
908885

909886

910-
911887
// return number of contacts supported by a single pass of narrowphase
912888
static int maxContacts(const mjCCDObj* obj1, const mjCCDObj* obj2) {
913889
const mjModel* m = obj1->model;
@@ -936,7 +912,6 @@ static int maxContacts(const mjCCDObj* obj1, const mjCCDObj* obj2) {
936912
}
937913

938914

939-
940915
// multi-point convex-convex collision, using libccd
941916
int mjc_Convex(const mjModel* m, const mjData* d,
942917
mjContact* con, int g1, int g2, mjtNum margin) {
@@ -1024,7 +999,6 @@ int mjc_Convex(const mjModel* m, const mjData* d,
1024999
}
10251000

10261001

1027-
10281002
// parameters for plane-mesh extra contacts
10291003
const int maxplanemesh = 3;
10301004
const mjtNum tolplanemesh = 0.3;
@@ -1063,7 +1037,6 @@ static int addplanemesh(mjContact* con, const float vertex[3],
10631037
}
10641038

10651039

1066-
10671040
// plane-convex collision, using libccd
10681041
int mjc_PlaneConvex(const mjModel* m, const mjData* d,
10691042
mjContact* con, int g1, int g2, mjtNum margin) {
@@ -1164,7 +1137,6 @@ int mjc_PlaneConvex(const mjModel* m, const mjData* d,
11641137
}
11651138

11661139

1167-
11681140
//---------------------------- heightfield collisions ---------------------------------------------
11691141

11701142
// ccd prism first dir
@@ -1191,7 +1163,6 @@ static void addVert(int* nvert, mjCCDObj* obj, mjtNum x, mjtNum y, mjtNum z) {
11911163
}
11921164

11931165

1194-
11951166
// entry point for heightfield collisions
11961167
int mjc_ConvexHField(const mjModel* m, const mjData* d,
11971168
mjContact* con, int g1, int g2, mjtNum margin) {
@@ -1379,7 +1350,6 @@ int mjc_ConvexHField(const mjModel* m, const mjData* d,
13791350
}
13801351

13811352

1382-
13831353
//--------------------------- fix contact frame normal ---------------------------------------------
13841354

13851355
// compute normal for point outside ellipsoid, using ray-projection SQP
@@ -1437,7 +1407,6 @@ static int mjc_ellipsoidInside(mjtNum nrm[3], const mjtNum pos[3], const mjtNum
14371407
}
14381408

14391409

1440-
14411410
// compute normal for point inside ellipsoid, using diagonal QCQP
14421411
static int mjc_ellipsoidOutside(mjtNum nrm[3], const mjtNum pos[3], const mjtNum size[3]) {
14431412
// algorithm constants
@@ -1487,7 +1456,6 @@ static int mjc_ellipsoidOutside(mjtNum nrm[3], const mjtNum pos[3], const mjtNum
14871456
}
14881457

14891458

1490-
14911459
// entry point
14921460
void mjc_fixNormal(const mjModel* m, const mjData* d, mjContact* con, int g1, int g2) {
14931461
mjtNum dst1, dst2;
@@ -1637,7 +1605,6 @@ void mjc_fixNormal(const mjModel* m, const mjData* d, mjContact* con, int g1, in
16371605
}
16381606

16391607

1640-
16411608
//---------------------------- flex collisions ---------------------------------------------
16421609

16431610
// geom-elem or elem-elem or vert-elem convex collision using ccd
@@ -1654,7 +1621,6 @@ int mjc_ConvexElem(const mjModel* m, const mjData* d, mjContact* con,
16541621
}
16551622

16561623

1657-
16581624
// test a height field and a flex element for collision
16591625
int mjc_HFieldElem(const mjModel* m, const mjData* d, mjContact* con,
16601626
int g, int f, int e, mjtNum margin) {

0 commit comments

Comments
 (0)