1
$\begingroup$

I can't seem to find any examples with imported URDFs (the universal robot examples don't seem to have any physics settings beyond joint inertias etc).

My robot has mass from the urdf:

The robot has mass

But it seems to just float:

enter image description here

If I manually add physics in webots (by right clicking on physics and adding a physics node) it falls as expected but the wheels fall off (despite still moving around with the controllers).

enter image description here

While amusing, this isn't exactly what I'd like it to do. Is there a physics tag or something I might be missing in the urdf?

These are the only webots sections I have in the urdf at the moment because it's all I could find reference to in the examples.

  <webots>
    <plugin type="webots_ros2_control::Ros2Control"/>
  </webots>

  <ros2_control name="WebotsControl" type="system">
    <hardware>
        <plugin>webots_ros2_control::Ros2ControlSystem</plugin>
    </hardware>

    <joint name="left_wheel_joint">
        <command_interface name="velocity"> 
          </command_interface>
        <state_interface name="position"/>
    </joint>
    <joint name="right_wheel_joint">
        <state_interface name="position"/>
        <command_interface name="velocity"/>
    </joint>
  </ros2_control>

Edit: This is the full urdf (I'll be generating it from a xacro eventually but I'm using just a single exported urdf at the moment to get the basics working before I complicated things). It's based on Josh's ROS 2 tutorials on his Articulated Robotics channel.

<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- |    This document was autogenerated by xacro from robot.urdf.xacro               | -->
<!-- |    EDITING THIS FILE BY HAND IS NOT RECOMMENDED                                 | -->
<!-- =================================================================================== -->
<robot name="articubot_one">

  <!-- BASE LINK -->
  <link name="base_link" />
  <!-- BASE_FOOTPRINT LINK -->
  <joint name="base_footprint_joint" type="fixed">
    <parent link="base_link"/>
    <child link="base_footprint"/>
    <origin rpy="0 0 0" xyz="0 0 0"/>
  </joint>
  <link name="base_footprint">
    </link>
  <!-- CHASSIS LINK -->
  <joint name="chassis_joint" type="fixed">
    <parent link="base_link"/>
    <child link="chassis"/>
    <origin xyz="-0.226 0 -0.01"/>
  </joint>
  <link name="chassis">
    <visual>
      <origin xyz="0.1675 0 0.069"/>
      <geometry>
        <box size="0.335 0.265 0.138"/>
      </geometry>
      <material name="orange"/>
    </visual>
    <collision>
      <origin xyz="0.1675 0 0.069"/>
      <geometry>
        <box size="0.335 0.265 0.138"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0.1675 0 0.069"/>
      <mass value="0.5"/>
      <inertia ixx="0.003719541666666667" ixy="0.0" ixz="0.0" iyy="0.005469541666666668" iyz="0.0" izz="0.007602083333333334"/>
    </inertial>
  </link>
  <!-- LEFT WHEEL LINK -->
  <joint name="left_wheel_joint" type="continuous">
    <parent link="base_link"/>
    <child link="left_wheel"/>
    <origin rpy="-1.5707963267948966 0 0" xyz="0 0.1485 0"/>
    <axis xyz="0 0 1"/>
  </joint>
  <link name="left_wheel">
    <visual>
      <geometry>
        <cylinder length="0.026" radius="0.033"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <geometry>
        <sphere radius="0.033"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.05"/>
      <inertia ixx="1.642916666666667e-05" ixy="0.0" ixz="0.0" iyy="1.642916666666667e-05" iyz="0.0" izz="2.7225000000000004e-05"/>
    </inertial>
  </link>

  <!-- RIGHT WHEEL LINK -->
  <joint name="right_wheel_joint" type="continuous">
    <parent link="base_link"/>
    <child link="right_wheel"/>
    <origin rpy="1.5707963267948966 0 0" xyz="0 -0.1485 0"/>
    <axis xyz="0 0 -1"/>
  </joint>
  <link name="right_wheel">
    <visual>
      <geometry>
        <cylinder length="0.026" radius="0.033"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <geometry>
        <sphere radius="0.033"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.05"/>
      <inertia ixx="1.642916666666667e-05" ixy="0.0" ixz="0.0" iyy="1.642916666666667e-05" iyz="0.0" izz="2.7225000000000004e-05"/>
    </inertial>
  </link>
  
  <!-- CASTER WHEEL LINK -->
  <joint name="caster_wheel_joint" type="fixed">
    <parent link="chassis"/>
    <child link="caster_wheel"/>
    <origin xyz="0.075 0 -0.013"/>
  </joint>
  <link name="caster_wheel">
    <visual>
      <geometry>
        <sphere radius="0.01"/>
      </geometry>
      <material name="white"/>
    </visual>
    <collision>
      <geometry>
        <sphere radius="0.01"/>
      </geometry>
    </collision>
    <inertial>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <mass value="0.01"/>
      <inertia ixx="4.0000000000000003e-07" ixy="0.0" ixz="0.0" iyy="4.0000000000000003e-07" iyz="0.0" izz="4.0000000000000003e-07"/>
    </inertial>
  </link>
  
  <webots>
    <plugin type="webots_ros2_control::Ros2Control"/>
  </webots>

  <ros2_control name="WebotsControl" type="system">
    <hardware>
        <plugin>webots_ros2_control::Ros2ControlSystem</plugin>
    </hardware>

    <joint name="left_wheel_joint">
        <command_interface name="velocity"> 
          </command_interface>
        <state_interface name="position"/>
    </joint>
    <joint name="right_wheel_joint">
        <state_interface name="position"/>
        <command_interface name="velocity"/>
    </joint>
  </ros2_control>
</robot>

Any thoughts would be appreciated.

Thanks

$\endgroup$

2 Answers 2

2
$\begingroup$

You can start by checking the e-puck URDF. It can be a good source of inspiration. The problem may come from the conversion of the URDF, which is not creating any physics for the whole robot node. One possible solution is to remove the chassis link and place its visual, collision and inertial tags in the base_link instead.

The converter will automatically create a child for the visual but will use the collision and inertial tags to define the BoundingObject and Physics of the Robot.

In addition, you should change the collision tag of the wheels to a cylinder instead of a sphere. origin tags should obviously be adapted to keep the initial design when applying those modifications.

I haven't tested to adapt the whole URDF but my suggested changes above are removing the problem of gravity and "detached" wheels.

Disclaimer: I am a Webots developer working at Cyberbotics.

$\endgroup$
0
$\begingroup$

I see you have a <joint> for "left_wheel_joint" and "right_wheel_joint", but what I'm not seeing are parent or child links. I'm also not seeing the joint type. All of these (type/parent/child) are required for a valid joint definition. From the documentation, the smallest possible joint definition you could use is the one that specifies only the required fields, which would look like the following:

 <joint name="left_wheel_joint" type="revolute">
    <parent link="body"/>
    <child link="left_wheel"/>
 </joint>

When I look back at your question, I'm wondering if you've given us the full URDF, or a plugin definition, or something else? I'm not seeing definitions for the body, caster, or wheels.

$\endgroup$
4
  • $\begingroup$ Apologies, I accidentally only added the webots tags but I've added the whole .urdf file I'm trying to get working to the original post. I do have links and joints, this urdf has worked completely in Gazebo before but I'm not familiar with the differences to webots. Cheers. $\endgroup$
    – Craig MS
    Commented Mar 23, 2023 at 5:24
  • $\begingroup$ @CraigMS - Ah, I haven't used Webots so I can't comment on that. Only thing I noticed in your URDF is that it looks like you're defining the joints before the links. I don't think this should cause any problems, but have you tried swapping the order to define the joints after all the links are defined? $\endgroup$
    – Chuck
    Commented Mar 23, 2023 at 13:36
  • $\begingroup$ @CraigMS - In looking around online, it looks like there was a discussion a couple years ago where Cyberbotics was asking if they should support URDF, but the only thing I can find that's current online is a URDF converter. In looking at the converter code, order doesn't matter. How are you including the URDF file? $\endgroup$
    – Chuck
    Commented Mar 23, 2023 at 14:09
  • $\begingroup$ That URDF converter is integrated into webots_ros2 now I believe. I'm using the node that can import urdfs or even interpret xacro files. It's used by the webots_ros2_universal_robot example package here. $\endgroup$
    – Craig MS
    Commented Mar 24, 2023 at 1:02

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.

Not the answer you're looking for? Browse other questions tagged or ask your own question.