Skip to content

Commit a3d251f

Browse files
yuvaltassacopybara-github
authored andcommitted
Add mjModel.sensor_intprm, integer parameters of sensors
PiperOrigin-RevId: 781053754 Change-Id: I90e5ef1cab3f87b894dbc70dccfc8bf0046ce1b6
1 parent 9d64ed9 commit a3d251f

File tree

9 files changed

+60
-1
lines changed

9 files changed

+60
-1
lines changed

doc/APIreference/APIglobals.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -444,6 +444,10 @@ shown in the table below. Their names are in the format ``mjKEY_XXX``. They corr
444444
- 5
445445
- The maximal number of real-valued parameters used to define the impedance of each scalar constraint.
446446
Determines the size of all ``mjModel.XXX_solimp`` fields.
447+
* - ``mjNSENS``
448+
- 2
449+
- The number of sensor parameters.
450+
Determines the size of ``mjModel.sensor_intprm``.
447451
* - ``mjNSOLVER``
448452
- 200
449453
- The number of iterations where solver statistics can be stored in ``mjData.solver``. This array is used

doc/includes/references.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1458,6 +1458,7 @@ struct mjModel_ {
14581458
int* sensor_objid; // id of sensorized object (nsensor x 1)
14591459
int* sensor_reftype; // type of reference frame (mjtObj) (nsensor x 1)
14601460
int* sensor_refid; // id of reference frame; -1: global frame (nsensor x 1)
1461+
int* sensor_intprm; // sensor parameters (nsensor x mjNSENS)
14611462
int* sensor_dim; // number of scalar outputs (nsensor x 1)
14621463
int* sensor_adr; // address in sensor array (nsensor x 1)
14631464
mjtNum* sensor_cutoff; // cutoff for real and positive; 0: ignore (nsensor x 1)
@@ -2324,6 +2325,7 @@ typedef struct mjsSensor_ { // sensor specification
23242325
mjString* objname; // name of sensorized object
23252326
mjtObj reftype; // type of referenced object
23262327
mjString* refname; // name of referenced object
2328+
int intprm[mjNSENS]; // integer parameters
23272329

23282330
// user-defined sensors
23292331
mjtDataType datatype; // data type for sensor measurement

include/mujoco/mjmodel.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#define mjNFLUID 12 // number of fluid interaction parameters
4242
#define mjNREF 2 // number of solver reference parameters
4343
#define mjNIMP 5 // number of solver impedance parameters
44+
#define mjNSENS 2 // number of sensor parameters
4445
#define mjNSOLVER 200 // size of one mjData.solver array
4546
#define mjNISLAND 20 // number of mjData.solver arrays
4647

@@ -1130,6 +1131,7 @@ struct mjModel_ {
11301131
int* sensor_objid; // id of sensorized object (nsensor x 1)
11311132
int* sensor_reftype; // type of reference frame (mjtObj) (nsensor x 1)
11321133
int* sensor_refid; // id of reference frame; -1: global frame (nsensor x 1)
1134+
int* sensor_intprm; // sensor parameters (nsensor x mjNSENS)
11331135
int* sensor_dim; // number of scalar outputs (nsensor x 1)
11341136
int* sensor_adr; // address in sensor array (nsensor x 1)
11351137
mjtNum* sensor_cutoff; // cutoff for real and positive; 0: ignore (nsensor x 1)

include/mujoco/mjspec.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -692,6 +692,7 @@ typedef struct mjsSensor_ { // sensor specification
692692
mjString* objname; // name of sensorized object
693693
mjtObj reftype; // type of referenced object
694694
mjString* refname; // name of referenced object
695+
int intprm[mjNSENS]; // integer parameters
695696

696697
// user-defined sensors
697698
mjtDataType datatype; // data type for sensor measurement

include/mujoco/mjxmacro.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -540,6 +540,7 @@
540540
X ( int, sensor_objid, nsensor, 1 ) \
541541
X ( int, sensor_reftype, nsensor, 1 ) \
542542
X ( int, sensor_refid, nsensor, 1 ) \
543+
X ( int, sensor_intprm, nsensor, mjNSENS ) \
543544
X ( int, sensor_dim, nsensor, 1 ) \
544545
X ( int, sensor_adr, nsensor, 1 ) \
545546
X ( mjtNum, sensor_cutoff, nsensor, 1 ) \

python/mujoco/introspect/structs.py

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4149,6 +4149,14 @@
41494149
doc='id of reference frame; -1: global frame',
41504150
array_extent=('nsensor',),
41514151
),
4152+
StructFieldDecl(
4153+
name='sensor_intprm',
4154+
type=PointerType(
4155+
inner_type=ValueType(name='int'),
4156+
),
4157+
doc='sensor parameters',
4158+
array_extent=('nsensor', 'mjNSENS'),
4159+
),
41524160
StructFieldDecl(
41534161
name='sensor_dim',
41544162
type=PointerType(
@@ -10388,6 +10396,14 @@
1038810396
),
1038910397
doc='name of referenced object',
1039010398
),
10399+
StructFieldDecl(
10400+
name='intprm',
10401+
type=ArrayType(
10402+
inner_type=ValueType(name='int'),
10403+
extents=(2,),
10404+
),
10405+
doc='integer parameters',
10406+
),
1039110407
StructFieldDecl(
1039210408
name='datatype',
1039310409
type=ValueType(name='mjtDataType'),

src/user/user_model.cc

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3454,6 +3454,7 @@ void mjCModel::CopyObjects(mjModel* m) {
34543454
m->sensor_objid[i] = psen->obj ? psen->obj->id : -1;
34553455
m->sensor_reftype[i] = psen->reftype;
34563456
m->sensor_refid[i] = psen->ref ? psen->ref->id : -1;
3457+
mjuu_copyvec(m->sensor_intprm+i*mjNSENS, psen->intprm, mjNSENS);
34573458
m->sensor_dim[i] = psen->dim;
34583459
m->sensor_cutoff[i] = (mjtNum)psen->cutoff;
34593460
m->sensor_noise[i] = (mjtNum)psen->noise;

test/engine/engine_sensor_test.cc

Lines changed: 31 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -544,7 +544,37 @@ TEST_F(SensorTest, Clock) {
544544
mj_deleteModel(model);
545545
}
546546

547-
// test clock sensor
547+
// test that integer parameters pass through
548+
TEST_F(SensorTest, IntPrm) {
549+
constexpr char xml[] = R"(
550+
<mujoco>
551+
<sensor>
552+
<clock name="dummy"/>
553+
</sensor>
554+
</mujoco>
555+
)";
556+
ASSERT_EQ(mjNSENS, 2);
557+
558+
char err[1024];
559+
mjSpec* spec = mj_parseXMLString(xml, 0, err, sizeof(err));
560+
ASSERT_THAT(spec, NotNull()) << err;
561+
562+
mjModel* model = mj_compile(spec, nullptr);
563+
EXPECT_EQ(model->sensor_intprm[0], 0);
564+
EXPECT_EQ(model->sensor_intprm[1], 0);
565+
mj_deleteModel(model);
566+
567+
mjsSensor* s = mjs_asSensor(mjs_findElement(spec, mjOBJ_SENSOR, "dummy"));
568+
s->intprm[0] = 3;
569+
s->intprm[1] = 4;
570+
model = mj_compile(spec, nullptr);
571+
EXPECT_EQ(model->sensor_intprm[0], 3);
572+
EXPECT_EQ(model->sensor_intprm[1], 4);
573+
mj_deleteModel(model);
574+
mj_deleteSpec(spec);
575+
}
576+
577+
// test sequential collision sensors
548578
TEST_F(SensorTest, CollisionSequential) {
549579
constexpr char xml[] = R"(
550580
<mujoco>

unity/Runtime/Bindings/MjBindings.cs

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ public static class MujocoLib {
4949
public const int mjNFLUID = 12;
5050
public const int mjNREF = 2;
5151
public const int mjNIMP = 5;
52+
public const int mjNSENS = 2;
5253
public const int mjNSOLVER = 200;
5354
public const int mjNISLAND = 20;
5455
public const bool THIRD_PARTY_MUJOCO_INCLUDE_MJPLUGIN_H_ = true;
@@ -5683,6 +5684,7 @@ public unsafe struct mjModel_ {
56835684
public int* sensor_objid;
56845685
public int* sensor_reftype;
56855686
public int* sensor_refid;
5687+
public int* sensor_intprm;
56865688
public int* sensor_dim;
56875689
public int* sensor_adr;
56885690
public double* sensor_cutoff;

0 commit comments

Comments
 (0)