Skip to content

Commit 5ba4d58

Browse files
committed
replace array on stack with std::vector
1 parent bd36144 commit 5ba4d58

File tree

1 file changed

+3
-2
lines changed

1 file changed

+3
-2
lines changed

python/mujoco/rollout.cc

+3-2
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ Roll out open-loop trajectories from initial states, get resulting states and se
5454
// C-style rollout function, assumes all arguments are valid
5555
// all input fields of d are initialised, contents at call time do not matter
5656
// after returning, d will contain the last step of the last rollout
57-
void _unsafe_rollout(const mjModel** m, mjData* d, int nroll, int nstep, unsigned int control_spec,
57+
void _unsafe_rollout(std::vector<const mjModel*>& m, mjData* d, int nroll, int nstep, unsigned int control_spec,
5858
const mjtNum* state0, const mjtNum* warmstart0, const mjtNum* control,
5959
mjtNum* state, mjtNum* sensordata) {
6060
// sizes
@@ -198,7 +198,8 @@ PYBIND11_MODULE(_rollout, pymodule) {
198198
) {
199199
// get raw pointers
200200
int nroll = state0.shape(0);
201-
const raw::MjModel* model_ptrs[nroll];
201+
std::vector<const raw::MjModel*> model_ptrs;
202+
model_ptrs.reserve(nroll);
202203
for (int r = 0; r < nroll; r++) {
203204
model_ptrs[r] = m[r].cast<const MjModelWrapper*>()->get();
204205
}

0 commit comments

Comments
 (0)