How to get mjcb_control to point to object member function?

Discussion in 'Simulation' started by AQLK, Dec 14, 2016.

  1. Hi,

    I wrote (in MuJoCo Pro, C++, VS2013) a sample program without classes, in which the model was loaded in the main() function (like your simulator example). After loading the model from xml I set: mjcb_control = myController;

    Where I had:
    void myController(const mjModel* mArg, mjData* dArg) {
    //Some useful code here
    dArg->act[someindex] = some actuator force/torque;
    }

    this worked perfectly fine.

    Now I want to encapsulate everything in a class, e.g.
    class Robot {
    public:
    Robot();
    ~Robot();
    private:
    mjModel* m = 0;
    mjData* d = 0;
    void myController(const mjModel*, mjData*);
    double someUsefulState = 0.0;

    };

    To create multiple robots (separate simulations to step through) in parallel.

    In the class constructor I want to attach/install the callback to the private myController(...) of this specific instance of the class, and maybe I want for this object instance to point it to a different controller function (i.e. it cannot be a static member function, also due to using instance specific data since it uses someUsefulState) that might be given as a constructor argument (not in the MWE below).

    I tried something like this:
    Robot::Robot()
    {
    //Something else happens first
    //...

    //Finally
    void(*cbFunPtr)(const mjModel* m, mjData* d) = this->myController;
    mjcb_control = cbFunPtr;
    }


    But installing the function pointer that way does not work. I don't know how to do the syntax for this properly. It mostly complains that whatever I do cannot be assigned to an entity of type mjfGeneric, or missing argument lists.

    Thanks!
     
  2. I was attempting this to allow for multi-threaded parallel calculation.

    But even though, if mjcb_control is only 'global', is there a way to pass an extra argument to the callback function (apart from mjModel and the mjData of the thread) so that in my control callback function I knows which mjData it is operating on?

    My current plan is to put some identifier, or even controller state data, in mjData->userdata.
     
  3. Vikash Kumar

    Vikash Kumar Staff Member

    That's exactly the purpose of userdata. Use it to you advantage. Make sure to assign an appropriate size to nuserdata field before using it.
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    Function pointers to class members are indeed complicated as you discovered. Saving an identified in mjData.userdata is the way to do it as Vikash suggested.

    Also, are you sure you actually need this identifier? Assuming each copy of mjData contains different state information, the same feedback controller will generate different controls... unless of course you need different feedback controllers for the different copies of mjData.
     
  5. Well, actually my controller is a neuromuscular controller with multiple muscles that have their own state that have to be integrated over time, but the joint actuator torques are a non-linear function of that state (i.e. I cannot use 'dyntype integrator' or 'mjcb_act_dyn'). The other mjData models should of course not use another model's muscle state.

    The controller dynamics are of the form:
    act = ctrl = f(s,s_dot,t)

    with f some nonlinear function of some state s, its derivative s_dot (these are not actuator or states of the rigid bodies in the model) and possibly mjData->time. State s is the time integrated from s_dot. It is not of the form act_dot = g(act,ctrl,t), with some nonlinear function g.

    As far as I understood, I cannot do this with 'dyntype integrator' or by using 'mjcb_act_dyn', since I cannot have MuJoCo integrate s_dot to s (I could start making 'useless' actuators that have 'integrator dyntype' to have s_dot integrate over time and use in function f to calculate ctrl/act?). It feels like I have to integrate s_dot myself with SIEuler or RK4 myself 'in parallel' to MuJoCo within the controller callback, since if I would store state s in mjData->userdata every time (sub)step, it is not integrated over time.
    As Emo Todorov says: "Assuming each copy of mjData contains different state information", how can I get mjData to contain state information and integrate it by itself (so not userdata), without it being an act_dot to act state or a rigid body state.

    Hopefully I completely missed the/some point and what I want actually can be done.
    So actually my problem has shifted from what I mentioned in the OP. Since if this integration can be done, a single global controller callback function would be sufficient, as Emo Todorov suggested.
     
  6. Emo Todorov

    Emo Todorov Administrator Staff Member

    Hmm, the muscle model you are using is different from what I had in mind when designing MuJoCo. My idea was to have the actuator activation state (stored in mjData.act) be linearly related to muscle force, with some state-dependent gain that captures the length-velocity-tension curve. But you want the activation state to have an arbitrary nonlinear relation to muscle force. The only way to do this is to keep your own activation states (in mjData.userdata or a separate buffer that you allocated) and integrate them in parallel with the MuJoCo simulation, as you described. Sorry about the inconvenience, but there are too many muscles models out there, so it is hard to come up with a computationally efficient abstraction that captures all of them.
     
  7. Ok thank you for the responses :). Now I know the proper way(s) to solve the problem.

    Will it be implemented in the future that one could have 'arbitrary' states be integrated the MuJoCo integrator? Like appending the q_pos/q_vel vectors?
     
  8. Emo Todorov

    Emo Todorov Administrator Staff Member

    Haven't decided yet, so don't count on it for now. Apart from wanting to avoid feature creep, one specific concern here is that some auxiliary states may need to be integrated with custom integrators that are not part of MuJoCo. For example, if such variables have much faster dynamics, you may need different integration timesteps, or maybe even analytical solutions (in the case of fast linear dynamics).
     
  9. Emo Todorov

    Emo Todorov Administrator Staff Member

    No. Users should implement custom integrators for auxiliary state variables as needed. Note the field mjData.userdata. It can be used to store extra state variables; MuJoCo does not touch that data.