티스토리 뷰

2021.6.13 16:58

 

안녕하세요

프로그래밍을 배우는 빛나는 샤트입니다.

 

 

자율주행 프로젝트 We-Go

진행하면서 공부한 내용들을 간략히 정리한 글입니다.

 

1. 주제: ROS에서 발행되는 Topic를 확인하고 발행 코드 작성하기

(정확히는 로봇의 조명 제어를 위함)

2. 내용

  • Topic 확인
  • 구독 노드가 있는지 확인
  • 데이터 타입 확인하기
  • 발행을 위한 변수 확인하기

 

 

3. Topic 확인

$ rostopic list

[터미널 결과 이미지]

 

위 실행 결과를 보면 발행노드(Publish)와 구독노드(Subscribe)를 확인할 수 있다.

 

4. 구독 노드가 있는지 확인/데이터 타입 확인하기

$ rostopic info /scout_light_control

$ rostopic info (topic name) 을 실행하게 되면 해당 토픽에 대한 정보(info)를 알 수 있다.

그러면 두 가지를 확인할 수 있는데,

첫 번째! 데이터 타입: (Type: scout_msgs/ScoutLightCmd)

두 번째! 구독 노드: (Subscribers: * /scout_base_node)

 

구독 노드가 있어야 발행을 할 수 있기 때문(정확히 말하면 구독이 없는 상태에서 발행만 있으면 무용지물)

 

5. 발행을 위한 변수 확인하기

이전에 /cmd_vel 토픽을 이용해 로봇의 모터를 제어했는데 총 6가지 변수가 있었다.

 

linear.x

linear.y

linear.z

angular.x

angular.y

angular.z

 

하지만 이건 위고 코리아에서 알려준 것이었기에 조명 제어를 위한 변수는 내가 찾아야했다.

일단 코드파일을 뒤져봤지만 내가 얻을 수 있는 것은 아래와 같았다.

 

uint8 LIGHT_CONST_OFF = 0
uint8 LIGHT_CONST_ON = 1
uint8 LIGHT_BREATH = 2
uint8 LIGHT_CUSTOM = 3

bool enable_cmd_light_control
uint8 front_mode
uint8 front_custom_value
uint8 rear_mode
uint8 rear_custom_value

음...느낌상 아래 문단의 5개인 것 같다. bool, unit8은 데이터 타입을 정의한 것으로 생각된다. (로봇 제어 코드는 다 C++로 짜여져 있었지만 C계열이 이렇게 변수의 데이터 타입을 모두 지정해준다는 사실은 알고 있었다.)

 

enable_cmd_light_control 변수는 bool타입이니까 True이면 조명 제어가 가능해지는 느낌이고,

나머지 4개는 front, rear라는 이름인 것을 보니 전방과 후방의 조명을 제어하는 느낌이다. 모두 정숫값을 가지고 있어서 일단 1을 지정해주면 켜지지 않을까? 라는 생각이 들었다. (사실 로봇에는 후방 조명이 없기 때문에 rear_mode, rear_custom_value 등에 값을 할당해도 변화는 없을 것이다. 즉, front_mode, front_custom_value 두 가지 변수만 조정해보면 된다는 뜻!)

 

그리고 명령어 코드로 발행을 해볼 수 있다는 것을 확인하고 시도했다.

$ rostopic pub /scout_light_control True 1 1 1 1 #$ rostopic pub [topic] [args]

enable_cmd_light_control에는 True를 할당하고 나머지는 1을 할당했더니....

light on

조명이 켜졌다!!

 

내 예상이 맞았다! 그래서 바로 조명을 켜는 발행 코드를 작성했다!

#! /usr/bin/env python

import rospy
from scout_msgs.msg import ScoutLightCmd

class Light_Control():
    def __init__(self):
        rospy.init_node('scout_light_control_shate', anonymous=False)
        self.msg_pub = rospy.Publisher(
            '/scout_light_control',
            ScoutLightCmd,
            queue_size=10
        )
        self.count = 0

    def onMsg(self):
        on = ScoutLightCmd()
        on.enable_cmd_light_control = True
        on.front_mode = 1
        self.msg_pub.publish(on)


# 조명 켜기
def on():
    while not rospy.is_shutdown():
        light = Light_Control()
        rate = rospy.Rate(10)
        light.onMsg()
        rate.sleep()

if __name__ == "__main__":
    on()

조명을 껐다가 다시 코드를 실행하니 다시 켜진 것을 확인함.

 

 

그래서 Rate를 조정해 주기적인 깜빡임을 구현하고자 했다. 그 결과는 아래와 같다.

 

코드는 아래와 같다.

총 네가지 메소드를 정의했다.

 

on(): 조명 켜기

off(): 조명 끄기

blink(): 1초 간격으로 깜빡임

emergency(): 빠르게 깜빡이기

 

*코드는 여기에: https://github.com/We-Go-Autonomous-driving/main-we-go-project/blob/master/light_control.py

#! /usr/bin/env python

import rospy
from scout_msgs.msg import ScoutLightCmd

class Light_Control():
    def __init__(self):
        rospy.init_node('scout_light_control_shate', anonymous=False)
        self.msg_pub = rospy.Publisher(
            '/scout_light_control',
            ScoutLightCmd,
            queue_size=10
        )
        self.count = 0

    def onMsg(self):
        on = ScoutLightCmd()
        on.enable_cmd_light_control = True
        on.front_mode = 1
        self.msg_pub.publish(on)

    def offMsg(self):
        off = ScoutLightCmd()
        off.enable_cmd_light_control = True
        off.front_mode = 0
        self.msg_pub.publish(off)

# 1초 간격으로 깜빡임
def blink():
    count = 0
    while not rospy.is_shutdown():
        light = Light_Control()
        rate = rospy.Rate(10)
        if str(count)[-1] == '1': light.onMsg() # 1초 주기로 on
        else: light.offMsg() # 나머지는 off
        rate.sleep()
        count+=1

# 조명 켜기
def on():
    while not rospy.is_shutdown():
        light = Light_Control()
        rate = rospy.Rate(10)
        light.onMsg()
        rate.sleep()

# 조명 끄기
def off():
    while not rospy.is_shutdown():
        light = Light_Control()
        rate = rospy.Rate(10)
        light.offMsg()
        rate.sleep()

def emergency():
    count = 0
    while not rospy.is_shutdown():
        light = Light_Control()
        rate = rospy.Rate(60)
        if str(count)[-1] in ['1', '6']: light.onMsg() # 1초 주기로 on
        else: light.offMsg() # 나머지는 off
        rate.sleep()
        count+=1

if __name__ == "__main__":
    blink()
    # off()
    # on()
    # emergency()

 

6. 마무리

아래의 명령어와 약간의 센스가 있다면 발행되는 토픽을 이용해 발행 코드를 작성할 수 있음!

 

  • rostopic list: 구독, 발행되는 모든 토픽 확인
  • rostopic info [topic]: 하나의 토픽에 대한 정보 확인(데이터 타입과 구독 노드 확인)
  • rostopic pub [topic] [args]: 하나의 토픽에 대한 사용자 정의값을 이용해 발행

ROS를 마냥 어렵게 생각했는데 이렇게 문제해결 경험을 겪고나니 자신감이 생겼다.

 

 

LIST
댓글