Robotics StackExchange | Archived questions

How to add laser sensor to my robot model

I have created my robot model and I'm able to successfully load it in Gazebo and make it move. Now, I would like to add a 2D laser sensor (30meters, 270°) but I'm having problems since I cannot see it in RVIZ.

When I run gmapping, for example, I continue to get:

Scan Matching Failed, using odometry. Likelihood=0
lp:-57.2393 0.222367 0.775704

and I can't see the laser beam in RVIZ when I select the laser frame as static frame.

How can I correctly add a laser sensor to my model?

This is my code for the robot model paviolier.urdf.xacro in my catkin workspace catkinws/src/paviolinerdescription/robot/:

    <?xml version="1.0"?>

<robot name="pavioliner_xl" xmlns:xacro="http://www.ros.org/wiki/xacro">

    <!-- Import pavioliner XL wheels -->
    <xacro:include filename="$(find pavioliner_description)/urdf/wheels/omni_wheel.urdf.xacro" />
    <xacro:include filename="$(find pavioliner_description)/urdf/base/pavioliner_base.urdf.xacro" />

     <!-- Laser  -->
         <xacro:include filename="$(find pavioliner_description)/plugins/laser/hokuyo.xacro"/>
         <xacro:laser name="pavioliner/laser" parent="pavioliner_base_link" xyz="0.13 0 0.36" rpy="0 0 0" meshes="package://gazebo_plugins/test/multi_robot_scenario/meshes/laser"/>


    <!-- Wheel parameters -->
    <xacro:property name="front_wheel_offset_x" value="0.37" />    <!-- x,y,z in translation from base_link to the center of the wheel -->
    <xacro:property name="front_wheel_offset_y" value="0.46" />
    <xacro:property name="wheel_offset_z" value="0.0" />
    <xacro:property name="back_wheel_offset_y" value="0.46" />
    <xacro:property name="back_wheel_offset_x" value="0.45" />

    <xacro:macro name="robot">
        <xacro:pavioliner_base/>

        <xacro:omni_wheel prefix="pavioliner_front_right" parent="pavioliner_base_link" reflect="false">
            <origin xyz="${front_wheel_offset_x} -${front_wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_wheel prefix="pavioliner_front_left" parent="pavioliner_base_link" reflect="true">
            <origin xyz="${front_wheel_offset_x} ${front_wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_wheel prefix="pavioliner_back_left" parent="pavioliner_base_link" reflect="true">
            <origin xyz="-${back_wheel_offset_x} ${back_wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_wheel prefix="pavioliner_back_right" parent="pavioliner_base_link" reflect="false">
            <origin xyz="-${back_wheel_offset_x} -${back_wheel_offset_y} ${wheel_offset_z}" rpy="0 0 0"/>
        </xacro:omni_wheel>

        <xacro:omni_steering/>

   </xacro:macro>

   <xacro:robot/>

</robot>

and this is the hokuyo.xacro file in catkinws/src/paviolinerdescription/plugins/:

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- Front Laser -->
<xacro:macro name="laser" params="name parent xyz rpy meshes" >

  <joint name="${parent}_${name}_joint" type="fixed">
      <axis xyz="0 0 1" />
      <origin xyz="${xyz}" rpy="${rpy}"/>
      <parent link="${parent}"/>
      <child link="${name}"/>
    </joint>

    <link name="${name}">
      <collision>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
          <box size="0.1 0.1 0.1"/>
        </geometry>
      </collision>
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <geometry>
          <mesh filename="${meshes}/hokuyo.dae"/>
        </geometry>
      </visual>
      <inertial>
        <mass value="1e-5" />
        <origin xyz="0 0 0" rpy="0 0 0"/>
        <inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
      </inertial>
    </link>

    <gazebo reference="${name}">
        <sensor name="laser" type="ray">
        <pose>0 0 0 0 0 0</pose>
          <ray>
            <scan>
              <horizontal>
                <!-- The URG-04LX-UG01  has  683 steps with 0.35139 Degree resolution -->
                <resolution>1</resolution>
                <max_angle>2.0944</max_angle> <!-- 120 Degree -->
                <min_angle>-2.0944</min_angle> <!-- -120 Degree -->
                <samples>683</samples>
              </horizontal>
            </scan>
            <range>
              <min>1</min>
              <max>80</max>
              <resolution>0.01</resolution>
            </range>
          </ray>

          <plugin name="laser" filename="libgazebo_ros_laser.so" >
            <robotNamespace></robotNamespace>
            <topicName>laser/scan</topicName>
            <frameName>laser</frameName>
          </plugin>
          <!--
          <plugin name="laser" filename="libRayPlugin.so" />
          -->

          <always_on>1</always_on>
          <update_rate>30</update_rate>
          <visualize>true</visualize>
        </sensor>
    </gazebo>
</xacro:macro>

</robot>

Asked by marcusbarnet on 2020-01-26 12:27:29 UTC

Comments

Answers