서비스 가용성 확인 조건 노드 (Service Availability Check Condition Node)
1. 개요
서비스 가용성 확인 조건 노드는 특정 ROS2 서비스 서버가 현재 가용한 상태인지를 판정하는 조건 노드이다. 서비스를 실제로 호출하지 않고, 서비스 서버의 존재 여부와 응답 준비 상태만을 확인한다. 이 조건 노드는 서비스 호출을 수행하는 액션 노드의 전제 조건으로 활용되어, 서버가 가용하지 않은 상태에서의 불필요한 호출 시도를 방지하고, 시스템 구성 요소의 건전성을 모니터링하는 데 사용된다.
2. 서비스 가용성의 정의
2.1 ROS2 DDS 기반 서비스 발견
ROS2에서 서비스 서버의 가용성은 DDS(Data Distribution Service) 발견(discovery) 프로토콜에 의해 결정된다. 서비스 클라이언트는 DDS 참여자(participant) 간의 통신을 통해 동일한 서비스 이름과 타입을 가진 서버의 존재를 감지한다.
rclcpp::Client<ServiceT>의 service_is_ready() 메서드는 다음 조건을 확인한다.
- 서비스 서버가 DDS 네트워크에 등록되어 있는가.
- 서비스 서버의 요청 수신 엔드포인트가 활성 상태인가.
이 메서드는 비차단(non-blocking) 호출로, 즉시 true 또는 false를 반환하므로 조건 노드의 빠른 평가 원칙에 부합한다.
2.2 가용성 상태 분류
| 상태 | service_is_ready() 결과 | 조건 노드 반환 |
|---|---|---|
| 서버가 존재하고 활성 상태 | true | SUCCESS |
| 서버가 존재하지 않음 | false | FAILURE |
| 서버가 종료됨 | false | FAILURE |
| DDS 발견이 완료되지 않음 | false | FAILURE |
3. 기본 구현
3.1 단일 서비스 가용성 확인
template <typename ServiceT>
class IsServiceAvailable : public BT::ConditionNode
{
public:
IsServiceAvailable(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config), node_(node)
{
std::string service_name;
getInput("service_name", service_name);
client_ = node_->create_client<ServiceT>(service_name);
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("service_name",
"확인할 서비스 이름")
};
}
BT::NodeStatus tick() override
{
if (client_->service_is_ready())
{
return BT::NodeStatus::SUCCESS;
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
typename rclcpp::Client<ServiceT>::SharedPtr client_;
};
이 구현은 매우 간결하며, tick() 메서드는 service_is_ready() 호출 결과만을 반환한다. 서비스를 실제로 호출하지 않으므로 부작용이 발생하지 않으며, 비차단 호출이므로 빠른 평가가 보장된다.
3.2 서비스 타입에 독립적인 구현
위 구현은 템플릿 매개변수로 서비스 타입을 요구하므로, 서비스 타입마다 별도의 인스턴스를 등록하여야 한다. 서비스 타입에 독립적으로 가용성만을 확인하고자 하는 경우, rclcpp::Node의 그래프 인터페이스를 활용할 수 있다.
class IsServiceAvailableGeneric : public BT::ConditionNode
{
public:
IsServiceAvailableGeneric(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config), node_(node)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("service_name",
"확인할 서비스 이름")
};
}
BT::NodeStatus tick() override
{
std::string service_name;
getInput("service_name", service_name);
auto service_names_and_types =
node_->get_service_names_and_types();
for (const auto& [name, types] : service_names_and_types)
{
if (name == service_name)
{
return BT::NodeStatus::SUCCESS;
}
}
return BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
};
get_service_names_and_types() 메서드는 현재 DDS 네트워크에서 발견된 모든 서비스의 이름과 타입을 반환한다. 이 방법은 서비스 타입을 알지 못하더라도 서비스의 존재를 확인할 수 있으나, DDS 발견 메커니즘에 의존하므로 약간의 지연이 존재할 수 있다.
4. 다중 서비스 가용성 확인
4.1 Sequence 기반 다중 서비스 확인
복수의 서비스가 모두 가용한지를 확인하기 위해 개별 조건 노드를 Sequence로 결합한다.
<BehaviorTree ID="SystemReadyCheck">
<Sequence name="AllServicesReady">
<Condition ID="IsServiceAvailable"
service_name="/map_server/map"/>
<Condition ID="IsServiceAvailable"
service_name="/controller_server/get_state"/>
<Condition ID="IsServiceAvailable"
service_name="/planner_server/get_state"/>
<Action ID="StartMission"/>
</Sequence>
</BehaviorTree>
Sequence 노드의 특성에 의해, 어느 하나의 서비스라도 가용하지 않으면 이후 노드의 평가가 중단되고 전체 시퀀스가 FAILURE를 반환한다.
4.2 단일 노드 내 다중 서비스 확인
복수의 서비스 이름을 입력 포트로 받아 단일 노드에서 확인하는 방식이다.
class AreServicesAvailable : public BT::ConditionNode
{
public:
AreServicesAvailable(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config), node_(node)
{}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("service_names",
"세미콜론으로 구분된 서비스 이름 목록")
};
}
BT::NodeStatus tick() override
{
std::string service_names_str;
getInput("service_names", service_names_str);
auto available_services =
node_->get_service_names_and_types();
std::istringstream stream(service_names_str);
std::string service_name;
while (std::getline(stream, service_name, ';'))
{
bool found = false;
for (const auto& [name, types] : available_services)
{
if (name == service_name)
{
found = true;
break;
}
}
if (!found)
{
return BT::NodeStatus::FAILURE;
}
}
return BT::NodeStatus::SUCCESS;
}
private:
rclcpp::Node::SharedPtr node_;
};
<Condition ID="AreServicesAvailable"
service_names="/map_server/map;/planner/get_state;/controller/get_state"/>
5. 캐싱 기반 가용성 확인
service_is_ready()나 get_service_names_and_types()의 호출은 DDS 질의를 수반하므로, 매 tick마다 반복 호출하면 불필요한 오버헤드가 발생할 수 있다. 시간 기반 캐싱을 적용하여 호출 빈도를 제한한다.
template <typename ServiceT>
class IsServiceAvailableCached : public BT::ConditionNode
{
public:
IsServiceAvailableCached(const std::string& name,
const BT::NodeConfiguration& config,
rclcpp::Node::SharedPtr node)
: BT::ConditionNode(name, config),
node_(node),
cached_available_(false),
has_cache_(false)
{
std::string service_name;
getInput("service_name", service_name);
client_ = node_->create_client<ServiceT>(service_name);
}
static BT::PortsList providedPorts()
{
return {
BT::InputPort<std::string>("service_name",
"확인할 서비스 이름"),
BT::InputPort<double>("cache_duration_sec", 5.0,
"캐시 유효 기간 (초)")
};
}
BT::NodeStatus tick() override
{
double cache_duration;
getInput("cache_duration_sec", cache_duration);
auto now = node_->get_clock()->now();
if (has_cache_)
{
double elapsed = (now - cache_time_).seconds();
if (elapsed < cache_duration)
{
return cached_available_ ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
}
cached_available_ = client_->service_is_ready();
cache_time_ = now;
has_cache_ = true;
return cached_available_ ? BT::NodeStatus::SUCCESS
: BT::NodeStatus::FAILURE;
}
private:
rclcpp::Node::SharedPtr node_;
typename rclcpp::Client<ServiceT>::SharedPtr client_;
bool cached_available_;
bool has_cache_;
rclcpp::Time cache_time_;
};
서비스 가용성은 일반적으로 초 단위 이상의 시간 동안 유지되므로, 5초 정도의 캐시 유효 기간이 적절하다. 다만, 시스템 초기화 직후나 장애 발생 시에는 가용성이 빈번히 변경될 수 있으므로, 상황에 따라 캐시 유효 기간을 조정하여야 한다.
6. XML 행동 트리에서의 활용
6.1 서비스 호출 전 가용성 전제 조건
서비스를 호출하는 액션 노드 앞에 가용성 확인 조건 노드를 배치하여, 서버가 가용한 경우에만 호출을 시도한다.
<BehaviorTree ID="SafeServiceCall">
<Sequence>
<Condition ID="IsServiceAvailable"
service_name="/compute_path_to_pose"/>
<Action ID="ComputePathToPose"
service_name="/compute_path_to_pose"
goal="{target_pose}"
path="{computed_path}"/>
</Sequence>
</BehaviorTree>
6.2 Fallback 기반 대체 서비스 선택
주 서비스가 가용하지 않은 경우 대체 서비스를 사용하는 패턴이다.
<BehaviorTree ID="FallbackService">
<Fallback>
<Sequence>
<Condition ID="IsServiceAvailable"
service_name="/planner_primary/compute_path"/>
<Action ID="ComputePath"
service_name="/planner_primary/compute_path"/>
</Sequence>
<Sequence>
<Condition ID="IsServiceAvailable"
service_name="/planner_backup/compute_path"/>
<Action ID="ComputePath"
service_name="/planner_backup/compute_path"/>
</Sequence>
<Action ID="ReportPlannerFailure"/>
</Fallback>
</BehaviorTree>
이 구조에서 Fallback 노드는 첫 번째 자식이 FAILURE를 반환하면 두 번째 자식을 시도한다. 주 경로 계획기가 가용하지 않으면 백업 경로 계획기를 시도하고, 두 서비스 모두 가용하지 않으면 실패 보고 액션을 실행한다.
6.3 시스템 초기화 대기 패턴
시스템 시작 후 필수 서비스가 모두 가용해질 때까지 대기하는 패턴이다.
<BehaviorTree ID="WaitForServices">
<RetryNode num_attempts="60">
<Sequence>
<Condition ID="IsServiceAvailable"
service_name="/map_server/map"/>
<Condition ID="IsServiceAvailable"
service_name="/amcl/get_state"/>
<Action ID="InitializeNavigation"/>
</Sequence>
</RetryNode>
</BehaviorTree>
RetryNode 데코레이터는 자식 노드가 FAILURE를 반환하면 지정된 횟수만큼 재시도한다. 행동 트리의 tick 주기가 1초인 경우, 60회 재시도는 최대 60초 동안 서비스가 가용해지기를 대기하는 것에 해당한다.
7. 설계 시 고려 사항
7.1 DDS 발견 지연
ROS2 노드가 시작된 직후에는 DDS 발견 프로토콜이 완료되기까지 수백 밀리초에서 수 초의 지연이 발생할 수 있다. 이 기간 동안 서비스 서버가 실제로 실행 중이더라도 service_is_ready()가 false를 반환할 수 있다. 시스템 초기화 단계에서는 이 지연을 고려하여 충분한 재시도 메커니즘을 적용하여야 한다.
7.2 가용성과 응답 가능성의 차이
service_is_ready()가 true를 반환하더라도, 서비스 서버가 실제로 요청에 올바르게 응답하는지는 보장되지 않는다. 서버가 DDS 네트워크에 등록되어 있으나 내부 상태 오류로 인해 요청을 처리하지 못하는 경우가 존재한다. 따라서 가용성 확인은 필요 조건이나 충분 조건은 아니며, 실제 서비스 호출의 성공 여부는 별도로 처리하여야 한다.
7.3 네임스페이스 고려
ROS2의 서비스 이름은 네임스페이스(namespace)를 포함할 수 있다. 조건 노드에서 서비스 이름을 지정할 때, 절대 경로(예: /robot1/map_server/map)와 상대 경로(예: map_server/map)를 올바르게 구분하여야 한다. 상대 경로는 노드의 네임스페이스에 따라 확장되므로, 다중 로봇 환경에서는 절대 경로를 명시적으로 사용하는 것이 안전하다.
7.4 서비스 클라이언트의 생존 주기
rclcpp::Client 객체는 생성 시 DDS에 클라이언트 엔드포인트를 등록한다. 조건 노드가 소멸되면 클라이언트도 함께 소멸되어 엔드포인트가 해제된다. 행동 트리가 동적으로 교체되는 환경에서는, 클라이언트의 빈번한 생성과 소멸이 DDS 발견 프로토콜에 부하를 줄 수 있으므로, 클라이언트의 생존 주기를 행동 트리와 분리하여 관리하는 방안을 검토할 필요가 있다.
8. 참고 문헌
- Colledanchise, M., & Ogren, P. (2018). Behavior Trees in Robotics and AI: An Introduction. CRC Press.
- Macenski, S., et al. (2020). “The Marathon 2: A Navigation System.” arXiv preprint arXiv:2003.00368.
- BehaviorTree.CPP 공식 문서. https://www.behaviortree.dev/
- ROS2 공식 문서. https://docs.ros.org/en/humble/
| 버전 | 날짜 | 변경 사항 |
|---|---|---|
| v0.1 | 2026-04-04 | 초안 작성 |