<launch>
<node name="rosbag_play" pkg="rosbag" type="play" output="screen" required="true" args="$(find rviz_lidar)/src/lidar_topic.bag" />
</launch>
#!/usr/bin/env python
import serial, time, rospy
from sensor_msgs.msg import Range # Range 임포트
from std_msgs.msg import Header # Header 임포트
rospy.init_node('lidar_range') # 노드 생성
pub1 = rospy.Publisher('scan1', Range, queue_size = 1)
pub2 = rospy.Publisher('scan2', Range, queue_size = 1)
pub3 = rospy.Publisher('scan3', Range, queue_size = 1)
pub4 = rospy.Publisher('scan4', Range, queue_size = 1) # 4개의 토픽 발행 준비
msg = Range() # Range 정보 채우기 준비
h = Header() # Header 정보 채우기 준비
h.frame_id = "sensorXY" # Header 정보 채우기
msg.header = h
msg.radiation_type = Range().ULTRASOUND
msg.min_range = 0.02
msg.max_range = 2.0 # Range 정보 채우기
msg.field_of_view = (30.0/180.0) * 3.14 # 원뿔 모양의 Range 표시에 필요한 정보 채우기
while not rospy.is_shutdown():
msg.header.stamp = rospy.Time.now()
msg.range = 0.4
pub1.publish(msg)
msg.range = 0.8
pub2.publish(msg)
msg.range = 1.2
pub3.publish(msg)
msg.range = 1.6
pub4.publish(msg) # msg.range에 장애물까지의 거리를 미터(m) 단위로 넣고 토픽을 발행
time.sleep(0.2)
<launch>
<!-- rviz display-->
<node name="rviz_visualizer" pkg="rviz" type="rviz" required="true" args="-d $(find rviz_lidar)/rviz/lidar_range.rviz" />
<node name="lidar_range" pkg="rviz_lidar" type="lidar_range.py" />
</launch>