.. Cover Letter

ㅇ 프로젝트/TEAM_Carla-Autoware-bridge

4. (CARLA Autoware Bridge) 추가적으로 자율주행을 위해 필요한 센서값들 연결하기 (신호등 연결)

BrainKimDu 2023. 4. 30. 05:32

이 프로젝트는 CARLA-Autoware Bridge의 완성을 적는 것이 아니라, 이렇게 만들면 Bridge가 가능하다라는 것을 증명하는 프로젝트임을 알립니다.

신호등 정보를 추가하기

  • Carla에서 카메라 영상정보를 보내면 이 영상정보에서 신호등을 detection하고, 여기서 빨간불인지 초록불인지 판단을 하고, autoware에 반영을 해주게 하는 방법이 있을 것입니다.
  • 우선은 여기서 신호등을 detection하는 과정을 생략하고 carla에서 현재 어느 구역의 신호등이 빨간불이다 라는 정보를 보내고 autoware는 이들 받아서 적용하는 과정을 제작해보고자 합니다.

 

Topic 분석하기

Carla에서 보내는 값

  • ros2 topic list를 통해서 어떤 토픽을 구독해야 현재 world의 신호등 정보를 받을 수 있을지 확인합니다.
  • 4개의 터미널이 필요합니다.
cd /opt/carla-simulator
./CarlaUE4.sh
car_ros_bridge
ros2 launch carla_autoware_bridge carla_ros_bridge.launch.py
car_ros_bridge
ros2 launch carla_autoware_bridge carla_autoware_ego_vehicle.launch.py
car_ros_bridge
#ros2 topic list
ros2 topic echo /carla/traffic_lights/status
ros2 topic info /carla/traffic_lights/status
  • 맵에 존재하는 신호등의 id와 상태를 모두 보여줍니다. 그리고 메시지 타입은 다음와 같습니다. 그러면 이 값을 받아서 autoware에게 보내주면 될 것입니다.

 

autoware에서 보내는 값

  • docker에 진입하고
sudo rocker --nvidia --x11 --user --volume $HOME/autoware --volume $HOME/autoware_map --  autoware_build:0.3
  • autoware를 실행합니다.
ros2 launch autoware_launch planning_simulator.launch.xml map_path:=$HOME/autoware_map/carla-town01 vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit
  • autoware에서 traffic_light_id를 조회하면 다음처럼 신호등의 ID를 알아낼 수 있습니다. 만약 신호등이 포함되지 않은 Vector map이라면 id를 조회할 수 없습니다.
  • 저는 이 값이 고정된 값이라 예상했습니다만, 값이 바뀌는 경우가 있습니다.
  • carla와 autoware에서의 신호등 각각의 ID는 서로 다릅니다. carla-town에 존재하는 신호등은 약 35개정도이며, 이를 일일히 비교하고 맞추기에는 문제가 있습니다. 그래서 하나의 교차로에서 3개의 신호등을 맞추보면서 검증을 하고자 하였습니다.
  • 다음의 패널을 추가합니다.
  • 다음처럼 29733 ID의 신호등을 빨간불로 지정하고 publishing하면 빨간불로 나타나는데, 혹시 이게 topic이 아닐까 생각했습니다.
car_ros_bridge
#ros2 topic list
ros2 topic echo /perception/traffic_light_recognition/traffic_signals
ros2 topic info /perception/traffic_light_recognition/traffic_signals
  • 29733번의 값이 1(red)인 상태로 지속적으로 발행되고 있습니다.

(메시지 타입을 분석하는 과정도 있으나 생략합니다. info로 찾은 메시지를 직접 뜯어보면서 메시지타입을 조사합니다.)

코드로 구현하기

  • 전체적인 코드는 하나의 교차로에서 carla에서 들어오는 신호등 신호를 autoware 메시지 타입에 맞게 변환해서 토픽을 발행하는 것입니다.
  • traffic_light.py
from autoware_auto_perception_msgs.msg import TrafficSignal, TrafficLight, TrafficSignalArray
from carla_msgs.msg import CarlaTrafficLightStatusList
from rclpy.node import Node
from std_msgs.msg import Header
import rclpy

class TrafficlightNode(Node):

    def __init__(self) -> None:
        super().__init__('traffic_light')

        self.carla_traffic = self.create_subscription(
            CarlaTrafficLightStatusList, '/carla/traffic_lights/status',
            self._carla_traffic_callback, 1)

        self.auto_traffic = self.create_publisher(
            TrafficSignalArray, '/perception/traffic_light_recognition/traffic_signals', 1)
        
        self.timer = self.create_timer(0.1, self.timer_callback)
        self.autoware_traffic_lights = []

    def _carla_traffic_callback(self, carla_traffic_msg):
        self.autoware_traffic_lights = []
        for traffic_light in carla_traffic_msg.traffic_lights:
            # carla에서 28번 신호등을 autoware에 맞게 변환하는 과정
            if traffic_light.id == 28:
                lights = [TrafficLight(color=traffic_light.state + 1, shape=5, status=14, confidence=1.0)]
                signal = TrafficSignal(map_primitive_id=29733, lights=lights)
                self.autoware_traffic_lights.append(signal)
            elif traffic_light.id == 38:
                lights = [TrafficLight(color=traffic_light.state + 1, shape=5, status=14, confidence=1.0)]
                signal = TrafficSignal(map_primitive_id=29847, lights=lights)
                self.autoware_traffic_lights.append(signal)
            elif traffic_light.id == 50:
                lights = [TrafficLight(color=traffic_light.state + 1, shape=5, status=14, confidence=1.0)]
                signal = TrafficSignal(map_primitive_id=29913, lights=lights)
                self.autoware_traffic_lights.append(signal)
                
    # 타이머를 설정하지 않으면 안됨, 실제로 autoware에서 /perception/traffic_light_recognition/traffic_signals  
    # 발행하는 이 토픽은 0.1초간격으로 발행되고 있으며, 끊기면 autoware에서는 신호등이 사라진거로 간주됨
    # 그래서 carla에서 쏘는 신호등 topic과 autoware에서 받아야 하는 토픽의 주기 차이로 인해
    # 0.1초 마다 토픽을 계속 발행해주어 오류를 방지함.
    def timer_callback(self):
        if self.autoware_traffic_lights is not None:
            header = Header(stamp=self.get_clock().now().to_msg(), frame_id='')
            signal_array = TrafficSignalArray(header=header, signals=self.autoware_traffic_lights)   
            self.auto_traffic.publish(signal_array)
            print(signal_array)



def main(args=None):
    rclpy.init(args=args)
    Traffic = TrafficlightNode()

    rclpy.spin(Traffic)

    Traffic.destroy_node()
    rclpy.shutdown()


if __name__ == '__main__':
    main()

setup.py 의 entry_points에 다음을 추가

'traffic_light = carla_autoware_bridge.traffic_light:main',

동작을 확인

실행

  • 이제 터미널이 7개 필요합니다.
  • 주의 사항으로는 하나하나 로딩이 완료된 후 진행합니다.

Carla실행

cd /opt/carla-simulator
./CarlaUE4.sh
car_ros_bridge
ros2 launch carla_autoware_bridge carla_ros_bridge.launch.py
car_ros_bridge
ros2 launch carla_autoware_bridge carla_autoware_ego_vehicle.launch.py
car_ros_bridge
ros2 launch carla_manual_control carla_manual_control.launch.py
car_ros_bridge
ros2 run carla_autoware_bridge carla_autoware_bridge
car_ros_bridge
ros2 run carla_autoware_bridge traffic_light

Autoware실행

sudo rocker --nvidia --x11 --user --volume $HOME/autoware --volume $HOME/autoware_map --  autoware_build:0.3
ros2 launch autoware_launch planning_simulator.launch.xml map_path:=$HOME/autoware_map/carla-town01 vehicle_model:=sample_vehicle sensor_model:=sample_sensor_kit

 

동작

  • 빨간불일 경우 autoware에 빨간불이라고 표시되면서 자동차도 함께 멈춥니다.
  • 초록불이 된 경우 자동차가 이동을 시작합니다.

 
 

  • 이로서 서로 성공적으로 연결되었음을 확인합니다. 문제점은 약 35개의 신호등을 모두 일일히 지정해주어야한다는 단점이 있습니다. 그리고 autoware에서 신호등의 ID가 변경되는 경우가 있습니다.

 
결국 Bridge 작업을 하는 것은 같은 주제의 토픽이 서로 다른 메시지 형태를 가지고 있고, 그 메시지들을 알맞게 converting하는 과정임을 알게되었으며
필요한 토픽을 하나하나 연결해가면서 완성해나가면 될 것이라 생각됩니다.
여기까지로 프로젝트를 마칩니다. autoware와 carla를 통해 ros로 bridge 작업을 한다는 것의 개념을 이해할 수 있는 좋은 프로젝트였습니다.