@@ -75,10 +75,11 @@ void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int start_roll,
75
75
const mjtNum* state0, const mjtNum* warmstart0,
76
76
const mjtNum* control, mjtNum* state, mjtNum* sensordata) {
77
77
// sizes
78
- int nstate = mj_stateSize (m[0 ], mjSTATE_FULLPHYSICS);
79
- int ncontrol = mj_stateSize (m[0 ], control_spec);
80
- int nv = m[0 ]->nv , nbody = m[0 ]->nbody , neq = m[0 ]->neq ;
81
- int nsensordata = m[0 ]->nsensordata ;
78
+ size_t nstate = static_cast <size_t >(mj_stateSize (m[0 ], mjSTATE_FULLPHYSICS));
79
+ size_t ncontrol = static_cast <size_t >(mj_stateSize (m[0 ], control_spec));
80
+ size_t nv = static_cast <size_t >(m[0 ]->nv );
81
+ int nbody = m[0 ]->nbody , neq = m[0 ]->neq ;
82
+ size_t nsensordata = static_cast <size_t >(m[0 ]->nsensordata );
82
83
83
84
// clear user inputs if unspecified
84
85
if (!(control_spec & mjSTATE_CTRL)) {
@@ -92,7 +93,7 @@ void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int start_roll,
92
93
}
93
94
94
95
// loop over rollouts
95
- for (int r = start_roll; r < end_roll; r++) {
96
+ for (size_t r = start_roll; r < end_roll; r++) {
96
97
// clear user inputs if unspecified
97
98
if (!(control_spec & mjSTATE_MOCAP_POS)) {
98
99
for (int i = 0 ; i < nbody; i++) {
@@ -117,7 +118,7 @@ void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int start_roll,
117
118
118
119
// set warmstart accelerations
119
120
if (warmstart0) {
120
- mju_copy (d->qacc_warmstart , warmstart0 + r* nv, nv);
121
+ mju_copy (d->qacc_warmstart , warmstart0 + r * nv, nv);
121
122
} else {
122
123
mju_zero (d->qacc_warmstart , nv);
123
124
}
@@ -128,7 +129,7 @@ void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int start_roll,
128
129
}
129
130
130
131
// roll out trajectory
131
- for (int t = 0 ; t < nstep; t++) {
132
+ for (size_t t = 0 ; t < nstep; t++) {
132
133
// check for warnings
133
134
bool nwarning = false ;
134
135
for (int i = 0 ; i < mjNWARNING; i++) {
@@ -141,7 +142,7 @@ void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int start_roll,
141
142
// if any warnings, fill remaining outputs with current outputs, break
142
143
if (nwarning) {
143
144
for (; t < nstep; t++) {
144
- int step = r*nstep + t;
145
+ size_t step = r*static_cast < size_t >( nstep) + t;
145
146
if (state) {
146
147
mj_getState (m[r], d, state + step*nstate, mjSTATE_FULLPHYSICS);
147
148
}
@@ -152,24 +153,24 @@ void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int start_roll,
152
153
break ;
153
154
}
154
155
155
- int step = r*nstep + t;
156
+ size_t step = r*static_cast < size_t >( nstep) + t;
156
157
157
158
// controls
158
159
if (control) {
159
- mj_setState (m[r], d, control + step* ncontrol, control_spec);
160
+ mj_setState (m[r], d, control + step * ncontrol, control_spec);
160
161
}
161
162
162
163
// step
163
164
mj_step (m[r], d);
164
165
165
166
// copy out new state
166
167
if (state) {
167
- mj_getState (m[r], d, state + step* nstate, mjSTATE_FULLPHYSICS);
168
+ mj_getState (m[r], d, state + step * nstate, mjSTATE_FULLPHYSICS);
168
169
}
169
170
170
171
// copy out sensor values
171
172
if (sensordata) {
172
- mju_copy (sensordata + step* nsensordata, d->sensordata , nsensordata);
173
+ mju_copy (sensordata + step * nsensordata, d->sensordata , nsensordata);
173
174
}
174
175
}
175
176
}
@@ -226,7 +227,8 @@ mjtNum* get_array_ptr(std::optional<const py::array_t<mjtNum>> arg,
226
227
py::buffer_info info = arg->request ();
227
228
228
229
// check size
229
- int expected_size = nbatch * nstep * dim;
230
+ size_t expected_size =
231
+ static_cast <size_t >(nbatch) * static_cast <size_t >(nstep) * static_cast <size_t >(dim);
230
232
if (info.size != expected_size) {
231
233
std::ostringstream msg;
232
234
msg << name << " .size should be " << expected_size << " , got " << info.size ;
0 commit comments