#!/usr/bin/env python
import rospy
import time
from sensor_msgs.msg import LaserScan # LaserScan 메시지 사용 준비
lidar_points = None
def lidar_callback(data): # 라이다 토픽이 들어오면 실행되는 콜백함수 정의
global lidar_points
lidar_points = data.ranges
rospy.init_node('my_lidar', anonymous = True) # my_lidar 이름의 노드 생성
rospy.Subscriber('/scan', LaserScan, lidar_callback, queue_size = 1) # LaserScan 토픽이 오면 콜백함수가 호출되도록 세팅
while not rospy.is_shutdown():
if lidar_points == None:
continue
rtn = ""
for i in range(12): # 30도씩 건너뛰면서 12개 거리값만 출력함
rtn += str(format(lidar_points[i * 30], '.2f')) + ", "
print(rtn[:-2])
time.sleep(1.0) # 천천히 출력함
<launch>
<include file="$(find xycar_lidar)/launch/lidar_noviewer.launch" />
<node name="my_lidar" pkg="my_lidar" type="lidar_scan.py" output="screen" />
</launch>
<launch>
<!-- rviz display-->
<node name="rviz_visualizer" pkg="rviz" type="rviz" required="true" args="-d $(find rviz_lidar)/rviz/lidar_3d.rviz" />
<node name="xycar_lidar" pkg="xycar_lidar" type="xycar_lidar" output="screen">
<param name="serial_port" type="string" value="/dev/ttyRPL" />
<param name="serial_baudrate" type="int" value="115200" />
<param name="frame_id" type="string" value="laser" />
<param name="inverted" type="bool" value="false" />
<param name="angle_compensate" type="bool" value="true" />
</node>
</launch>
<launch>
<!-- rviz display-->
<node name="rviz_visualizer" pkg="rviz" type="rviz" required="true" args="-d $(find rviz_lidar)/rviz/lidar_3d.rviz" />
<node name="rosbag_play" pkg="rosbag" type="play" output="screen" required="true" args="-d $(find rviz_lidar)/src/lidar_topic.bag" />
</launch>