ros gazebo添加GPS传感器

1.下载插件

sudo apt-get install ros-noetic-hector-gazebo*
  1. 在你的urdf模型文件中添加gps的描述
  <link name="gps_link">
    <inertial>
      <mass value="0.1"/>
      <origin xyz="0 0 0" />
      <inertia ixx="0.01" iyy="0.01" izz="0.01" ixy="0.01" ixz="0.01" iyz="0.01"/>
    </inertial>
    <visual>
      <geometry>
        <sphere radius="0.01"/>
      </geometry>
      <material name="blue"/>
    </visual>
    <collision>
      <geometry>
        <sphere radius="0.1"/>
      </geometry>
    </collision>
    <sensor name="gps_sensor" type="gps">
      <update_rate>1.0</update_rate>
      <vertical_fov>90.0</vertical_fov>
      <horizontal_fov>90.0</horizontal_fov>
      <visualize>true</visualize>
      <gps>
        <position>0 0 0</position>
      </gps>
    </sensor>
  </link>
  <joint name="base_to_gps" type="fixed">
  <parent link="base_footprint" />
  <child link="gps_link" />
  <origin xyz="0.0 0.0 0.1" rpy="0 0 0" />  <!-- 适当设置位置 -->
</joint>

3.添加gazebo插件

  <gazebo>
    <plugin name="gps_controller" filename="libhector_gazebo_ros_gps.so">
      <updateRate>40</updateRate>
      <bodyName>base_link</bodyName>
      <frameId>base_link</frameId>
      <topicName>navsat/fix</topicName>
      <velocityTopicName>navsat/vel</velocityTopicName>
      <referenceLatitude>$(optenv GAZEBO_WORLD_LAT 49.9)</referenceLatitude>
      <referenceLongitude>$(optenv GAZEBO_WORLD_LON 8.9)</referenceLongitude>
      <referenceHeading>90</referenceHeading>
      <referenceAltitude>0</referenceAltitude>
      <drift>0.0000001 0.000001 0.000001</drift>
    </plugin>
  </gazebo>
  

之后运行你的模型程序,通过 rostopic list 可以看到gps话题

在这里插入图片描述
在这里插入图片描述

  • 3
    点赞
  • 1
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值