모의 ROS2 토픽을 활용한 테스트 (Testing with Mock ROS2 Topics)
1. 개요
모의 ROS2 토픽을 활용한 테스트는 테스트 환경에서 직접 ROS2 토픽 메시지를 발행하여, 토픽 기반 조건 노드의 동작을 검증하는 기법이다. 실제 센서나 다른 노드의 가동 없이도 다양한 메시지 내용과 발행 패턴을 인위적으로 생성하여 조건 노드를 체계적으로 테스트할 수 있다.
2. 테스트 환경 구성
2.1 ROS2 테스트 노드와 발행자 설정
class TopicConditionTest : public ::testing::Test
{
protected:
void SetUp() override
{
rclcpp::init(0, nullptr);
test_node_ = std::make_shared<rclcpp::Node>("test_node");
// 모의 토픽 발행자 생성
scan_pub_ = test_node_->create_publisher<
sensor_msgs::msg::LaserScan>("/scan", 10);
odom_pub_ = test_node_->create_publisher<
nav_msgs::msg::Odometry>("/odom", 10);
// 행동 트리 팩토리 설정
BT::RosNodeParams params;
params.nh = test_node_;
factory_.registerNodeType<IsObstacleDetected>(
"IsObstacleDetected", params);
}
void TearDown() override
{
rclcpp::shutdown();
}
void spinForDelivery(int ms = 100)
{
auto start = std::chrono::steady_clock::now();
while (std::chrono::steady_clock::now() - start <
std::chrono::milliseconds(ms))
{
rclcpp::spin_some(test_node_);
std::this_thread::sleep_for(
std::chrono::milliseconds(1));
}
}
rclcpp::Node::SharedPtr test_node_;
rclcpp::Publisher<sensor_msgs::msg::LaserScan>::SharedPtr scan_pub_;
rclcpp::Publisher<nav_msgs::msg::Odometry>::SharedPtr odom_pub_;
BT::BehaviorTreeFactory factory_;
};
2.2 모의 메시지 생성 헬퍼
sensor_msgs::msg::LaserScan createMockScan(
float min_range = 0.1,
float max_range = 30.0,
float default_value = 5.0,
int num_readings = 360)
{
sensor_msgs::msg::LaserScan msg;
msg.header.stamp = rclcpp::Clock().now();
msg.angle_min = -M_PI;
msg.angle_max = M_PI;
msg.angle_increment = 2 * M_PI / num_readings;
msg.range_min = min_range;
msg.range_max = max_range;
msg.ranges.resize(num_readings, default_value);
return msg;
}
nav_msgs::msg::Odometry createMockOdom(
double x = 0.0, double y = 0.0,
double vx = 0.0, double vy = 0.0)
{
nav_msgs::msg::Odometry msg;
msg.header.stamp = rclcpp::Clock().now();
msg.pose.pose.position.x = x;
msg.pose.pose.position.y = y;
msg.twist.twist.linear.x = vx;
msg.twist.twist.linear.y = vy;
return msg;
}
3. 테스트 구현 예시
3.1 장애물 감지 조건의 토픽 기반 테스트
TEST_F(TopicConditionTest, DetectsObstacleInScan)
{
auto xml = createTreeXml("IsObstacleDetected",
{{"topic_name", "/scan"},
{"detection_range", "1.0"},
{"min_points", "3"}});
auto tree = factory_.createTreeFromText(xml);
// 장애물이 있는 스캔 데이터 생성
auto scan = createMockScan();
scan.ranges[0] = 0.5; // 장애물
scan.ranges[1] = 0.6; // 장애물
scan.ranges[2] = 0.7; // 장애물
scan_pub_->publish(scan);
spinForDelivery();
EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS);
}
TEST_F(TopicConditionTest, NoObstacleInClearScan)
{
auto tree = factory_.createTreeFromText(xml_);
// 장애물이 없는 스캔 데이터
auto scan = createMockScan(0.1, 30.0, 10.0); // 전부 10m
scan_pub_->publish(scan);
spinForDelivery();
EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);
}
3.2 메시지 갱신에 대한 반응 테스트
TEST_F(TopicConditionTest, ReactsToMessageUpdate)
{
auto tree = factory_.createTreeFromText(xml_);
// 1단계: 장애물 없음
scan_pub_->publish(createMockScan(0.1, 30.0, 10.0));
spinForDelivery();
EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);
// 2단계: 장애물 출현
auto scan = createMockScan();
scan.ranges[90] = 0.3;
scan.ranges[91] = 0.4;
scan.ranges[92] = 0.5;
scan_pub_->publish(scan);
spinForDelivery();
EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::SUCCESS);
// 3단계: 장애물 소멸
scan_pub_->publish(createMockScan(0.1, 30.0, 10.0));
spinForDelivery();
EXPECT_EQ(tree.tickOnce(), BT::NodeStatus::FAILURE);
}
3.3 QoS 호환성 테스트
TEST_F(TopicConditionTest, WorksWithSensorDataQoS)
{
// SensorDataQoS (BEST_EFFORT)로 발행
auto pub = test_node_->create_publisher<
sensor_msgs::msg::LaserScan>(
"/scan", rclcpp::SensorDataQoS());
pub->publish(createMockScan());
spinForDelivery();
// 조건 노드의 구독자 QoS와 호환되는지 확인
auto status = tree_.tickOnce();
EXPECT_NE(status, BT::NodeStatus::FAILURE);
}
4. 설계 시 고려 사항
4.1 DDS 발견 지연
테스트 내에서 발행자와 구독자가 거의 동시에 생성되면, DDS 발견 프로토콜이 완료되지 않아 첫 번째 메시지가 전달되지 않을 수 있다. spinForDelivery()에서 충분한 대기 시간을 설정하거나, 발행-구독 쌍이 연결된 것을 확인하는 동기화 로직을 추가한다.
4.2 테스트의 결정적 실행
ROS2의 비동기 통신 특성으로 인해 테스트 결과가 비결정적일 수 있다. 메시지 전달을 보장하기 위해 재시도 로직이나 조건부 대기를 적용한다.
4.3 테스트 격리
각 테스트에서 사용하는 토픽 이름이 다른 테스트와 충돌하지 않도록 하여야 한다. 고유한 토픽 이름을 사용하거나, 각 테스트에서 rclcpp::init()/shutdown() 쌍을 실행하여 DDS 참여자를 격리한다.
5. 참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
- ROS2 테스트 가이드. https://docs.ros.org/en/humble/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |