Capturing a state in Simulation

Discussion in 'Priority support' started by Nihar S Talele, Feb 27, 2019.

  1. I am running a simulation of 5 link planar walker in mujoco. I want to loop the simulation such that when I detect a certain condition in the simulation, I want to capture that state, save it and then start the simulation from that state with t=0 and x coordinate in qpos set to 0. For eg. I start the simulation at t=0 and x=0 and then at the end of t=5s I want to capture that state and save it and using this state I want to start the simulation again from t=0 and x=0. In order to do this do I have to copy the entire mjdata structure to simulate accurately from that state?
    I am using mujoco_py and using the get_state() function which only captures time, qpos, qvel, actuator and udd_callback fields. Is this enough information to simulate accurately from the captured state or do I need to copy the entire mjdata structure?
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    Definitely do not copy the entire mjData. It is big, and most of it is re-computed automatically given the state.

    In most cases the state is just (qpos, qvel). If you are using actuators with third-order dynamics then mjData.act is also part of the state (don't know if 'actuator' in mujoco_py means that or something else).

    Note that the constraint solver uses warm-starts, so the field qacc_warmstart is technically also part of the state. You can disable warm-starts but that may slow down the simulation. See longer discussion of state here:

    http://www.mujoco.org/book/programming.html#siStateControl
     
  3. Ok Thanks! I was missing the qacc_warmstart so my state values were slightly different. Although if I'm correct I think that may just be because of the early termination of the optimization algorithm
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    Yes it is because of early termination. Constraint forces are computed by solving a convex optimization problem which has a unique minimum. If you run the Newton solver to convergence and set the tolerance to a small value, say 1e-10, then warm-starts will affect the number of iterations but not the final solution.