【原创】gazebo中激光雷达不能够显示激光线且话题中ranges显示为inf的问题解决方法之一

gazebo插件使用libgazebo_ros_ray_sensor.so时,激光雷达在gazebo中不能够显示激光线且话题中ranges显示为inf的问题解决

现象

我的环境的gazebo插件使用libgazebo_ros_ray_sensor.so时(在xx.gazebo.xacro配置中查看,要找到gazebo的激光雷达插件配置的地方):

  1. 激光雷达在gazebo中不能够显示激光线
  2. laser的node所发布的topic中ranges属性中显示inf
  3. 在某些电脑上一切正常,在某些电脑会同时出现上面1和2的现象

解决方法

如下为解决方法之一:

在不能够正常显示的电脑上,要找到配置gazebo的激光雷达插件的文件xx.gazebo.xacro,在其中关于激光雷达的配置,要将出现gpu_ray的地方改为使用cpu的ray方案。

例如:

      <!-- sensor type="gpu_ray" name="${name}" -->
      <sensor type="ray" name="${name}">

示例

在我的电脑的项目中路径为

  • 文件一:/opt/ros/humble/share/pal_urdf_utils/urdf/laser/range.gazebo.xacro
  • 文件二:/opt/ros/humble/share/pal_urdf_utils/urdf/laser/sick_tim571_laser.gazebo.xacro

根据项目不同urdf文件的位置会不同,因项目而异。

文件一range.gazebo.xacro注释并修改后的具体内容示例

<?xml version="1.0"?>

<!-- 
  Copyright (c) 2025 PAL Robotics S.L. All rights reserved.

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

      http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
 -->

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

  <xacro:macro name="range_gazebo" params="name ros_topic update_rate maxRange minRange fov radiation">
    <gazebo reference="${name}_link">
      <!-- sensor type="gpu_ray" name="${name}" -->
      <sensor type="ray" name="${name}">
        <pose>0 0 0 0 0 0</pose>
        <update_rate>${update_rate}</update_rate>
        <visualize>false</visualize>
        <ray>
          <scan>
            <horizontal>
              <samples>5</samples>
              <resolution>1</resolution>
              <min_angle>-${fov/2}</min_angle>
              <max_angle>${fov/2}</max_angle>
            </horizontal>
            <vertical>
              <samples>5</samples>
              <resolution>1</resolution>
              <min_angle>-${fov/2}</min_angle>
              <max_angle>${fov/2}</max_angle>
            </vertical>
          </scan>
          <range>
            <min>${minRange}</min>
            <max>${maxRange}</max>
            <resolution>0.01</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.005</stddev>
          </noise>
        </ray>
        <plugin name="${name}_gazebo_ros_range" filename="libgazebo_ros_ray_sensor.so">
          <ros>
            <namespace>${namespace}</namespace>
            <remapping>~/out:=${ros_topic}</remapping>
          </ros>
          <output_type>sensor_msgs/Range</output_type>
          <radiation_type>${radiation}</radiation_type>
          <frame_name>${name}_link</frame_name>
        </plugin>
      </sensor>
      <material>Gazebo/DarkGrey</material>
    </gazebo>
  </xacro:macro>

</robot>

文件二sick_tim571_laser.gazebo.xacro注释并修改后的具体内容示例

<?xml version="1.0"?>
<!-- 
  Copyright (c) 2025 PAL Robotics S.L. All rights reserved.

  Licensed under the Apache License, Version 2.0 (the "License");
  you may not use this file except in compliance with the License.
  You may obtain a copy of the License at

      http://www.apache.org/licenses/LICENSE-2.0

  Unless required by applicable law or agreed to in writing, software
  distributed under the License is distributed on an "AS IS" BASIS,
  WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  See the License for the specific language governing permissions and
  limitations under the License.
 -->
<robot xmlns:xacro="http://ros.org/wiki/xacro">

  <xacro:macro name="sick_tim571_laser_gazebo" params="name ros_topic update_rate min_angle max_angle">
    <gazebo reference="${name}_link">
      <!-- sensor type="gpu_ray" name="${name}" -->
      <sensor type="ray" name="${name}">
        <pose>0 0 0 0 0 0</pose>
        <update_rate>${update_rate}</update_rate>
        <visualize>true</visualize>
        <ray>
          <scan>
            <horizontal>
              <!-- 818 (270/0.33) steps in 270deg fov -->
              <samples>${818*(max_angle - min_angle)/(270.0 * deg_to_rad)}</samples>
              <resolution>1</resolution>              <!-- not the sensor resolution; just 1 -->
              <min_angle>${min_angle}</min_angle>
              <max_angle>${max_angle}</max_angle>
            </horizontal>
          </scan>
          <range>
            <min>0.05</min>
            <max>25.0</max>
            <resolution>0.001</resolution>
          </range>
          <noise>
            <type>gaussian</type>
            <mean>0.0</mean>
            <stddev>0.01</stddev>
          </noise>
        </ray>
        <plugin name="${name}" filename="libgazebo_ros_ray_sensor.so">
          <ros>
            <namespace>${namespace}</namespace>
            <remapping>~/out:=${ros_topic}</remapping>
          </ros>
          <output_type>sensor_msgs/LaserScan</output_type>
          <frame_name>${name}_link</frame_name>
        </plugin>
      </sensor>
      <material>Gazebo/DarkGrey</material>
    </gazebo>
  </xacro:macro>

</robot>
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值