How to Handle Floating Base Issues in Mujoco with a Robotic Arm?

Typically: "How do I... ", "How can I... " questions
Post Reply
zorro
Posts: 27
Joined: 06 Nov 2023, 09:31

How to Handle Floating Base Issues in Mujoco with a Robotic Arm?

Post by zorro »

Hello!

I am creating a scene with a crawling robotic arm. In this scene, there is a state where the robotic arm doesn't have a base. In this configuration, the robotic arm relies on a dummy attached to an end effector link and another dummy on an object without dynamics for connection. The joints of the robotic arm are set to position control mode in Dynamic Mode.

Everything works fine in the Bullet engine, but in the Mujoco engine, as long as the robotic arm doesn't have a base, it tends to enter an unstable state, with all joints starting to move erratically. How can this situation be handled? I have created a scene to demonstrate this issue:

For the first robotic arm, the base is connected to a cube through a dummy. After simulation, dragging the cube with the mouse stabilizes the robotic arm better as the mass of the cube increases.

For the second robotic arm, the end effector link is connected to a cube through a dummy. After simulation, the robotic arm tends to jerk or twitch.

https://1drv.ms/u/s!Ar1_NNuNx1urnExoOKx ... f?e=niBmUe

zorro
Posts: 27
Joined: 06 Nov 2023, 09:31

Re: How to Handle Floating Base Issues in Mujoco with a Robotic Arm?

Post by zorro »

I've tried many times but still couldn't achieve my requirements in Mujoco, so I temporarily used Bullet to implement it. However, soon I encountered a new problem. I will provide my `.ttt` and `.py` files to illustrate this specific issue. As I mentioned earlier, the concept of the base and end of my robotic arm is somewhat ambiguous, and it crawls by alternating through the end effector. Previously, I achieved this by swapping the order of all joints and links after each crawl, but that method can only be considered a workaround. Therefore, I want to achieve the same functionality without changing the hierarchical structure of the robotic arm.

Here's my scene setup: Firstly, there's a cube `Cuboid[0]` as the fixed end of the robotic arm. This cube has a child object named `lock`. Next is my robotic arm, and the last joint of the arm contains a dummy named `lock`. These two dummies are connected with "Dynamic,overlap_constraint" to simulate the end effector of the robotic arm being fixed to a base. To call the `simIK` library, I set the respective `Target` and `tip` dummies. In the air, there's a target point dummy named `tar_test`, and two cuboids as obstacles.

Now, I need to find a collision-free inverse solution to reach the target point and plan a collision-free path. Unlike the usual case, the end effector of my robotic arm is actually stationary, and the base of the robotic arm becomes the freely moving end. Therefore, some transformations need to be done when solving the inverse kinematics. The specific code is as follows:

```python

Code: Select all

pose = sim.getObjectPose(simTip, targets[i])  # Originally: pose = sim.getObjectPose(targets[i], simBase)
simIK.setObjectPose(ikEnv, ikTarget, pose, ikBase)
```

After obtaining the collision-free inverse solution, I perform path planning. The rest of the code remains unchanged.

The current situation is that the robotic arm can indeed obtain a correct collision-free inverse solution and can also plan a path to reach the Goal State through OMPL. However, this path often has collisions. This is the biggest problem. I think this must be caused by the special connection form of my robotic arm. However, I believe that the processes of solving the inverse kinematics and path planning should be decoupled. OMPL should only need me to provide the current config and the target config, and theoretically should not be affected by the connection of the robotic arm.

I hope you can help me figure out what's causing this issue. I think this can also be considered a special case. Thank you very much!

https://1drv.ms/f/s!Ar1_NNuNx1urnFHkiPY ... J?e=OuH46n

coppelia
Site Admin
Posts: 10376
Joined: 14 Dec 2012, 00:25

Re: How to Handle Floating Base Issues in Mujoco with a Robotic Arm?

Post by coppelia »

Hello,

indeed, something is strange at first sight... I can't put my finger on it. Upside-down causes the joint controller to behave strangely, while bottom-up, things look relatively ok.
This is not the reason, but make sure to adjust the 'armature' MuJoCo parameter somewhat to the upside (in general).

Cheers

zorro
Posts: 27
Joined: 06 Nov 2023, 09:31

Re: How to Handle Floating Base Issues in Mujoco with a Robotic Arm?

Post by zorro »

Thank you for the response!
Adjusting the "armature" parameter does indeed reduce the extent to which the robotic arm joints lose control, but the state where the robotic arm loses control is still unacceptable to me. I've temporarily given up on using Mujoco to implement this scene.
Could you please help me take a look at the issue with OMPL mentioned in the second post?

coppelia
Site Admin
Posts: 10376
Joined: 14 Dec 2012, 00:25

Re: How to Handle Floating Base Issues in Mujoco with a Robotic Arm?

Post by coppelia »

About your second problems:

Many things can go wrong or are rather tricky:
  • You have the sim and IK world. They should be synced, otherwise you'll see some strange effects due to mismatches
  • Since your robot can be upside-down, things get tricky because the IK world does not understand upside-down (and the sim world neither by the way: only the dynamics engine resolves the upside-down robot configuration, but the hierarchy and how coppeliaSim sees it is always upside-up!)
  • So e.g. if you apply a configuration to check if it is collision-free, then the dynamics engine doesn't resolve the connection constraint.
I would take another more pragmatic approach, that would also solve the MuJoCo problem you have:
  • Build two robot models, one normal, then other one upside-down
  • At any time, have just one model enabled, i.e. visible and dynamically enabled, etc. Check the model properties, also with sim.setModelProperty / sim.getModelProperty. Changing this will trigger a MuJoCo world rebuild, that takes a few moments and might slow-down things.
  • When the attachement needs to switch, simply make sure both models are overlapping, then switch them out (disable one, while enabling the other)
  • In the IK world, also have two IK models for each of the two robots.
The only problem with above approach that I see is if the simulations are highly dynamic while switching contact points (e.g. the robot is moving during that time, s.g. like in a zero-gravity situation as it appears you are in). In that case, you'll have to go the hard route.

Also, while computing IK and Path planning, make sure that simulation is not moving forward, otherwise you might mess up the dynamics. Use the stepping mode.

Cheers

Post Reply