국민대학교 자율주행 대회

예선 시스템 구축

ROS 기반 보안 인증 및 자동화 평가 플랫폼

조 윤범
기획 및 백엔드 담당 (프론트엔드와 랭크서버 외 전부)
2023년

프로젝트 개요

목적

국민대 자율주행 대회 예선 시스템 구축

역할

  • 기획 및 백엔드 총괄
  • 보안 시스템 설계 및 구현
  • ROS 기반 자동화 파이프라인 구축
  • 인프라 구축 (Docker, Nginx, Bind9)

시스템 구성

  • Docker 기반 6개 컨테이너 환경
  • 학생 로컬 PC에서 전체 시스템 구동
  • REST API 기반 자동화 제어
  • 중앙 인증 서버와 TLS 통신

배포 방식

쉘 스크립트를 바이너리로 컴파일하여 바이너리 실행만으로 전체 시스템 구동

기술 스택

C++ Python ROS1 Noetic Docker Unreal Engine Carla 0.9.13 Nginx Bind9 OpenSSL PostgreSQL Crow (C++ Web Framework)

전체 시스템 아키텍처

graph TD subgraph 학생 로컬 PC 환경 A[컨테이너 1: Bind9 DNS 서버
- divinetech.rc 로컬 도메인 관리
- 공인 DNS와 CNAME 연동] B[컨테이너 2: Nginx 리버스 프록시
- Let's Encrypt SSL 종단
- server_name 기반 라우팅] C[컨테이너 3: 커스텀 Carla Server] D[컨테이너 4: ROS 자동 실행기
C++ Crow:20001] E[컨테이너 5: CarlaViz 시각화:8080] F[컨테이너 6: WebSocket:8081] G[Docker 공유 볼륨 /shared
모든 컨테이너가 파일 공유] A --> B B --> C B --> D B --> E B --> F C -.-> G D -.-> G E -.-> G F -.-> G end subgraph 글로벌 중앙 서버 H[인증 서버
- auth.contest.divinetech.dev
- Flask + PostgreSQL
- RSA 개인키 보관
- 랭킹 DB 관리] I[웹 UI 서버
- HTML/JavaScript 제공
- 파일 업로드 처리
- 신호 수신 /signal?type=1/2/3/4
- 로그 다운로드 제공] end B -.->|HTTPS| H B -.->|HTTPS| I

네트워크 라우팅

  • web.km.7.divinetech.dev → 글로벌 웹 UI 서버 (외부)
  • api.km.7.divinetech.dev → 172.172.172.173:20001 (로컬 ROS)
  • carlaviz.km.7.divinetech.dev → 172.172.172.177:8080 (로컬)
  • ws.km.7.divinetech.dev → 172.172.172.174:8081 (로컬)

완전 자동화 워크플로우

1. ROS 패키지 작성 /catkin_ws/src/student_package/ start.launch 작성 xycar_motor 토픽 발행 2. tar 압축 tar czf src.tgz catkin_ws/src/ 3. 웹 업로드 https://api.km.7 .divinetech.dev 4. 공유 볼륨 배치 /shared에 src.tgz 4개 컨테이너 접근 가능 5. Extract 버튼 클릭 (학생 웹 UI) 6. ROS API 호출 GET /extract tar xf ./src.tgz 중앙 서버 신호 전송 7. Build 버튼 클릭 (학생 웹 UI) 8. ROS API 호출 GET /build catkin_make 실행 build_log.txt 저장 9. Launch 버튼 클릭 (학생 웹 UI) 10. ROS API 호출 GET /launch roslaunch ./start.launch Carla 자동 연동 11. 자율주행 시작 Carla → ROS 센서 데이터 ROS → Carla 제어 명령 12. 실시간 모니터링 CarlaViz WebSocket :8081 13. Compress 버튼 (주행 완료 후) 14. ROS API 호출 GET /compress ~/.ros 전체 압축 UUID.tgz 생성 다운로드 URL 전송 15. 리플레이 저장 Carla Unreal Engine 리플레이 파일 ✓ 완료

ROS 노드 및 토픽 구조

ROS 노드

graph TD A[ROS Master
roscore
127.0.0.1:11311] --> B[carla_ctl 노드] A --> C[학생 노드]

ROS 토픽 흐름

graph LR A[Carla Simulator
Unreal Engine] --> B[carla_ctl 노드
C++] B --> C[ROS 토픽] C --> D[/usb_cam/image_raw/sensor_msgs/Image
RGB 카메라 이미지 640x480 30Hz] C --> E[/scan/sensor_msgs/LaserScan
1채널 LiDAR 360도 10Hz] C --> F[/imu/sensor_msgs/Imu
IMU 데이터 100Hz] D --> G[학생 자율주행 노드
Python/C++] E --> G F --> G G --> H[/xycar_motor/xycar_msgs/xycar_motor
angle -1.0 ~ 1.0
speed 0.0 ~ 1.0] H --> B B --> I[Carla Simulator
차량 움직임]

주요 토픽 상세

토픽 메시지 타입 주파수 설명
/usb_cam/image_raw sensor_msgs/Image 30Hz RGB 카메라 (640x480, BGRA8)
/scan sensor_msgs/LaserScan 10Hz 1채널 LiDAR (360도)
/imu sensor_msgs/Imu 100Hz IMU (가속도, 각속도, 자세)
/xycar_motor xycar_msgs/xycar_motor 10Hz 차량 제어 명령

REST API 기반 ROS 자동화 시스템

컨테이너 구조

graph TD subgraph ROS 자동 실행 컨테이너 C++ A[Crow Web Server
포트 20001
GET /extract → extract
GET /build → build
GET /launch → launch
GET /compress → compress
GET /stop → stop] --> B[Execute 클래스 Exe.cpp
fork + execvp 프로세스
비동기 실행 std::future
ROS 환경변수 자동 설정] B --> C[/home/divinetech/catkin_ws/
src/ 학생 패키지
build/
devel/] end

Exe.cpp 핵심 함수

1. extract() - tar 압축 해제

C++
std::future<int> Execute::extract() 
{
    return intProcess(
        "/home/divinetech/catkin_ws",  // 작업 디렉토리
        "/bin/tar",                     // 실행 명령
        { "xf", "./src.tgz" },         // 인자
        1                               // 프로세스 코드
    );
}

2. build() - catkin_make 빌드

C++
std::future<std::string> Execute::build() 
{
    return stringProcess(
        "/home/divinetech/catkin_ws",
        "/opt/ros/noetic/bin/catkin_make",
        {},  // 인자 없음
        2
    );
}
// 빌드 로그를 build_log.txt에 저장

3. launch() - roslaunch 실행

C++
std::future<std::string> Execute::launch() 
{
    return stringProcess(
        "/home/divinetech/catkin_ws/src",
        "/opt/ros/noetic/bin/roslaunch",
        { "./start.launch" },
        3
    );
}
// launch 로그를 launch_log.txt에 저장

4. compress() - 로그 압축 및 업로드

C++
std::future<int> Execute::compress() 
{
    // UUID 생성
    uuid_t uuid;
    char uuid_str[37];
    uuid_generate_random(uuid);
    uuid_unparse(uuid, uuid_str);
    
    std::string file_name = std::string(uuid_str) + ".tgz";
    
    // ~/.ros 전체를 tar로 압축
    return intProcess(
        "/home/divinetech/.ros",
        "/bin/tar",
        { "czpf", "/home/divinetech/logs/" + file_name, 
          "-C", "/home/divinetech/.ros", "." },
        4
    );
}
// 완료 후 중앙 서버에 다운로드 URL 전송

C++ 기반 프로세스 관리 시스템

intProcess() 동작 방식

C++
std::future<int> Execute::intProcess(
    const std::string& workDir,
    const std::string& command,
    const std::vector<std::string>& args,
    int procCode
) 
{
    currentProc = procCode;  // 현재 프로세스 상태 저장
    
    pid_t pid = fork();  // 자식 프로세스 생성
    
    if (pid == 0) {
        // 자식 프로세스
        chdir(workDir.c_str());  // 작업 디렉토리 변경
        
        // ROS 환경변수 설정
        setenv("ROS_MASTER_URI", "http://127.0.0.1:11311", 1);
        setenv("ROS_DISTRO", "noetic", 1);
        setenv("CMAKE_PREFIX_PATH", "/home/divinetech/catkin_ws/devel:/opt/ros/noetic", 1);
        // ... 기타 ROS 환경변수
        
        execvp(command.c_str(), c_args.data());  // 명령 실행
        _exit(127);  // exec 실패 시
    } 
    else {
        // 부모 프로세스
        currentPID = pid;
        
        // 비동기로 자식 프로세스 종료 대기
        std::thread([pid, promise]() mutable {
            int status;
            waitpid(pid, &status, 0);
            
            if (WIFEXITED(status)) {
                promise.set_value(WEXITSTATUS(status));
            }
        }).detach();
        
        return future;
    }
}

stringProcess() - 로그 캡처

C++
// stdout/stderr을 파이프로 리다이렉션
int pipe_fd[2];
pipe(pipe_fd);

if (pid == 0) {
    dup2(pipe_fd[1], STDOUT_FILENO);  // stdout → pipe
    dup2(pipe_fd[1], STDERR_FILENO);  // stderr → pipe
    execvp(command.c_str(), c_args.data());
}

// 부모 프로세스에서 파이프 읽기
std::async([pipe_fd]() {
    char buffer[128];
    std::stringstream ss;
    while (read(pipe_fd[0], buffer, sizeof(buffer)) > 0) {
        ss.write(buffer, count);
    }
    return ss.str();  // 전체 로그 반환
});

핵심 포인트

  • 비동기 실행: std::future로 논블로킹
  • 로그 캡처: pipe + dup2로 stdout/stderr 수집
  • 프로세스 추적: PID 저장, 상태 관리
  • ROS 환경 자동 설정: 12개 환경변수 자동 주입

C++ Crow 프레임워크 기반 API

Web.cpp - API 엔드포인트

GET /extract

C++
crow::response WebServer::extract()
{
    // 이미 실행 중이면
    if (exe->getStatus() == 1) {
        return makeJson(200, "Extracting...", true);
    }
    
    // 압축 해제 시작
    auto extract_future = exe->extract();
    
    // 비동기로 완료 대기 후 중앙 서버에 신호
    std::thread([extract_future]() mutable {
        int exit_code = extract_future.get();
        
        CURL *curl = curl_easy_init();
        curl_easy_setopt(curl, CURLOPT_URL, 
            "https://api.km.7.divinetech.dev/signal?type=1");
        curl_easy_perform(curl);
        curl_easy_cleanup(curl);
    }).detach();
    
    return makeJson(200, "Extract Start!!", true);
}

GET /build

C++
crow::response WebServer::build()
{
    if (exe->getStatus() == 2) {
        return makeJson(200, "Building...", true);
    }
    
    auto build_future = exe->build();
    
    std::thread([build_future]() mutable {
        std::string build_log = build_future.get();
        
        // 로그 저장
        std::ofstream outFile("/home/divinetech/.ros/build_log.txt");
        outFile << build_log;
        outFile.close();
        
        // 중앙 서버에 신호
        CURL *curl = curl_easy_init();
        curl_easy_setopt(curl, CURLOPT_URL, 
            "https://api.km.7.divinetech.dev/signal?type=2");
        curl_easy_perform(curl);
        curl_easy_cleanup(curl);
    }).detach();
    
    return makeJson(200, "Build Start!!", true);
}

GET /launch

C++
crow::response WebServer::launch()
{
    if (exe->getStatus() == 3) {
        return makeJson(200, "Launching...", true);
    }
    
    auto launch_future = exe->launch();
    
    std::thread([launch_future]() mutable {
        std::string launch_log = launch_future.get();
        
        std::ofstream outFile("/home/divinetech/.ros/launch_log.txt");
        outFile << launch_log;
        outFile.close();
        
        CURL *curl = curl_easy_init();
        curl_easy_setopt(curl, CURLOPT_URL, 
            "https://api.km.7.divinetech.dev/signal?type=3");
        curl_easy_perform(curl);
        curl_easy_cleanup(curl);
    }).detach();
    
    return makeJson(200, "Launch!!", true);
}

GET /compress

C++
crow::response WebServer::compress()
{
    auto compress_future = exe->compress();
    
    std::thread([compress_future]() mutable {
        int exit_code = compress_future.get();
        
        // 완료 신호
        CURL *curl = curl_easy_init();
        curl_easy_setopt(curl, CURLOPT_URL, 
            "https://api.km.7.divinetech.dev/signal?type=4");
        curl_easy_perform(curl);
        curl_easy_cleanup(curl);
        
        // .ros 폴더 삭제
        exe->deleteFolder("/home/divinetech/.ros");
    }).detach();
    
    return makeJson(200, "Compress Start!!", true);
}

GET /stop

C++
crow::response WebServer::stop()
{
    exe->stop();  // 현재 프로세스 SIGINT
    exe = std::make_unique<Execute>();  // 재초기화
    
    return makeJson(200, "stop function Executed", true);
}

API 흐름

학생 웹 UI 버튼 클릭 중앙 API 서버 api.km.7.divinetech.dev 내부 라우팅 Nginx 리버스 프록시 ROS 컨테이너 127.0.0.1:20001 C++ Crow 서버 Execute 클래스 fork + execvp 실제 프로세스 tar/catkin_make roslaunch 완료 중앙 서버 신호 /signal?type=X

carla_ctl 노드 상세

carla_ctl.cpp 주요 기능

1. Carla 초기화

C++
// Carla 연결
CarlaCtl carla("127.0.0.1", 2000);

// 월드 로드
carla.LoadWorld("Kookmin");

// 동기 모드 설정
carla::rpc::EpisodeSettings settings;
settings.synchronous_mode = true;
settings.fixed_delta_seconds = 0.05;  // 20Hz
carla.ApplyWorldSettings(settings);

// 차량 스폰
carla.SpawnVehicle("vehicle.tesla.model3", SpawnLocation);

2. 센서 부착

C++
// 카메라 센서
const cg::Transform sensorTransform = 
    carla.MakeTransform(
        camera_sensor_y,  // 파라미터에서 읽음
        camera_sensor_x,
        camera_sensor_z,
        0.0, 0.0, 0.0
    );

carla.AttachSensor(
    "sensor.camera.rgb",
    sensorTransform,
    attr,
    cameraListen  // 콜백 함수
);

// LiDAR 센서
const std::map<std::string, std::string> LaserScanAttribute = {
    {"channels", "1"},
    {"rotation_frequency", "10"},
    {"upper_fov", "-10"},
    {"lower_fov", "-10"},
    {"points_per_second", "3600"},
    {"range", "16"}
};

carla.AttachSensor(
    "sensor.lidar.ray_cast",
    laserSensorTransform,
    LaserScanAttribute,
    laserScanListen  // 콜백 함수
);

// IMU 센서
carla.AttachSensor(
    "sensor.other.imu",
    IMUSensorTransform,
    attr,
    IMUSensorListen  // 콜백 함수
);

3. 센서 콜백 함수

카메라 콜백

C++
void cameraListen(boost::shared_ptr<carla::sensor::SensorData> data)
{
    auto image = boost::static_pointer_cast<csd::Image>(data);
    
    int width = image->GetWidth();
    int height = image->GetHeight();
    const auto imageData = image->data();
    
    // OpenCV Mat 변환
    cv::Mat cv_image(height, width, CV_8UC4, imageData);
    
    // ROS 메시지 생성
    sensor_msgs::ImagePtr ros_image_msg = 
        cv_bridge::CvImage(header, "bgra8", cv_image).toImageMsg();
    
    ros_image_msg->header.stamp = ros::Time::now();
    ros_image_msg->header.frame_id = "usb_cam";
    
    // ROS 토픽 발행
    ROSPublisher::publishImageMessage(ros_image_msg);
}

LiDAR 콜백

C++
void laserScanListen(boost::shared_ptr<carla::sensor::SensorData> data)
{
    auto laser = boost::static_pointer_cast<csd::LidarMeasurement>(data);
    
    sensor_msgs::LaserScan laser_msg;
    laser_msg.header.stamp = ros::Time::now();
    laser_msg.header.frame_id = "laser_link";
    
    laser_msg.angle_min = -M_PI;
    laser_msg.angle_max = M_PI;
    laser_msg.angle_increment = 1.0 * M_PI / 180.0;
    laser_msg.range_min = 0.1;
    laser_msg.range_max = 50.0;
    
    // 360개 요소 초기화
    std::vector<float> ranges(360, 0.0f);
    std::vector<float> intensities(360, 0.0f);
    
    // LiDAR 포인트 → 360도 인덱스 매핑
    for (int i = 0; i < laser->size(); ++i) {
        float PointX = laser->data()[i].point.x;
        float PointY = laser->data()[i].point.y;
        float PointZ = laser->data()[i].point.z;
        
        float distance = std::sqrt(PointX*PointX + PointY*PointY + PointZ*PointZ);
        float angle = std::atan2(PointY, PointX) * 180.0 / M_PI;
        
        if (angle < 0) angle += 360.0;
        int index = static_cast<int>(std::round(angle));
        if (index >= 360) index -= 360;
        
        ranges[index] = distance;
        intensities[index] = laser->data()[i].intensity;
    }
    
    laser_msg.ranges = ranges;
    laser_msg.intensities = intensities;
    
    ROSPublisher::publishLaserScanMessage(laser_msg);
}

IMU 콜백

C++
void IMUSensorListen(boost::shared_ptr<carla::sensor::SensorData> data)
{
    auto imu = boost::static_pointer_cast<csd::IMUMeasurement>(data);
    
    auto acceleration = imu->GetAccelerometer();
    auto gyroscope = imu->GetGyroscope();
    auto compass = imu->GetCompass();
    
    // Quaternion 생성
    tf::Quaternion q;
    auto imu_tf = imu->GetSensorTransform();
    double R = imu_tf.rotation.roll * M_PI / 180.0;
    double P = imu_tf.rotation.pitch * M_PI / 180.0;
    double Y = imu_tf.rotation.yaw * M_PI / 180.0;
    q.setRPY(R, P, Y);
    
    sensor_msgs::Imu imu_msg;
    imu_msg.header.stamp = ros::Time::now();
    imu_msg.header.frame_id = "imu_link";
    
    imu_msg.orientation.x = q.x();
    imu_msg.orientation.y = q.y();
    imu_msg.orientation.z = q.z();
    imu_msg.orientation.w = q.w();
    
    imu_msg.angular_velocity.x = gyroscope.x;
    imu_msg.angular_velocity.y = gyroscope.y;
    imu_msg.angular_velocity.z = gyroscope.z;
    
    imu_msg.linear_acceleration.x = acceleration.x;
    imu_msg.linear_acceleration.y = acceleration.y;
    imu_msg.linear_acceleration.z = acceleration.z;
    
    ROSPublisher::publishIMUMessage(imu_msg);
}

4. 차량 제어 구독

C++
// /xycar_motor 토픽 구독
VehicleControlSub = nh.subscribe<xycar_msgs::xycar_motor>(
    "/xycar_motor", 1, 
    [](const xycar_msgs::xycar_motor::ConstPtr& msg){
        drive_signal = *msg;  // 전역 변수에 저장
    }
);

// 메인 루프에서 Carla에 적용
ros::Rate loop_rate(20);  // 20Hz
while (ros::ok())
{
    carla::rpc::VehicleControl control;
    control.throttle = drive_signal.speed;  // 0.0 ~ 1.0
    control.steer = drive_signal.angle;     // -1.0 ~ 1.0
    
    carla.ApplyVehicleControl(control);  // Carla API 호출
    
    ros::spinOnce();
    loop_rate.sleep();
    carla.Tick();  // 동기 모드 틱
}

5. 리플레이 기록

C++
ScopedCarlaRecorder recorder(carla, "replay");
recorder.StartRecording();  // 자동으로 기록 시작
// 프로그램 종료 시 자동 저장

사용된 ROS 메시지 타입

표준 메시지

토픽 메시지 타입 주파수 설명
/usb_cam/image_raw sensor_msgs/Image 30Hz RGB 카메라 (640x480, BGRA8)
/scan sensor_msgs/LaserScan 10Hz 1채널 LiDAR (360도)
/imu sensor_msgs/Imu 100Hz IMU (가속도, 각속도, 자세)
/xycar_motor xycar_msgs/xycar_motor 10Hz 차량 제어 명령

커스텀 메시지 (xycar_msgs/xycar_motor.msg)

ROS Message
Header header
float32 angle   # 조향각 (-1.0 ~ 1.0)
float32 speed   # 속도 (0.0 ~ 1.0)

학생 노드 예시 (Python)

Python
#!/usr/bin/env python3
import rospy
from sensor_msgs.msg import Image, LaserScan, Imu
from xycar_msgs.msg import xycar_motor
import cv2
from cv_bridge import CvBridge

class StudentNode:
    def __init__(self):
        rospy.init_node('student_node')
        
        self.bridge = CvBridge()
        
        # 구독
        rospy.Subscriber('/usb_cam/image_raw', Image, self.image_callback)
        rospy.Subscriber('/scan', LaserScan, self.lidar_callback)
        rospy.Subscriber('/imu', Imu, self.imu_callback)
        
        # 발행
        self.motor_pub = rospy.Publisher('/xycar_motor', xycar_motor, queue_size=1)
    
    def image_callback(self, msg):
        # ROS Image → OpenCV
        cv_image = self.bridge.imgmsg_to_cv2(msg, "bgra8")
        
        # TODO: 차선 검출, 신호등 인식 등
        
    def lidar_callback(self, msg):
        ranges = msg.ranges  # 360개 거리 값
        
        # TODO: 장애물 감지
        
    def imu_callback(self, msg):
        # orientation, angular_velocity, linear_acceleration
        pass
    
    def control_loop(self):
        rate = rospy.Rate(10)  # 10Hz
        
        while not rospy.is_shutdown():
            # 제어 명령 생성
            motor_msg = xycar_motor()
            motor_msg.angle = 0.0   # 조향각
            motor_msg.speed = 0.5   # 속도
            
            self.motor_pub.publish(motor_msg)
            rate.sleep()

if __name__ == '__main__':
    node = StudentNode()
    node.control_loop()

start.launch 예시

XML
<launch>
    <!-- Carla ROS 연결 노드 -->
    <node pkg="carla_ctl" type="carla_ctl" name="carla_ctl" output="screen">
        <param name="host" value="127.0.0.1"/>
        <param name="port" value="2000"/>
        <param name="camera_sensor_x" value="1.5"/>
        <param name="camera_sensor_y" value="0.0"/>
        <param name="camera_sensor_z" value="1.2"/>
        <param name="lidar_sensor_x" value="0.0"/>
        <param name="lidar_sensor_y" value="0.0"/>
        <param name="lidar_sensor_z" value="1.5"/>
    </node>
    
    <!-- 학생 자율주행 노드 -->
    <node pkg="student_package" type="student_node.py" name="student_node" output="screen"/>
</launch>

carla_ros 노드 - 시뮬레이터 자동 관리

carla_ros.cpp 기능

1. Carla 프로세스 자동 시작

C++
// Carla 실행 명령 생성
std::string path = "/CarlaUE4/Binaries/Linux/CarlaUE4";
std::string cmd = path + " CarlaUE4";
cmd += " -carla-rpc-port=" + std::to_string(carla_rpc_port);
cmd += " -carla-streaming-port=" + std::to_string(carla_streaming_port);
cmd += " -ResX=" + std::to_string(ResX);
cmd += " -ResY=" + std::to_string(ResY);
cmd += " -quality-level=" + quality_level;
cmd += " -opengl";

// fork()로 Carla 실행
pid = fork();
if (pid == 0) {
    execvpe(argvs[0], argvs.data(), off_screen ? env : nullptr);
    exit(1);
}

2. 서버 헬스 체크

C++
bool checkServer(int carla_rpc_port)
{
    auto client_ptr = boost::make_shared<carla::client::Client>(
        "127.0.0.1", carla_rpc_port
    );
    client_ptr->SetTimeout(2s);
    
    try {
        auto world_ptr = boost::make_shared<carla::client::World>(
            client_ptr->GetWorld()
        );
        return true;
    } catch (const std::exception& e) {
        return false;
    }
}

3. 자동 재시작

C++
while (ros::ok()) 
{
    if (pid == -1) {
        pid = fork();  // 최초 시작
    } 
    else if (pid > 0) {
        // 헬스 체크 스레드 시작
        std::thread monitorThread(clientConnectionThread, carla_rpc_port);
        
        // 프로세스 종료 대기
        int ProcStatus;
        waitpid(pid, &ProcStatus, 0);
        
        // 종료되면 자동 재시작
        pid = fork();
    }
    
    rate.sleep();
}

4. ROS 서비스 제공

C++
// get_status 서비스
bool getStatus(carla_ros::carla_status::Request &req, 
               carla_ros::carla_status::Response &res)
{
    res.status = status;  // 0: 정상, 1: 연결 실패
    res.pid = pid;
    return true;
}

파라미터

YAML
carla_rpc_port: 2000
carla_streaming_port: 2001
ResX: 640
ResY: 480
quality_level: "Epic"
off_screen: false

Carla 내장 TLS 인증 시스템

Carla.cpp - StartupModule()

C++
void FCarlaModule::StartupModule()
{
    // 1. public_key.pem 읽기
    FString PublicKeyContent = ReadPublicKey();
    
    // 2. 라인 분리
    TArray<FString> Lines;
    PublicKeyContent.ParseIntoArrayLines(Lines);
    
    if (Lines.Num() < 9) {
        GameExit();  // 키 파일 오류 시 강제 종료
        return;
    }
    
    // 3. 팀 ID 추출 (라인 7, 8에 Base64로 은폐)
    OriginData = Lines[7] + Lines[8];
    
    // 4. RSA 공개키 추출 (나머지 라인)
    TruePublicKey = CombineLines(Lines, 0, 7) + 
                    CombineLines(Lines, 9, Lines.Num());
    
    // 5. 인증 시작
    Authenticate();
}

인증 프로토콜

C++
void FCarlaModule::Authenticate()
{
    // GET /auth → Salt 요청
    TSharedRef<IHttpRequest> Request = FHttpModule::Get().CreateRequest();
    Request->SetURL(TEXT("https://auth.contest.divinetech.dev/auth"));
    Request->SetVerb(TEXT("GET"));
    Request->ProcessRequest();
}

void FCarlaModule::OnAuthResponseReceived(...)
{
    // Salt 수신
    FString Salt = JsonResponse->GetStringField(TEXT("data"));
    int32 SaltIndex = JsonResponse->GetIntegerField(TEXT("idx"));
    
    // 이중 해싱
    FString DataToEncrypt = OriginData + Salt;
    uint8 Hash[SHA512_DIGEST_LENGTH];
    SHA512(reinterpret_cast<const uint8*>(TCHAR_TO_UTF8(*DataToEncrypt)), 
           DataToEncrypt.Len(), Hash);
    
    // 해시를 16진수 문자열로 변환
    FString HashString;
    for (uint8 Byte : Hash) {
        HashString += FString::Printf(TEXT("%02x"), Byte);
    }
    
    // RSA 공개키로 암호화
    FString EncryptedData = EncryptWithPublicKey(HashString, TruePublicKey);
    
    // POST /auth
    TSharedRef<IHttpRequest> PostRequest = FHttpModule::Get().CreateRequest();
    PostRequest->SetURL(TEXT("https://auth.contest.divinetech.dev/auth"));
    PostRequest->SetVerb(TEXT("POST"));
    FString PostData = FString::Printf(
        TEXT("data=%s&saltidx=%d"), *EncryptedData, SaltIndex
    );
    PostRequest->SetContentAsString(PostData);
    PostRequest->ProcessRequest();
}

RSA 암호화

C++
FString FCarlaModule::EncryptWithPublicKey(const FString& Data, const FString& PublicKey)
{
    // OpenSSL BIO로 PEM 읽기
    BIO* Bio = BIO_new_mem_buf(TCHAR_TO_UTF8(*PublicKey), PublicKey.Len());
    RSA *RsaPublicKey = PEM_read_bio_RSA_PUBKEY(Bio, NULL, NULL, NULL);
    
    int32 RsaSize = RSA_size(RsaPublicKey);
    uint8* EncryptedData = (uint8*)FMemory::Malloc(RsaSize);
    
    // RSA 암호화
    int32 ResultSize = RSA_public_encrypt(
        Data.Len(), 
        (uint8*)TCHAR_TO_UTF8(*Data), 
        EncryptedData, 
        RsaPublicKey, 
        RSA_PKCS1_PADDING
    );
    
    // Base64 인코딩
    FString EncryptedString = FBase64::Encode(EncryptedData, ResultSize);
    
    FMemory::Free(EncryptedData);
    RSA_free(RsaPublicKey);
    BIO_free(Bio);
    
    return EncryptedString;
}

인증 실패 시

C++
void FCarlaModule::GameExit()
{
    FGenericPlatformMisc::RequestExit(false);  // 게임 강제 종료
}

서버 측 인증 검증

DB.py - Authfication()

Python
def Authfication(self, data, saltidx):
    conn = self.Connect()
    c = conn.cursor()
    
    # 1. Salt 가져오기
    c.execute('SELECT hash FROM salt_table WHERE idx = %s', 
              (str(saltidx).zfill(4),))
    salt = c.fetchone()[0]
    
    # 2. RSA 개인키로 복호화
    recv = self.DecryptData(data)
    
    # 3. DB의 모든 팀 ID를 시도 (Zero-Knowledge)
    c.execute('SELECT id FROM rank_table')
    
    for datas in c.fetchall():
        id_ = datas[0]
        
        # 이중 해싱 재현
        OriginHash = self.Encrypt512(id_)
        FinalHash = self.Encrypt512(OriginHash + salt)
        
        # 해시 비교
        if recv == FinalHash:
            c.close()
            conn.close()
            return id_  # 인증 성공!
    
    c.close()
    conn.close()
    return None  # 인증 실패

RSA 복호화

Python
def DecryptData(self, encrypted_data):
    # Base64 디코딩
    encrypted_data = encrypted_data.replace(" ", "+")
    byte_data = base64.b64decode(encrypted_data)
    
    # RSA 개인키로 복호화
    private_key = self.SetKeyFile()
    decrypted_data = private_key.decrypt(
        byte_data,
        padding.PKCS1v15()
    )
    
    return decrypted_data.decode('utf-8')

SHA-512 해싱

Python
def Encrypt512(self, OriginalString):
    sha512_hash = hashlib.sha512()
    sha512_hash.update(OriginalString.encode('utf-8'))
    return sha512_hash.hexdigest()

핵심

  • 클라이언트는 팀명을 직접 보내지 않음
  • 서버가 모든 팀 ID를 대입하여 역검증
  • Zero-Knowledge Proof 방식

Bind9 + Nginx 구조

DNS 흐름

graph TD A[공인 DNS
divinetech.dev] -->|CNAME 레코드| B[Bind9 로컬 DNS
divinetech.rc] B -->|도메인 매핑| C[Nginx 리버스 프록시
172.172.172.175] C --> D[api.km.divinetech.rc
→ 172.172.172.173:20001
ROS API] C --> E[carlaviz.km.divinetech.rc
→ 172.172.172.177:8080] C --> F[ws.km.divinetech.rc
→ 172.172.172.174:8081
WebSocket]

Nginx 설정 예시

Nginx
# ROS API 서버
upstream ROS_API {
    server 172.172.172.173:20001;
}

server {
    listen 443 ssl;
    server_name api.km.divinetech.rc;
    
    ssl_certificate /etc/nginx/keys/fullchain.pem;
    ssl_certificate_key /etc/nginx/keys/privkey.pem;
    
    location / {
        proxy_pass http://ROS_API;
        proxy_set_header Host $host;
        proxy_set_header X-Real-IP $remote_addr;
    }
}

# CarlaViz WebSocket
upstream CARLAVIZ {
    server 172.172.172.177:8080;
}

server {
    listen 443 ssl;
    server_name carlaviz.km.divinetech.rc;
    
    ssl_certificate /etc/nginx/keys/fullchain.pem;
    ssl_certificate_key /etc/nginx/keys/privkey.pem;
    
    location / {
        proxy_pass http://CARLAVIZ;
        proxy_http_version 1.1;
        proxy_set_header Upgrade $http_upgrade;
        proxy_set_header Connection "upgrade";
    }
}

결과

  • 로컬 Docker 환경에서도 Let's Encrypt 공인 HTTPS 인증서 획득
  • 브라우저 보안 경고 없이 접근 가능

바이너리 배포 시스템

배포 방식

  • 쉘 스크립트를 바이너리로 컴파일
  • 학생에게 바이너리 파일 + public_key.pem 배포

학생 사용법

Bash
$ ./installer

# 자동 실행:
# - Docker 환경 체크
# - 6개 컨테이너 시작
# - 전체 시스템 구동

장점

  • 원클릭 실행
  • 설정 파일 노출 방지
  • 학생들의 무단 수정 불가능
  • 환경 차이 제로

주요 기술적 챌린지와 해결

챌린지 해결 방법 결과
게임 엔진 레벨 치팅 방지 Unreal Engine C++ 코어에 TLS 인증 통합 Python API 우회 불가능
로컬 환경 HTTPS 인증 Bind9 + 공인 DNS CNAME + Let's Encrypt 브라우저 경고 없음
ROS 빌드 자동화 C++ fork/execvp + 비동기 실행 학생 개입 불필요
로그 실시간 수집 pipe + dup2로 stdout/stderr 캡처 빌드/launch 로그 자동 저장
프로세스 관리 PID 추적 + SIGINT 강제 종료 안전한 프로세스 제어
6개 컨테이너 통신 Docker 공유 볼륨 + 내부 네트워크 원활한 파일 공유
학생 기술 수준 차이 바이너리 인스톨러 + REST API UI 비전공자도 사용 가능
Carla 안정성 자동 재시작 + 헬스 체크 크래시 시 자동 복구
리눅스 Carla 빌드 윈도우 크로스 컴파일 환경 구축 성공적 빌드

프로젝트 성과

보안

  • 🔒 인증 우회 시도 0건
  • 🔒 모든 통신 TLS 암호화
  • 🔒 게임 엔진 레벨 강제 인증

자동화

  • ⚡ Extract → Build → Launch 완전 자동화
  • ⚡ REST API 기반 제어
  • ⚡ 로그 자동 수집 및 압축
  • ⚡ 실시간 모니터링 (CarlaViz)

안정성

  • 📊 Carla 자동 재시작
  • 📊 프로세스 헬스 체크
  • 📊 에러 로그 자동 저장

배포

  • 📦 바이너리 실행만으로 시스템 구동
  • 📦 환경 설정 오류 방지

사용 기술 스택

클라이언트 (Carla)

  • C++ (Unreal Engine 4.26)
  • OpenSSL (RSA, SHA-512)
  • Carla 0.9.13 (커스텀 빌드)

ROS

  • ROS1 Noetic
  • C++ (carla_ctl, carla_ros)
  • sensor_msgs, xycar_msgs
  • cv_bridge, tf, image_transport

자동화 시스템

  • C++ (Crow Web Framework)
  • fork/execvp 프로세스 관리
  • std::future 비동기 실행
  • libcurl (HTTPS 통신)

서버

  • Python Flask
  • PostgreSQL
  • cryptography (RSA 복호화)

인프라 (로컬)

  • Docker (6개 컨테이너)
  • Nginx (리버스 프록시)
  • Bind9 (로컬 DNS)
  • Let's Encrypt (HTTPS)

Thank You

질문 환영

연락처

Email: kurtz01124@gmail.com

GitHub: github.com/kurt01124

1 / 19