1

I'm new and currently working on my 6 Dof Arm project, right now I am try to simulate it using Mujoco but I don't really understand why and how it works, here is the problem: My 6 Dof Arm is always moving in the simulation.

I don't really know why, the position (home) I set it at 0 to all the joint but when I start the simulation the joint 3 and 6 (upperarm_joint and endeffector_joint) always moving so randomly, the log status so that joint 3 usually run from 0 to 0,9 and joint 6 usually run from 0 to 0.3 and not only that I can't control the any joint except the linear one.

I think is it because the servo do not have enough force, but when I create another file I change the force range to higher x100 but it's still not working, it only can move one time. How can I narrow down the problem?

Here is the link drive for all the robot asset you can download: https://drive.google.com/drive/folders/1D_i0oXhlEZeCfKm559ciYAL0cHJ87w60?usp=sharing

My code:

<mujoco model="robot"
  <compiler angle="degree" meshdir="assets" autolimits="true"/>
  <option integrator="implicitfast"/>
  <default>
    <default class="robot">
      <material specular="0.5" shininess="0.25"/>
      <default class="revolute">
        <joint range="0 180"/>
        <general gaintype="fixed" biastype="affine" ctrlrange="0 180"
                 gainprm="100 0 0" biasprm="0 0 0" forcerange="-1.5 1.5"/>
      </default>
      <default class="linear">
        <joint range="0 540" type="slide"/>
        <general gaintype="fixed" biastype="affine" ctrlrange="0 540"
                 gainprm="500 0 0" biasprm="0 -50 -100" forcerange="-200 200"/>
      </default>
      <default class="visual">
        <geom type="mesh" contype="0" conaffinity="0" group="2"/>
      </default>
      <site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
    </default>
  </default>
  <asset>
    <material class="robot" name="white" rgba="1 1 1 1"/>
    <material class="robot" name="jointgray" rgba="0.278 0.278 0.278 1"/>
    <material class="robot" name="linkgray" rgba="0.82 0.82 0.82 1"/>
    <material class="robot" name="blue" rgba="0.49 0.678 0.8 1"/>
    <mesh file="base.obj"/>
    <mesh file="gantry.obj"/>
    <mesh file="armbase.obj"/>
    <mesh file="forearm.obj"/>
    <mesh file="shoulder.obj"/>
    <mesh file="upperarm.obj"/>
    <mesh file="wrist.obj"/>
    <mesh file="endeffector.obj"/>
  </asset>
  <worldbody>
    <light name="spotlight" mode="targetbodycom" target="gantry" pos="0 -1 2"/>
    <body name="base" zaxis="1 0 0" childclass="robot">
      <inertial mass="4.0" pos="0 0 0" diaginertia="0.00443333156 0.00443333156 0.0072"/>
      <geom mesh="base" material="white" class="visual"/>
      <body name="gantry" pos="5 190 50 " euler="180 0 90">
        <inertial mass="3.7" pos="0 0 0" diaginertia="0.0102675 0.0102675 0.00666"/>
        <joint name="gantry_joint" class="linear" axis="-1 0 0" pos="0 0 0"/>
        <geom mesh="gantry" material="blue" class="visual"/>
        <geom mesh="armbase" material="white" class="visual" pos="-47 30 8"/>
        <body name="forearm_link" pos="-47 30 8">
          <inertial mass="3.7" pos="0 0 0" diaginertia="0.0102675 0.0102675 0.00666"/>
          <joint name="forearm_joint" class="revolute" axis="0 1 0" pos="0 0 16"/>
          <geom mesh="forearm" material="blue" class="visual"/>
          <body name="shoulder_link" pos="0 0 0">
            <inertial mass="8.393" pos="0 0 0.2125" diaginertia="0.133886 0.133886 0.0151074"/>
            <joint name="shoulder_joint" class="revolute" axis="1 0 0" pos="0 141 -19"/>
            <geom mesh="shoulder" material="linkgray" class="visual"/>
            <body name="upperarm_link" pos="0 0 0">
              <inertial mass="2.275" pos="0 0 0.196" diaginertia="0.0311796 0.0311796 0.004095"/>
              <joint name="upperarm_joint" class="revolute" axis="1 0 0" pos="0 195 -180"/>
              <geom mesh="upperarm" material="blue" class="visual"/>
              <body name="wrist_link" pos="0 0 0.0" zaxis="0 0 1">
                <inertial mass="1.219" pos="0 0.127 0" diaginertia="0.0025599 0.0025599 0.0021942"/>
                <joint name="wrist_joint" class="revolute" axis="0 0.3 -1" pos="0 230 -300"/>
                <geom mesh="wrist" material="white" class="visual"/>
                <body name="endeffector_link" pos="0 0 0">
                  <inertial mass="0.1889" pos="0 0.0771683 0" quat="1 0 0 1"
                    diaginertia="0.000132134 9.90863e-05 9.90863e-05"/>
                  <joint name="endeffector_joint" class="revolute" axis="1 0 0" pos="-125 236.5 -342.7"/>
                  <geom material="linkgray" mesh="endeffector" class="visual"/>
                  <site name="attachment_site" pos="0 0.1 0" quat="-1 1 0 0"/>
                </body>
              </body>
            </body>
          </body>
        </body>
      </body>
    </body>
  </worldbody>
  <actuator>
    <position class="linear" name="gantry_act" joint="gantry_joint"
              kp="500" kv="60" ctrlrange="0 540" forcerange="-200 200"/>
    <position class="revolute" name="forearm_actuator" joint="forearm_joint"
              kp="120" kv="12" ctrlrange="0 180" forcerange="-1.5 1.5"/>
    <position class="revolute" name="shoulder_actuator" joint="shoulder_joint"
              kp="180" kv="18" ctrlrange="0 180" forcerange="-1.5 1.5"/>
    <position class="revolute" name="upperarm_actuator" joint="upperarm_joint"
              kp="140" kv="30" ctrlrange="0 180" forcerange="-1.5 1.5"/>
    <position class="revolute" name="wrist_actuator" joint="wrist_joint"
              kp="100" kv="10" ctrlrange="0 180" forcerange="-1.5 1.5"/>
    <position class="revolute" name="endeffector_actuator" joint="endeffector_joint"
              kp="80" kv="8" ctrlrange="0 180" forcerange="-1.5 1.5"/>
  </actuator>
  <keyframe>
    <key name="home" qpos="0 0 0 0 0 0" ctrl="0 0 0 0 0 0"/>
  </keyframe>
</mujoco>
1
  • "robotframework" has nothing to do with robots. it's a framework for testing software. Commented Aug 9 at 12:00

0

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Start asking to get answers

Find the answer to your question by asking.

Ask question

Explore related questions

See similar questions with these tags.