[SOLVED] pybullet urdf cartpole model joint does not move

Post Reply
benelot
Posts: 350
Joined: Sat Jul 04, 2015 10:33 am
Location: Bern, Switzerland
Contact:

[SOLVED] pybullet urdf cartpole model joint does not move

Post by benelot »

Hello,

I know that this is a pretty exotic question for the bullet physics forum, but I still give it a try.

I am working on a cartpole model for reinforcement learning with pybullet, so the model is built in urdf. The model looks all well but the joint between the cart and the pole somehow is fixed instead of continuous. Can anybody spot the problem here:

Code: Select all

<?xml version="1.0"?>
<robot name="cartpolev0">
  <link name="cart">
    <contact>
      <lateral_friction value="1.0"/>
      <rolling_friction value="0.0"/>
      <inertia_scaling value="3.0"/>
      <contact_cfm value="0.0"/>
      <contact_erp value="1.0"/>
    </contact>
    <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.0 0.0"/>
      <geometry>
        <box size="0.2 0.2 0.05"/>
      </geometry>
      <material name="blockmat">
        <color rgba="0.9 0.2 0.1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.0 0.0 0.0"/>
      <geometry>
        <box size="0.2 0.2 0.05"/>
      </geometry>
    </collision>
  </link>

  <joint name="cart_pole_joint" type="continuous">
    <parent link="cart"/>
    <child link="pole"/>
    <origin rpy="1.57 0 0" xyz="0 0 0"/>
    <axis xyz="0 1 0"/>
  </joint>

  <link name="pole">
    <contact>
      <lateral_friction value="1.0"/>
      <rolling_friction value="0.0"/>
      <inertia_scaling value="3.0"/>
      <contact_cfm value="0.0"/>
      <contact_erp value="1.0"/>
    </contact>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.2"/>
      <inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0.0 0.25 0.0"/>
      <geometry>
        <box size="0.02 0.5 0.02"/>
      </geometry>
      <material name="blockmat">
        <color rgba="0.2 0.7 0.1 1"/>
      </material>
    </visual>
    <collision>
      <origin rpy="0 0 0" xyz="0.0 0.25 0.0"/>
      <geometry>
        <box size="0.02 0.5 0.02"/>
      </geometry>
    </collision>
  </link>
 </robot>
Any help would be appreciated!
benelot
Posts: 350
Joined: Sat Jul 04, 2015 10:33 am
Location: Bern, Switzerland
Contact:

Re: pybullet urdf cartpole model joint does not move

Post by benelot »

Apparently it is not the model, it is that every multibody somehow is very rigid by default. I experienced the same with the loaded nao robot.
User avatar
Erwin Coumans
Site Admin
Posts: 4221
Joined: Sun Jun 26, 2005 6:43 pm
Location: California, USA
Contact:

Re: pybullet urdf cartpole model joint does not move

Post by Erwin Coumans »

All revolute and slider joints have active motors. Try using pybullet.setJointMotorControl2 in p.VELOCITY_CONTROL mode using force = 0. I'll clarify it in the pybullet quickstart guide.
benelot
Posts: 350
Joined: Sat Jul 04, 2015 10:33 am
Location: Bern, Switzerland
Contact:

Re: pybullet urdf cartpole model joint does not move

Post by benelot »

Oh ok, thank you! I was expecting something like that after a while. What is the reasoning for enabling them by default? Is this just meant to actively keep up the current robot pose when not changing anything?
Post Reply