Adding an Infrared Range Sensor - Always reads the minimum range

I’ll apologize in advance for the large URDF file.

I am attempting to add a group of laser range finders around the lower perimeter of my robot design. The sensor I am using has a maximum range of two meters, and I am trying to simulate this sensor in Gazebo. Unfortunately, the sensor seems to only register the minimum range of the sensor, and does not detect anything outside of this value.

I’m guessing that the laser is colliding with the link I’ve defined for sensor, or with the robot. But I honestly can’t tell which it is. I’ve tried commenting out the tag for both the sensor link, as well as the part of the body onto which the sensor is attached, but I’m not having very much luck. Could someone give this URDF a look, and tell me what I’m doing wrong?

The sensor link in question is named sensor_fl_range_1.

<?xml version="1.0"?>
<robot name="echo_bot">
    <material name="black">
        <color rgba="0 0 0 1"/>
    </material>
    <material name="grey">
        <color rgba=".2 .2 .2 1"/>
    </material>
    <material name="red">
        <color rgba="0.8 0.0 0.0 1.0"/>
    </material>
    <material name="orange">
        <color rgba="1 0.42 0.0392 1.0"/>
    </material>
    <material name="silver">
        <color rgba="0.403 0.501 0.623 1.0"/>
    </material>

    <!-- base_link - box - 8.5in 18in 10in -->
    <link name="base_link">        
        <visual>
            <geometry>
                <box size="0.2159 0.4572 0.254"/>
            </geometry>            
            <material name="grey"/>
        </visual> 
        <collision>
            <geometry>
                <box size="0.2159 0.4572 0.254"/>
            </geometry>
        </collision>
    </link>

    <!-- bottom_frame_link - box - 30.75in 10in 3in -->
    <link name="bottom_frame_link">
        <visual>
            <geometry>
                <box size="0.78105 0.2921 0.0762"/>                
            </geometry>            
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>      
        <collision>
            <geometry>
                <box size="0.78105 0.2921 0.0762"/>                
            </geometry>            
        </collision>
        <inertial>
            <mass value="4.53592"/>
            <inertia ixx="0.232785509428" ixy="0.0" ixz="0.0"
                    iyy="0.0344460977743" iyz="0.0"
                    izz="0.262842015982"/>
        </inertial>       
    </link>

    <!-- sensor_fl_range_1 - front corner of robot -->
    <link name="sensor_fl_range_1">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <!--
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>
        -->
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>        
    </link>

    <joint name="sensor_fl_range_1_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="sensor_fl_range_1"/>
        <origin xyz=".3937 -0.13245837 0" rpy="0 0 0"/>
    </joint>    

    <gazebo reference="sensor_fl_range_1">
        <material>Gazebo/Red</material>
        <sensor type="ray" name="sensor_fl_range_1">
            <pose>0 0 0 0 0 0</pose>
            <visualize>true</visualize>
            <update_rate>10</update_rate>
            <ray>
                <scan>
                    <horizontal>
                        <samples>10</samples>
                        <resolution>1</resolution>
                        <min_angle>-10.0</min_angle>
                        <max_angle>10.0</max_angle>
                    </horizontal>
                    <vertical>
                        <samples>10</samples>
                        <resolution>1</resolution>
                        <min_angle>-10.0</min_angle>
                        <max_angle>10.0</max_angle>
                    </vertical>
                </scan>
                <range>
                    <min>0.05</min>
                    <max>2.0</max>
                    <resolution>0.05</resolution>
                </range>
            </ray>
            <plugin name="gazebo_ros_range" filename="libgazebo_ros_range.so">
                <topicName>proximity/frontleft</topicName>
                <frameName>sensor_fl_range_1</frameName>
                <gaussianNoise>0.000</gaussianNoise>
                <updateRate>10</updateRate>
                <radiation>infrared</radiation>
                <fov>0.20</fov>
                <visualize>true</visualize>
            </plugin>
        </sensor>
    </gazebo>    

    <!-- sensor_fr_range_1 - front corner of robot -->
    <link name="sensor_fr_range_1">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>    
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>            
    </link>

    <joint name="sensor_fr_range_1_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="sensor_fr_range_1"/>
        <origin xyz=".3937 0.13245837 0" rpy="0 0 0"/>
    </joint>        

    <joint name="frame_joint" type="fixed">
        <parent link="base_link"/>
        <child link="bottom_frame_link"/>
        <origin xyz="0 0 -0.0889"/>
    </joint>

    <!-- front caster -->
    <link name="front_caster_post">
        <visual>
            <geometry>
                <box size="0.0254 0.0254 0.0762"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.0254 0.0254 0.0762"/>
            </geometry>        
        </collision>
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.000243866178933" ixy="0.0" ixz="0.0"
                    iyy="0.000243866178933" iyz="0.0"
                    izz="4.87732357867e-05"/>
        </inertial>        
    </link>

    <link name="front_caster_wheel">
        <visual>
            <geometry>
                <sphere radius="0.0508"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <sphere radius="0.0508"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="2.9029888" ixy="0.0" ixz="0.0"
                    iyy="2.9029888" iyz="0.0"
                    izz="2.9029888"/>
        </inertial>       
    </link>

    <gazebo reference="front_caster_wheel">
        <turnGravityOff>false</turnGravityOff>
    </gazebo>    

    <joint name="front_caster_wheel_joint" type="fixed">
        <parent link="front_caster_post"/>
        <child link="front_caster_wheel"/>
        <origin xyz="0 0 -0.0381" rpy="0 0 0"/>
    </joint>

    <joint name="front_caster_post_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="front_caster_post"/>
        <origin xyz="0.339725 0 -0.0762"/>
    </joint>

    <!-- rear caster -->
    <link name="rear_caster_post">
        <visual>
            <geometry>
                <box size="0.0254 0.0254 0.0762"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.0254 0.0254 0.0762"/>
            </geometry>        
        </collision>
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.000243866178933" ixy="0.0" ixz="0.0"
                    iyy="0.000243866178933" iyz="0.0"
                    izz="4.87732357867e-05"/>
        </inertial>        
    </link>

    <link name="rear_caster_wheel">
        <visual>
            <geometry>
                <sphere radius="0.0508"/>
            </geometry>
            <material name="black"/>
        </visual>
        <collision>
            <geometry>
                <sphere radius="0.0508"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="2.9029888" ixy="0.0" ixz="0.0"
                    iyy="2.9029888" iyz="0.0"
                    izz="2.9029888"/>
        </inertial>
    </link>

    <gazebo reference="rear_caster_wheel">
        <turnGravityOff>false</turnGravityOff>
    </gazebo>

    <joint name="rear_caster_wheel_joint" type="fixed">
        <parent link="rear_caster_post"/>
        <child link="rear_caster_wheel"/>
        <origin xyz="0 0 -0.0381" rpy="0 0 0"/>
    </joint>

    <joint name="rear_caster_post_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="rear_caster_post"/>
        <origin xyz="-0.339725 0 -0.0762"/>
    </joint>    

    <!-- front_fenders_rear_box -->
    <link name="front_fenders_rear_box">
        <visual>
            <geometry>
                <box size="0.01905 0.4572 0.0762"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.01905 0.4572 0.0762"/>
            </geometry>
        </collision>   
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.000233197033605" ixy="0.0" ixz="0.0"
                    iyy="0.00812074375848" iyz="0.0"
                    izz="0.00791498167"/>
        </inertial>             
    </link>

    <joint name="front_fender_rear_box_joint" type="fixed">
        <parent link="base_link"/>
        <child link="front_fenders_rear_box"/>
        <origin xyz="0.117475 0 -0.0889"/>
    </joint>

    <!-- rear_fenders_rear_box -->
    <link name="rear_fenders_rear_box">
        <visual>
            <geometry>
                <box size="0.01905 0.4572 0.0762"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.01905 0.4572 0.0762"/>
            </geometry>
        </collision>       
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.000233197033605" ixy="0.0" ixz="0.0"
                    iyy="0.00812074375848" iyz="0.0"
                    izz="0.00791498167"/>
        </inertial>         
    </link>

    <joint name="rear_fender_rear_box_joint" type="fixed">
        <parent link="base_link"/>
        <child link="rear_fenders_rear_box"/>
        <origin xyz="-0.117475 0 -0.0889"/>
    </joint>

    <!-- front_left_fender  10.753in 4in 3in-->

    <link name="front_left_fender">
        <visual>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
        </collision>
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.00303923124767" ixy="0.0" ixz="0.0"
                    iyy="0.000609665447333" iyz="0.0"
                    izz="0.00320993757293"/>
        </inertial>                
    </link>

    <!-- sensor_fl_range_2 -->
    <link name="sensor_fl_range_2">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>   
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>             
    </link>

    <joint name="sensor_fl_range_2_joint" type="fixed">
        <parent link="front_left_fender"/>
        <child link="sensor_fl_range_2"/>
        <origin xyz="0.07805 -0.05715 0" rpy="0 0 -1.5708"/>
    </joint>

    <!-- sensor_fl_range_3 -->
    <link name="sensor_fl_range_3">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>     
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>           
    </link>

    <joint name="sensor_fl_range_3_joint" type="fixed">
        <parent link="front_left_fender"/>
        <child link="sensor_fl_range_3"/>
        <origin xyz="0.0336 -0.05715 0" rpy="0 0 -1.5708"/>
    </joint>        

    <!-- sensor_fl_range_4 -->
    <link name="sensor_fl_range_4">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>     
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>           
    </link>

    <joint name="sensor_fl_range_4_joint" type="fixed">
        <parent link="front_left_fender"/>
        <child link="sensor_fl_range_4"/>
        <origin xyz="-0.01085 -0.05715 0" rpy="0 0 -1.5708"/>
    </joint>

    <!-- sensor_fl_range_5 -->
    <link name="sensor_fl_range_5">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>       
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>         
    </link>

    <joint name="sensor_fl_range_5_joint" type="fixed">
        <parent link="front_left_fender"/>
        <child link="sensor_fl_range_5"/>
        <origin xyz="-0.0553 -0.05715 0" rpy="0 0 -1.5708"/>
    </joint> 

    <!-- sensor_fl_range_6 -->
    <link name="sensor_fl_range_6">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry> 
        </collision>       
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>         
    </link>

    <joint name="sensor_fl_range_6_joint" type="fixed">
        <parent link="front_left_fender"/>
        <child link="sensor_fl_range_6"/>
        <origin xyz="-0.09975 -0.05715 0" rpy="0 0 -1.5708"/>
    </joint>                    

    <joint name="front_left_fender_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="front_left_fender"/>
        <origin xyz="0.245 -0.140 0" rpy="0 0 0.310"/>
    </joint>
    

    <!-- front_right_fender - 10.753in 4in 3in -->
    <link name="front_right_fender">
        <visual>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
        </collision>   
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.00303923124767" ixy="0.0" ixz="0.0"
                    iyy="0.000609665447333" iyz="0.0"
                    izz="0.00320993757293"/>
        </inertial>             
    </link>

    <!-- sensor_fr_range_2 -->
    <link name="sensor_fr_range_2">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>     
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>           
    </link>

    <joint name="sensor_fr_range_2_joint" type="fixed">
        <parent link="front_right_fender"/>
        <child link="sensor_fr_range_2"/>
        <origin xyz="0.07805 0.05715 0" rpy="0 0 1.5708"/>
    </joint>

    <!-- sensor_fr_range_3 -->
    <link name="sensor_fr_range_3">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>     
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>           
    </link>

    <joint name="sensor_fr_range_3_joint" type="fixed">
        <parent link="front_right_fender"/>
        <child link="sensor_fr_range_3"/>
        <origin xyz="0.0336 0.05715 0" rpy="0 0 1.5708"/>
    </joint>        

    <!-- sensor_fr_range_4 -->
    <link name="sensor_fr_range_4">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>    
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>            
    </link>

    <joint name="sensor_fr_range_4_joint" type="fixed">
        <parent link="front_right_fender"/>
        <child link="sensor_fr_range_4"/>
        <origin xyz="-0.01085 0.05715 0" rpy="0 0 1.5708"/>
    </joint>

    <!-- sensor_fr_range_5 -->
    <link name="sensor_fr_range_5">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>   
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>             
    </link>

    <joint name="sensor_fr_range_5_joint" type="fixed">
        <parent link="front_right_fender"/>
        <child link="sensor_fr_range_5"/>
        <origin xyz="-0.0553 0.05715 0" rpy="0 0 1.5708"/>
    </joint> 

    <!-- sensor_fr_range_6 -->
    <link name="sensor_fr_range_6">
        <visual>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="red"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.00635 0.009525 0.009525"/>
            </geometry>
        </collision>        
        <inertial>
            <mass value="0.00453592"/>
            <inertia ixx="4.95353175958e-08" ixy="0.0" ixz="0.0"
                    iyy="6.8587362825e-08" iyz="0.0"
                    izz="4.95353175958e-08"/>
        </inertial>        
    </link>

    <joint name="sensor_fr_range_6_joint" type="fixed">
        <parent link="front_right_fender"/>
        <child link="sensor_fr_range_6"/>
        <origin xyz="-0.09975 0.05715 0" rpy="0 0 1.5708"/>
    </joint>                  

    <joint name="front_right_fender_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="front_right_fender"/>
        <origin xyz="0.245 0.140 0" rpy="0 0 -0.310"/>
    </joint>

    <!-- rear_left_fender  10.753in 4in 3in-->
    <link name="rear_left_fender">
        <visual>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
        </collision>   
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.00303923124767" ixy="0.0" ixz="0.0"
                    iyy="0.000609665447333" iyz="0.0"
                    izz="0.00320993757293"/>
        </inertial>             
    </link>

    <joint name="rear_left_fender_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="rear_left_fender"/>
        <origin xyz="-0.245 -0.140 0" rpy="0 0 -0.310"/>
    </joint>  

    <!-- rear_right_fender - 10.753in 4in 3in -->
    <link name="rear_right_fender">
        <visual>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
            <origin rpy="0 0 0" xyz="0 0 0"/>
            <material name="grey"/>
        </visual>
        <collision>
            <geometry>
                <box size="0.2731262 0.1016 0.0762"/>
            </geometry>
        </collision>   
        <inertial>
            <mass value="0.453592"/>
            <inertia ixx="0.00303923124767" ixy="0.0" ixz="0.0"
                    iyy="0.000609665447333" iyz="0.0"
                    izz="0.00320993757293"/>
        </inertial>             
    </link>

    <joint name="rear_right_fender_joint" type="fixed">
        <parent link="bottom_frame_link"/>
        <child link="rear_right_fender"/>
        <origin xyz="-0.245 0.140 0" rpy="0 0 0.310"/>
    </joint>      

    <!-- left_wheel - cylinder - 10in diameter / 5in radius, 3.5in length -->
    <link name="left_wheel">        
        <visual>
            <origin rpy="1.5708 0 0" xyz="0 0 0"/>  
            <geometry>
                <cylinder length="0.0889" radius="0.127"/>
            </geometry>                        
            <material name="black"/>
        </visual>  
        <collision>
            <origin rpy="1.5708 0 0" xyz="0 0 0"/>  
            <geometry>
                <cylinder length="0.0889" radius="0.127"/>
            </geometry>
        </collision>  
        <inertial>
            <mass value="6.80389"/>
            <inertia ixx="0.0319160330764" ixy="0.0" ixz="0.0"
                    iyy="0.0319160330764" iyz="0.0"
                    izz="0.054869970905"/>
        </inertial>                          
    </link>

    <joint name="left_wheel_joint" type="revolute">
        <parent link="base_link"/>
        <child link="left_wheel"/>
        <origin xyz="0 -0.27305 -0.127" rpy="0 0 0"/>
        <limit lower="-100.0" upper="100.0" effort="0.1" velocity="0.005"/>
        <axis xyz="0 1 0"/>
    </joint>

    <!-- right_wheel - cylinder - 10in diameter / 5in radius, 3.5in length -->
    <link name="right_wheel">        
        <visual>
            <origin rpy="1.5708 0 0" xyz="0 0 0"/>  
            <geometry>
                <cylinder length="0.0889" radius="0.127"/>
            </geometry>                        
            <material name="black"/>
        </visual>    
        <collision>
            <origin rpy="1.5708 0 0" xyz="0 0 0"/>  
            <geometry>
                <cylinder length="0.0889" radius="0.127"/>
            </geometry>
        </collision>      
        <inertial>
            <mass value="6.80389"/>
            <inertia ixx="0.0319160330764" ixy="0.0" ixz="0.0"
                    iyy="0.0319160330764" iyz="0.0"
                    izz="0.054869970905"/>
        </inertial>                    
    </link>

    <joint name="right_wheel_joint" type="revolute">
        <parent link="base_link"/>
        <child link="right_wheel"/>
        <origin xyz="0 0.27305 -0.127" rpy="0 0 0"/>
        <limit lower="-100.0" upper="100.0" effort="0.1" velocity="0.005"/>
        <axis xyz="0 1 0"/>
    </joint>
</robot>
1 Like

I found the issue. I had copied/pasted the definition of the sensor, and the example I had drawn from used degrees for the min_angle/max_angle elements for the scan tag. Once I changed those, and set a pose equal to the front of the link representing my sensor, everything worked like a champ.

2 Likes