Modelling 3D Goal for reacher

Discussion in 'Modeling' started by Andrea Franceschetti, Nov 4, 2017.

  1. Hello to everybody!
    I'm trying to create a controllable 3D goal for my UR5+gripper environment...
    Obviously i followed the example of the 2D reacher MuJoCo Gym model, adding one more slide joint with axis, yet the sphere is falling due to gravity.
    I tried to bump up damping and stiffness to hold the goal in place, but it seems to me a bad way to do it..

    Code:
            <body name="goal" pos="0 0 1.4">
                <joint name="goal_x" axis="1 0 0" type="slide" damping="0" stiffness="0" armature="0"/>
                <joint name="goal_y" axis="0 1 0" type="slide" damping="0" stiffness="0" armature="0"/>
                <joint name="goal_z" axis="0 0 1" type="slide" damping="40" stiffness="100" armature="0"/>
                <geom name="goal" conaffinity="0" contype="0" size="0.05" type="sphere" rgba="1 0 0 0.2" />
            </body>
    I don't want to disable gravity, since my arm must compensate its weight with the motors, besides reaching the goal.
    Any useful tips?
    Thank you so much!!
     
  2. Any news? I have not found any solution to this simple problem :(
     
  3. Hi, do you need the joints for the goal? You could consider simply removing them since you don't want any dynamics on the goal object. You can still programmatically set the goal coordinates without joints by modifying body_pos.
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    MuJoCo has a special type of body called mocap body. It is fixed for the purposes of physics simulation, but its position and orientation are in mjData.mocap_pos/quat, and the idea is that the user will be changing them programmatically at runtime. They were introduced to help stream motion capture data into a simulation, but you could also use them for goal setting.
     
  5. Sorry for the delay.. I followed your suggestion @Emo Todorov , and it works great!
    Yet the mujoco_py wrapper gives a Runtime Warning of the type:
    Code:
    RuntimeWarning: invalid value encountered in true_divide
      return lin_moms / mass.reshape((-1, 1))
    Something is wrong with masses?

    My goal is now simply

    Code:
    <body name="goal" pos="0 0 0" mocap="true">
       <geom name="goal" conaffinity="0" contype="0" size="0.05" type="sphere" rgba="1 0 0 0.2" />
    </body>
     
    Last edited: Dec 1, 2017
    Kyokushin likes this.