Beginner question: How to specify time-varying actuator torques?

Discussion in 'Simulation' started by Chris Richards, Jun 7, 2016.

  1. Dear Forum,
    I am very new to MuJoCo and have read much of the documentation, but have no experience simulating in this platform. I have a naive question (and a follow-up):

    Is it possible to specify an arbitrary predefined actuator torque waveform (instead of a constant torque value)? Where would this waveform be specified - in the XML file? Or would a .txt file be called somewhere in the C code or XML?

    To help me understand, are there any examples/samples available that include non-zero actuator torques? All of the samples I've seen so far are passive as far as I can tell.

    Thanks for your time,
    Chris
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    This is done programmatically. See example below. If you don't have actuators in your model and want to specify applied torques directly, set the field d->qfrc_applied instead of d->ctrl. As in all other examples, m and d are of type mjModel* and mjData* respectively.

    // generate sinusoidal control waveform
    void setcontrol(mjtNum time, mjtNum* ctrl, int nu)
    {
    for( int i=0; i<nu; i++ )
    ctrl = mju_sin(time);
    }

    // simulation loop
    {
    // set control vector
    setcontrol(d->time, d->ctrl, m->nu);

    // advance simulation state with specified controls
    mj_step(m, d);
    }
     
  3. Fantastic, that makes sense to me, thanks for the quick reply! I now see that the documentation lists the built-in math functions...

    But, is it also possible to substitute the mju_sin(time) function for an arbitrary waveform "wav" (see below) sampled at discrete time intervals - i.e. to load some data from a .txt file into an array that is indexed as the simulation steps forward?

    e.g.
    // following some kind of declaration of wav as an array of appropriate size...
    wav = "data loaded from file...";
    ctrl = wav;

    Thanks again for answering my basic questions- I'm trying to get a feel for the capabilities of the software to help me decide whether I want to purchase it for my lab. I have some background in modeling rigid body dynamics in Mathematica and am conversant in python, but have no experience with C (although my student does).

    Chris
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    You can do this by extending the setcontrol function from the above example. In that function, use the simulation time index and look up the data in a global array that you allocated and filled in earlier (possibly by loading the data from a file). Note also that you can install a control callback, by setting the global pointer mjcb_control to point to your function. It will get called automatically from within mj_step whenever the simulator needs the control signals to be filled in.

    We will soon release a mex file that allows you to call MuJoCo from MATLAB. OpenAI has released something similar for Python. We don't have plans to integrate with Mathematica, but maybe one of the users will do that, by adapting the MATLAB or Python integration code.
     
    yongxf likes this.
  5. That's fantastic, thanks again for the prompt reply. I'm sure that function will suit my needs.
    Thanks again,
    Chris