2025年8月26日 星期二

雷射(LiDAR) ,IMU for Gazebo URDF

 依照你前面在 Gazebo log 裡看到的兩個問題:

  1. Laser(ray sensor)缺 <output_type> → Gazebo 預設成 PointCloud2,RViz2 看起來不直覺。

  2. IMU sensor 缺 noise 配置 → 導致 Get noise index not valid

我幫你把這兩個部分補齊,直接整合進 xacro 版本。


修正版片段

雷射(LiDAR)

<gazebo reference="lidar_link"> <sensor name="lidar" type="ray"> <pose>0 0 0 0 0 0</pose> <visualize>true</visualize> <update_rate>30</update_rate> <ray> <scan> <horizontal> <samples>720</samples> <resolution>1</resolution> <min_angle>-1.5708</min_angle> <max_angle>1.5708</max_angle> </horizontal> </scan> <range> <min>0.12</min> <max>3.5</max> <resolution>0.01</resolution> </range> </ray> <!-- ROS 2 插件 --> <plugin name="gazebo_ros_laser" filename="libgazebo_ros_ray_sensor.so"> <ros> <namespace>/twowheel_amr</namespace> <remapping>~/out:=scan</remapping> </ros> <output_type>sensor_msgs/LaserScan</output_type> <!-- 新增 --> <frame_name>lidar_link</frame_name> </plugin> </sensor> </gazebo>

IMU

<gazebo reference="imu_link"> <sensor name="imu_sensor" type="imu"> <update_rate>200</update_rate> <always_on>true</always_on> <visualize>false</visualize> <imu> <angular_velocity> <x> <noise type="gaussian"> <mean>0.0</mean> <stddev>0.0002</stddev> <bias_mean>0.0</bias_mean> <bias_stddev>0.00001</bias_stddev> </noise> </x> <y><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev><bias_mean>0</bias_mean><bias_stddev>0.00001</bias_stddev></noise></y> <z><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev><bias_mean>0</bias_mean><bias_stddev>0.00001</bias_stddev></noise></z> </angular_velocity> <linear_acceleration> <x><noise type="gaussian"><mean>0</mean><stddev>0.02</stddev><bias_mean>0</bias_mean><bias_stddev>0.001</bias_stddev></noise></x> <y><noise type="gaussian"><mean>0</mean><stddev>0.02</stddev><bias_mean>0</bias_mean><bias_stddev>0.001</bias_stddev></noise></y> <z><noise type="gaussian"><mean>0</mean><stddev>0.02</stddev><bias_mean>0</bias_mean><bias_stddev>0.001</bias_stddev></noise></z> </linear_acceleration> </imu> <!-- ROS 2 插件 --> <plugin name="gazebo_ros_imu" filename="libgazebo_ros_imu_sensor.so"> <ros> <namespace>/twowheel_amr</namespace> <remapping>~/out:=imu/data</remapping> </ros> <initial_orientation_as_reference>false</initial_orientation_as_reference> <frame_name>imu_link</frame_name> </plugin> </sensor> </gazebo>

測試方法

  1. 重新轉換:

xacro twowheel.urdf.xacro -o /tmp/twowheel.urdf
  1. 再 spawn 進 Gazebo:

ros2 run gazebo_ros spawn_entity.py -entity twowheel_amr -file /tmp/twowheel.urdf
  1. 檢查 ROS2 topic:

ros2 topic list | egrep "scan|imu" ros2 topic echo /twowheel_amr/scan --once ros2 topic echo /twowheel_amr/imu/data --once


[建議測試]

# 轉成 URDF

xacro /path/to/twowheel.fixed.urdf.xacro -o /tmp/twowheel.urdf


#(可選)檢查

check_urdf /tmp/twowheel.urdf



/spawn_entity 不存在=你的 gzserver 沒跑,或沒載入 libgazebo_ros_factory.so,或終端的 GAZEBO_MASTER_URI 不一致。照下面最短路徑做就會好:

1) 在「終端A」起 gzserver(一定要帶 factory)

source /opt/ros/humble/setup.bash export ALSOFT_DRIVERS=null export LIBGL_ALWAYS_SOFTWARE=1 GALLIUM_DRIVER=llvmpipe LIBGL_DRI3_DISABLE=1 #(可選)統一埠,兩個終端都要設同一值 export GAZEBO_MASTER_URI=http://127.0.0.1:11345 gzserver --verbose /usr/share/gazebo-11/worlds/empty.world \ -s libgazebo_ros_init.so \ -s libgazebo_ros_factory.so \ -s libgazebo_ros_force_system.so

別關掉這個終端;保持 gzserver 在跑。

# 先起 gzserver(建議 headless、靜音、軟體渲染)


# 另開終端 spawn(用檔案最穩)load urdf to gzserver world 

ros2 run gazebo_ros spawn_entity.py -entity twowheel_amr -file /tmp/twowheel.urdf


#gzclient is show GUI 

gzclient 


# 驗證感測器

ros2 topic list | egrep "scan|imu"

ros2 topic echo /twowheel_amr/scan --once

ros2 topic echo /twowheel_amr/imu/data --once


沒有留言:

張貼留言