はじめに
- Gazebo (classic)で、LiDAR反射強度のある物体の作成方法
- ROS2 2D LiDARの場合は、sensor_msgs/msg/LaserScanのintensitesに入る値
動作確認環境
- ROS2 Foxy
- Gazebo 11 (Gazebo classic)
- 2D LiDAR Plugin
- libgazebo_ros_ray_sensor.so
<output_type>sensor_msgs/LaserScan</output_type>
- libgazebo_ros_ray_sensor.so
方法
ポイントは、<laser_retro>
タグを<visual>タグ
に入れて、物体をSDFで作成する。
例 (50cm x 50cm x 5mm の反射板)
mode.sdf
<?xml version="1.0"?>
<sdf version="1.6">
<model name="reflection_panel">
<static>true</static>
<pose>0 0 0.25 0 0 0</pose>
<link name="left_reflection_panel_link">
<pose>0 0 0 0 0 0</pose>
<collision name="collision">
<laser_retro>1000.0</laser_retro>
<geometry>
<box>
<size>0.005 0.5 0.5</size>
</box>
</geometry>
</collision>
<visual name="visual">
<laser_retro>1000.0</laser_retro>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/White</name>
</script>
</material>
<geometry>
<box>
<size>0.005 0.05 0.5</size>
</box>
</geometry>
</visual>
</link>
</model>
</sdf>
上記の場合は、2D LiDARデータsensor_msgs/msg/LaserScanのintensitiesに1000.0が入る。
-
<laser_retro>
タグは、<collision>
タグには入れなくても大丈夫だったが入れても問題ない。
Gazeboモデルのパッケージ化は以下の記事を参考にすると良い。
参考