ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Range sensor in Gazebo always reports the minimum range

asked 2021-02-28 15:37:19 -0500

Jim Greene gravatar image

I will apologize in advance for any faux pas with respect to posting questions here. This is my first time posting a question on this forum. I'm a relatively new ROS user, and am really struggling to get something working that should be pretty simple.

I am attempting to use a set of range sensors, arranged around the lower portion of my robot frame, to be used for collision avoidance. Unfortunately, I cannot get the sensors to read anything in Gazebo other than roughly the minimum distance allowed for the sensor. I'm guessing that the range plugin is experiencing a collision with the body representing the sensor. I've tried removing the collision tag from the links representing the sensors. I've even tried arranging the sensor links a short distance away from the actual robot body, to rule out that there weren't any collisions occurring with the links the sensors are being attached to. Unfortunately, I get the same result no matter what.

Link sensor_fl_range_1 represents the range sensor. When I echo the topic for this sensor, /proximity/frontleft, it returns only the following result:

header: 
    seq: 11  
    stamp: 
        secs: 95 
        nsecs: 148000000 
    frame_id: "sensor_fl_range_1" 
radiation_type: 1 
field_of_view: 0.20000000298023224 
min_range: 0.05000000074505806 
max_range: 2.0 
range: 0.05668118596076965

My environment is using ROS Noetic. I'm currently doing my development online at theconstructsim.com. Here's what I get back regarding the OS:

user:~$ cat /etc/os-release
NAME="Ubuntu"
VERSION="20.04.1 LTS (Focal Fossa)"
ID=ubuntu
ID_LIKE=debian
PRETTY_NAME="Ubuntu 20.04.1 LTS"
VERSION_ID="20.04"
HOME_URL="https://www.ubuntu.com/"
SUPPORT_URL="https://help.ubuntu.com/"
BUG_REPORT_URL="https://bugs.launchpad.net/ubuntu/"
PRIVACY_POLICY_URL="https://www.ubuntu.com/legal/terms-and-policies/privacy-policy"
VERSION_CODENAME=focal
UBUNTU_CODENAME=focal

Would anyone happen to have some time to take a look at this URDF, and let me know what I'm doing wrong. I've been beating my skull against my desk for two days now, to no avail. I'll apologize in advance for the length of the URDF. I haven't gotten to a point where I am ready to factor the model out using xacro's yet.

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" 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> ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2021-03-01 19:21:08 -0500

Jim Greene gravatar image

I actually found the issue. I had copied/pasted the definition for the ray sensor, and had not paid attention to the fact that the min_angle/max_angle vlaues for the scan element were in degrees, and not radians. After changing these values, and providing a proper pose to identify where the beam originates its link, and everything started working perfectly.

Here's what my sensor definition looks like now:

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

I also wouldn't recommend using this robot definition as good example, due to the fact that I used joints for the creation of my caster wheels. I discovered, after a good bit of reading last night, that this is in fact a really bad idea.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2021-02-28 15:37:19 -0500

Seen: 598 times

Last updated: Mar 01 '21