오늘은 저번에 이어서 가제보 환경에 라이다와 IMU 센서를 플러그인 해서 ROS 데이터를 받아오는 것을 포스팅하겠습니다 !
제가 여기서 사용한 라이다 모델은 Velodyne이고, Gazebo-classic 환경입니다.
먼저 velodyne 모델이 있는 git repository를 clone 한 후 아래의 경로에 붙여넣어 줍니다.
PX4-Autopilot/Tools/simulation/gazebo-classic/models
git clone https://github.com/osrf/gazebo_models.git
이후 아래 경로의 model.sdf 에서 다음과 같이 라이다를 include 해주고 joint를 넣어줘서 기존의 드론 모델과 결합을 시켜줍니다.
PX4-Autopilot/Tools/simulation/gazebo-classic/models/iris/model.sdf
<include name="velodyne">
<uri>model://velodyne_hdl32</uri>
<pose>0 0 -0.1 0 0 0</pose> <!-- 드론 중심 기준 위치 -->
</include>
<joint name="velodyne_joint" type="fixed">
<parent>base_link</parent> <!-- 드론의 메인 링크 -->
<child>velodyne::base</child> <!-- velodyne 모델의 링크 이름 -->
</joint>
아래 센서를 사용하기 위해서는 일단 아래와 같은 패키지를 설치해야 합니다.
sudo apt install ros-humble-gazebo-ros-pkgs ros-humble-gazebo-ros2-control
sudo apt install ros-humble-velodyne-description ros-humble-velodyne-gazebo-plugins ros-humble-velodyne-simulator
이후 velodyne 모델 sdf 파일에서 센서 블록안에 다음과 같이 추가를 해줍니다. 아래를 추가해줘야 시뮬레이션을 실행했을 때 ROS 메시지가 나옵니다 !
여기서의 토픽이름은 "/velodyne_points" 입니다.
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
<ros>
<namespace>/velodyne</namespace>
<remapping>~/out:=velodyne_points</remapping>
</ros>
<frame_name>top</frame_name>
<organize_cloud>false</organize_cloud>
<min_range>0.9</min_range>
<max_range>130.0</max_range>
<gaussian_noise>0.008</gaussian_noise>
</plugin>
1.3 까지 하고 라이다를 스캔을 시각화했을 때 포인트 수가 적고 시야각이 좁아서 다음과 같이 샘플 수와 시야각을 늘려 주었습니다. 다음은 라이다의 모델 sdf 파일에서 ray 블록안에 추가해주면 됩니다.
<scan>
<horizontal>
<samples>1024</samples>
<resolution>1</resolution>
<min_angle>-3.1415</min_angle>
<max_angle>3.1415</max_angle>
</horizontal>
<vertical>
<samples>128</samples>
<resolution>1</resolution>
<min_angle>-3.1415</min_angle>
<max_angle>3.1415</max_angle>
</vertical>
</scan>
다음은 IMU Plugin 입니다. 라이다에서는 include 했지만 imu는 바로 모델 sdf 파일에 센서 플러그인을 하였습니다. 크게 다음과 같이 추가했습니다.
mass 같은 경우에는 추가하지 않으면 드론이 제대로 날지 않았어서 추가해줬습니다. 그리고 질량이 너무 크면 드론이 천천히 날고, waypoint를 주었을 때 급하강했다가 상승하는 현상이 보이기 때문에 적당한 값을 넣어줘야 합니다.
<link name="imu_link">
<pose>0.05 0 -0.1 0 0 0</pose>
<inertial>
<mass>0.001</mass>
<inertia>
<ixx>1e-6</ixx>
<iyy>1e-6</iyy>
<izz>1e-6</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
<sensor name="imu_sensor" type="imu">
<pose>0 0 0 0 0 0</pose> <!-- IMU 위치 설정 -->
<always_on>true</always_on>
<update_rate>100.0</update_rate>
<visualize>true</visualize>
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<namespace>/imu</namespace>
<remapping>~/out:=data</remapping>
</ros>
<topicName>imu/data</topicName>
<frameName>imu_link</frameName>
</plugin>
</sensor>
</link>
<joint name="imu_joint" type="fixed">
<parent>base_link</parent>
<child>imu_link</child>
</joint>
센서 실행은 저번에 포스팅한 드론 실행하는 command를 사용하면 센서가 활성화가 됩니다 !
topic list

라이다 topic echo

imu topic echo

Scan 시각화

감사합니다 .