RobotiqThreeFingerGripper articulation and control
I am trying to simulate a robotiq 3 finger gripper. In my environment I would like to have only one gripper that is currently fixed in space.
I'm controlling the gripper by modifying the MjSim.data.ctrl attribute which has 4 actuators, one for each of the 3 fingers and a fourth actuator to change the distance between the two fingers (scissors). The articulation of the simulated gripper is different from the real gripper. The upper phalanx of the real gripper bends completely when the joint is at maximum, this does not happen in the simulation.
This is a frame from the simulation, the scissor is completely open and the 3 fingers are closed.
the gripper I own behaves differently under the same condition:
Am I doing something wrong in the control of the actuators? Is there an API to control the gripper similar to that for controlling robots? thanks in advance for the support
This is the code to reproduce the behavior.
import xml.etree.ElementTree as ET
from robosuite.models import MujocoWorldBase
from robosuite.models.arenas.table_arena import TableArena
from robosuite.models.grippers import RobotiqThreeFingerGripper,RobotiqThreeFingerDexterousGripper
from robosuite.models.objects import BoxObject
from robosuite.utils import OpenCVRenderer
from robosuite.utils.binding_utils import MjRenderContextOffscreen, MjSim
world = MujocoWorldBase()
arena = TableArena(table_full_size=(0.4, 0.4, 0.05), table_offset=(0, 0, 1.1), has_legs=False)
world.merge(arena)
gripper = RobotiqThreeFingerGripper()
gripper_body = ET.Element("body", name="gripper_base")
gripper_body.set("pos", "0 0 1.32")
# gripper_body.set("quat", "0 0 1 0") # flip z
world.worldbody.append(gripper_body)
world.merge(gripper, merge_body="gripper_base")
# add an object for grasping
mujoco_object = BoxObject(
name="box", size=[0.02, 0.02, 0.02], rgba=[1, 0, 0, 1], friction=[1, 0.005, 0.0001]
).get_obj()
# Set the position of this object
mujoco_object.set("pos", "0 0 1.50")
# Add our object to the world body
world.worldbody.append(mujoco_object)
# start simulation
model = world.get_model(mode="mujoco")
sim = MjSim(model)
viewer = OpenCVRenderer(sim)
render_context = MjRenderContextOffscreen(sim, device_id=1)
sim.add_render_context(render_context)
sim_state = sim.get_state()
sim.set_state(sim_state)
gripper_actuators = [sim.model.actuator_name2id(x) for x in gripper.actuators]
STEP = 0
i = 0
while True:
# Step through sim
if STEP < 99:
sim.data.ctrl[gripper_actuators] = [0, 0, 0, -1 / (100 - STEP)]
if STEP >= 400:
if not i >= 1:
i += 0.01
sim.data.ctrl[gripper_actuators] = [i,i,i, -1]
print("STEP", STEP)
sim.step()
viewer.render()
STEP += 1
The joints seem to be correctly defined in the xml file. But I could be wrong given my little experience with mujoco.
After a few hours of work on the XML I was able to get this. Should I submit a pull request?
Thanks for opening up the issue. If you can create a pull request for us to review, that would be great. We really appreciate the contribution!
I haven't forgotten about this problem, I haven't done any more PR because I haven't actually solved the problem yet (the actuation articulation is anything but precise) but I will work on it soon. If you have any updates please post them here.