The masses of Two balls are twice of the mass of white box.
The initial velocities and angular velocities are all 0, and the gravity is also 0.
Only the red ball starts to rotate around upper right corner of the white box with axis aligned top line of the box.
The green ball is fixed to the white box.
When a simulation starts, white box starts to rotate opposite direction of red ball by the counter action, this is natural.
What seems very unnatural is the motion is too stable. Since the heavy red ball rotates around non centre of mass,
I think the white box should show wobble motion, but the simulation says white box only rotates smoothly.
The python code and URDF are as follows. Are there some mistakes?
Code: Select all
import pybullet as p
import time
physicsClient = p.connect(p.GUI)
body = p.loadURDF("b.urdf",0,0,1)
p.changeDynamics(body, -1, linearDamping = 0.0, angularDamping = 0.0)
p.changeDynamics(body, 0, linearDamping = 0.0, angularDamping = 0.0)
p.setJointMotorControl2(
body, 0, p.VELOCITY_CONTROL,
targetVelocity = 5, force = 1000
)
while True:
p.stepSimulation()
time.sleep(0.01)
Code: Select all
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1.0 .4 2.0"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1.0 .4 2.0"/>
</geometry>
</collision>
</link>
<link name="ball">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 1"/>
<geometry>
<sphere radius="0.2"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 1"/>
<geometry>
<sphere radius="0.2"/>
</geometry>
</collision>
</link>
<joint name="joint_baseLink_ball" type="continuous">
<parent link="baseLink"/>
<child link="ball"/>
<origin xyz="0.7 0 1"/>
<axis xyz="1 0 0"/>
</joint>
<link name="ball2">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="2"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 1"/>
<geometry>
<sphere radius="0.2"/>
</geometry>
<material name="green">
<color rgba="0 1 0 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 1"/>
<geometry>
<sphere radius="0.2"/>
</geometry>
</collision>
</link>
<joint name="joint_baseLink_ball2" type="fixed">
<parent link="baseLink"/>
<child link="ball2"/>
<origin xyz="-0.7 0 1"/>
</joint>
</robot>