로봇/ROS

ROS1에 CygLiDAR 연동하기

with-RL 2023. 1. 19. 20:38

LiDAR는 주변상황을 인식하기 위한 장비로 카메라와는 다르게 레이저를 이용해서 객체의 위치와 거리를 정확하게 측정할 수 있습니다. 라이다로 인식된 정보를 subscribe 하는 과정에 대한 설명입니다.

 

아래 과정은 모두 아래 명령을 통해 Docker Container에 접속한 이후 실행하는 내용입니다.

$ docker exec -it ros1 /bin/bash

1. 시험환경

  • H/W: X86 계열 노트북
  • Host OS: Ubuntu-22.04-LTS Desktop
  • Docker Container: Ubuntu에서 Docker를 이용한 ROS1, ROS2 설치 과정을 통해 실행된 docker
  • 소스코드: ROS1에 YOLO v5 연동하기를 통해 카메라의 영상에서 Object Detection이 동작이 구현된 소스코드
  • <Container_ws>를 '/home/cchyun/Workspace'로 지정했습니다. 아래 경로에서 본인 환경에 맞게 수정해서 실행하면 됩니다.

2. CygLiDAR 연동

2.1. CygLiDAR 연결

CygLiDAR에 관련한 정보는 https://www.cygbot.com/에서 확인할 수 있습니다.

위 그림은 CygLiDAR를 컴퓨터에 USB로 연결하기 위해 구성품을 조립한 모습입니다.

LiDAR를 연결하지 않은 상황에서 아래 명령으로 '/dev' 폴더아래 tty 목록을 확인합니다.

# ls /dev/tty*

위 그림과 같은 tty 목록을 확인할 수 있습니다.

이제 LiDAR를 USB로 연결한 후 아래 명령으로 다시 한번 '/dev' 폴더아래 tty 목록을 확인합니다.

# ls /dev/tty*

'/dev/ttyUSB0'가 추가된 것을 확인할 수 있습니다.

2.3. CygLiDAR 패키지 설치

아래 명령으로 ROS1에 LiDAR를 연동하기 위한 패키지를 다운로드합니다.

# cd /home/cchyun/Workspace/ros_ws/src
# git clone https://github.com/CygLiDAR-ROS/cyglidar_d1.git

'/home/cchyun/Workspace/ros_ws/src/cyglidar_d1/launch/cyglidar.launch'의 port를 '/dev/ttyUSB0'로 변경합니다.

catkin_make 명령으로 패키지를 빌드합니다.

# cd /home/cchyun/Workspace/ros_ws
# catkin_make

roscore 및 ros 관련해서 실행된 모든 프로그램을 정지한 후 아래 명령으로 프로그램을 실행합니다.

# source devel/setup.bash
# roslaunch cyglidar_d1 cyglidar.launch

위 화면과 같이 rviz 화면에 LiDAR 정보가 출력된 것을 확인할 수 있습니다.

2.3. CygLiDAR 개별 실행

cyglidar.launch를 통한 실행이 아닌 rosrun을 이용해서 직접 실행하는 과정입니다.

우선 ctrl+c를 눌러서 cyglidar.launch 프로그램을 종료합니다.

 

5개의 터미널을 실행하고 Docoker Container에 접속 후 각각 아래 명령을 실행해서 실행 환경을 준비합니다.

# cd /home/cchyun/Workspace/ros_ws
# source devel/setup.bash

첫 번째 터미널에서 아래 명령을 실행해서 roscore를 실행합니다.

# roscore

두 번째 터미널에서 아래 명령을 실행해서 '/uvc_camera' node를 실행합니다.

# rosrun uvc_camera uvc_camera_node _skip_frames:=5

세 번째 터미널에서 아래 명령을 실행해서 '/yolov5_ros' node를 실행합니다.

# rosrun yolov5_ros detect.py

네 번째 터미널에서 아래 명령을 실행해서 'cyglidar_d1' node를 실행합니다.

run_mode가 0이면 2D 모드로 동작합니다.

# rosrun cyglidar_d1 cyglidar_pcl_publisher _port:=/dev/ttyUSB0 _run_mode:=0

다섯 번째 터미널에서 아래 명령을 실행해서 'rviz'를 실행합니다.

# rviz -d /home/cchyun/Workspace/ros_ws/src/cyglidar_d1/rviz/cyglidar_config.rviz

rviz에서 2D 형식의 LiDAR 정보를 확인할 수 있습니다.

네 번째 터미널에서 ctrl+c 를 눌려서 'cyglidar_d1' node를 종료 후 아래 명령을 입력해서 3D 모드로 'cyglidar_d1' node를 실행합니다.

# rosrun cyglidar_d1 cyglidar_pcl_publisher _port:=/dev/ttyUSB0 _run_mode:=1

rviz에서 3D 형식의 LiDAR 정보를 확인할 수 있습니다.

네 번째 터미널에서 ctrl+c 를 눌려서 'cyglidar_d1' node를 종료 후 아래 명령을 입력해서 2D/3D 모드로 'cyglidar_d1' node를 실행합니다.

# rosrun cyglidar_d1 cyglidar_pcl_publisher _port:=/dev/ttyUSB0 _run_mode:=2

rviz에서 2D/3D 형식의 LiDAR 정보를 확인할 수 있습니다.

2.4. robot_ctrl 패키지에서 LiDAR 정보 수신하기

Ubuntu에서 Docker를 이용한 ROS1, ROS2 설치의 '2.5. robot_ctrl 패키지 기능 구현'으로 만든 코드를 수정해서 LiDAR 정보를 수신하도록 수정하는 과정입니다.

 

'/home/cchyun/Workspace/ros_ws/src/robot_ctrl/src/control.py' 파일의 내용을 아래와 같이 변경합니다.

#!/usr/bin/env python3

import math
import rospy

from sensor_msgs.msg import LaserScan
from yolov5_ros.msg import BoundingBoxes

class RobotControl:
    def __init__(self):
        self.RAD2DEG = 180/math.pi

        rospy.Subscriber('/yolov5_ros', BoundingBoxes, self.bbox_cb)
        rospy.Subscriber('/scan_laser', LaserScan, self.lidar_cb)
    
    def bbox_cb(self, bbox_msg):
        pass
    
    def lidar_cb(self, scan_data): # 초당 6 ~ 7 프레임
        distance_dic = {}
        for i, distance in enumerate(scan_data.ranges):
            angle = (scan_data.angle_min + scan_data.angle_increment * i) * self.RAD2DEG # ang -60 ~ 60
            distance_dic[angle] = distance
        print(distance_dic)
        print()


if __name__ == "__main__":
    rospy.init_node("robot_control", anonymous=True)

    control = RobotControl()
    
    rospy.spin()

아래 명령을 수행해서 'robot_ctrl' 기능을 수행합니다.

# rosrun robot_ctrl control.py

위 그림과 같이 2D의 경우 -60° ~ 60° 각도를 0.75° 간격 분할하고 각 간격의 거리정보를 미터 단위로 확인할 수 있습니다.

 

이상으로 ROS1에 CygLiDAR를 연동하는 과정에 대한 설명이었습니다.