Drive wheels not attached to model in Gazebo when radius is small.

asked 2019-11-01 12:25:40 -0500

FailFTW gravatar image

Hello, i am trying to run a simulation for a custom holonomic drivetrain. This is on 16.04 Kinetic. I have a URDF file that is having problems whenever the drive wheels get below a certain threshold. The full project is at https://github.com/JakeAllison/FRC-ROS on the swerve_sim branch. Specifically, this is the frc_ros package. Running just sim.launch will bring up the simulation. The question is, how can changing the wheel radius cause the gazebo model not to work, and any idea why it isn't is working in this case? I'd be happy to provide more information.

Here's a snippet of the main file:

<robot name="myfirst" xmlns:xacro="http://ros.org/wiki/xacro">
    <xacro:include filename="$(find frc_robot)/urdf/drivetrain.urdf.xacro" />

    ...

    <xacro:swerve_drive name="swerve_drive" parent="base_link" z_offset="0.0" wheelbase_width="0.6096" wheelbase_length="0.6096" wheel_radius="0.1" wheel_width="0.0381" wheel_mass="1" />

    ...


    <!--                          For Gazebo Simulation                          -->

    <gazebo>
      <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
        <robotNamespace>/drivetrain</robotNamespace>
        <legacyModeNS>true</legacyModeNS>
        </plugin>
    </gazebo>
</robot>

When wheel radius is 0.1, the Gazebo model is fine. When it's 0.075 for example, the wheel will not be attached to the chassis, and just be on the floor at 0, 0, 0. Here's the relevant parts of the drivetrain URDF:

<xacro:macro name="swerve_drive" params="name parent z_offset wheelbase_width wheelbase_length wheel_radius wheel_width wheel_mass">

<root xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:include filename="$(find frc_robot)/urdf/inertia.urdf.xacro" />

  <xacro:property name="front" value="1" />
  <xacro:property name="middle" value="0" />
  <xacro:property name="rear" value="-1" />
  <xacro:property name="left" value="1" />
  <xacro:property name="right" value="-1" />
  <xacro:property name="no_drop" value="0" />
  <xacro:property name="drop" value="-1" />
  <xacro:property name="high_friction" value="200.0" />
  <xacro:property name="medium_friction" value="100.0" />
  <xacro:property name="low_friction" value="1.0" />
  <xacro:property name="pivot_radius" value="0.025" />
  <xacro:property name="pivot_height" value="0.025" />
  <xacro:property name="pivot_mass" value="1.0" />


...


<!--                          Swerve Pivot                           -->
  <xacro:macro name="swerve_pivot" params="parent2 prefix side fntbck friction">

    <!--                          Swerve Wheel                           -->
      <xacro:macro name="swerve_wheel" params="parent3 prefix2 friction2">
        <link name="${prefix2}_swerve_wheel">
          <visual>
            <geometry>
              <cylinder length="${wheel_width}" radius="${wheel_radius}"/>
            </geometry>
            <origin xyz="0 0 0"/>
            <material name="blue"/>
          </visual>
          <collision>
            <geometry>
              <cylinder length="${wheel_width}" radius="${wheel_radius}"/>
            </geometry>
            <origin xyz="0 0 0"/>
          </collision>
          <inertial>
            <mass value="${wheel_mass}"/>
            <xacro:cylinder_inertia
            m="${wheel_mass}"
            r="${wheel_radius}"
            h="${wheel_width}" />
            <origin xyz="0 0 0"/>
          </inertial>
        </link>
        <joint name="${parent3}_to_${prefix2}_swerve_wheel" type="continuous">
          <parent link="${parent3}"/>
          <child link="${prefix2}_swerve_wheel"/>
          <axis xyz="0 0 1"/>
          <origin rpy="${-pi/2} 0 0" xyz="0 0 0"/>
        </joint>

        <transmission name="${prefix2}_swerve_wheel_trans">
          <type>transmission_interface/SimpleTransmission</type>
          <actuator name="${prefix2 ...
(more)
edit retag flag offensive close merge delete