Skip to content

Conversation

magdelinekuan
Copy link

  • Created a new MJCF file of the openarm bimanual robot that uses position control for each of the joints
  • Modified joint limits according to those provided in the openarm_bimanual URDF
  • Added forcerange according to peak torque specified in motor datasheets
  • Added kp and damping to reduce overshoot and oscillations in simulation (may not reflect real values)

magdelinekuan and others added 5 commits July 16, 2025 11:25
Add support for simulated openarm hardware with MuJoCo backend.

Refactor the mujoco

Move meshes to top level

Add back the readme
Co-authored-by: Sutou Kouhei <kou@cozmixng.org>
Co-authored-by: Sutou Kouhei <kou@cozmixng.org>

Update openarm_mujoco_hardware/include/openarm_mujoco_hardware/openarm_mujoco_hardware.hpp

Co-authored-by: Sutou Kouhei <kou@cozmixng.org>

Update openarm_mujoco_hardware/openarm_mujoco_hardware.xml

Co-authored-by: Sutou Kouhei <kou@cozmixng.org>

Update openarm_mujoco_hardware/package.xml

Co-authored-by: Sutou Kouhei <kou@cozmixng.org>

Update openarm_mujoco_hardware/test/test_load_openarm_mujoco_hardware.cpp

Co-authored-by: Sutou Kouhei <kou@cozmixng.org>

Update openarm_mujoco_hardware/src/openarm_mujoco_hardware.cpp

Co-authored-by: Sutou Kouhei <kou@cozmixng.org>
Comment on lines 4 to +6
<default class="motor">
<joint armature="0.001" frictionloss="0.1"/>
<motor ctrlrange="-0.2 0.2"/>
<motor ctrlrange="-0.2 0.2" gear="10"/>
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It might be more worth it to add the damping property to the class here instead of repeating it below.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Also, if we are updating gearing ratios, might as well also add armature:
https://mujoco.readthedocs.io/en/stable/XMLreference.html#body-joint-armature

@@ -46,48 +48,48 @@
<geom name="right_link1_collision" pos="0.0 0.0 0.0289" type="box" size="0.055 0.0365 0.0296" class="collision" />
<geom name="right_link1_visual" pos="0.0 0.0 -0.0007" material="gray" type="mesh" mesh="link1.stl" class="visual" />
<body name="right_link2" pos="0.0 0.0 0.05325">
<joint name="right_rev1" type="hinge" class="motor" range="-2.0943951023931953 2.0943951023931953" axis="0 0 1" />
<joint name="right_rev1" type="hinge" class="motor" damping="2.0" range="-2.0943951023931953 2.0943951023931953" axis="0 0 1" />
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants