1296.36 포트의 기본값 설정

1. 기본값의 개념과 역할

포트의 기본값(default value)은 XML 트리 정의에서 해당 포트의 값이 명시적으로 지정되지 않은 경우에 사용되는 사전 정의된 값이다. BehaviorTree.CPP 라이브러리에서 기본값은 InputPort<T>BidirectionalPort<T>의 선언 시 두 번째 인자로 문자열 형식으로 지정된다. OutputPort<T>에는 기본값의 개념이 적용되지 않는다.

기본값의 설정은 노드의 사용 편의성과 파라미터화 간의 균형을 달성하는 수단이다. 기본값이 적절히 설정된 포트는 XML에서의 지정이 선택적이 되어, 대부분의 사용 사례에서 간결한 XML 정의를 가능하게 한다(Faconti, 2022).

2. 기본값의 선언 구문

2.1 InputPort의 기본값

// 기본값 없음 (필수 포트)
BT::InputPort<T>(포트명, 설명)

// 기본값 있음 (선택적 포트)
BT::InputPort<T>(포트명, 기본값_문자열, 설명)
static BT::PortsList providedPorts()
{
    return {
        // 필수: 기본값 없음
        BT::InputPort<geometry_msgs::msg::PoseStamped>(
            "goal_pose",
            "내비게이션 목표 위치"),

        // 선택적: 기본값 "30.0"
        BT::InputPort<double>(
            "timeout_sec",
            "30.0",
            "타임아웃 (초)"),

        // 선택적: 기본값 "navigate_to_pose"
        BT::InputPort<std::string>(
            "server_name",
            "navigate_to_pose",
            "액션 서버 이름"),

        // 선택적: 기본값 "true"
        BT::InputPort<bool>(
            "allow_replanning",
            "true",
            "재계획 허용 여부")
    };
}

2.2 BidirectionalPort의 기본값

BT::BidirectionalPort<T>(포트명, 기본값_문자열, 설명)
BT::BidirectionalPort<int>(
    "retry_count",
    "0",
    "현재 재시도 횟수")

3. 기본값의 해석 과정

기본값이 설정된 포트에서 getInput() 호출 시의 값 해석 과정을 기술한다.

getInput("timeout_sec", timeout)
    │
    ├─ XML에서 값이 지정되었는가?
    │       │
    │       ├─ 예: XML 값 사용
    │       │       │
    │       │       ├─ "{key}" 형식 → 블랙보드 키 조회
    │       │       │
    │       │       └─ 리터럴 값 → convertFromString<T>()
    │       │
    │       └─ 아니오: 기본값 사용
    │               │
    │               └─ convertFromString<T>("30.0") → timeout = 30.0
    │
    └─ 결과: 성공 또는 실패

기본값은 XML의 명시적 지정보다 항상 낮은 우선순위를 가진다. XML에서 값이 지정되면 기본값은 무시된다.

3.1 우선순위

우선순위값의 출처조건
1 (최고)XML 블랙보드 키 참조port="{key}" 지정 시
2XML 리터럴 값port="value" 지정 시
3포트 기본값XML에서 미지정 시
4 (최저)없음 (실패)기본값도 없는 경우

4. 기본값의 타입 변환

기본값은 문자열 형식으로 선언되며, getInput() 호출 시 convertFromString<T>()를 통해 대상 타입으로 변환된다.

4.1 기본 타입의 변환

타입기본값 문자열 예시변환 결과
int"0"0
double"30.0"30.0
bool"true"true
std::string"navigate_to_pose""navigate_to_pose"
unsigned"5"5

4.2 사용자 정의 타입의 변환

사용자 정의 타입의 기본값은 해당 타입에 등록된 convertFromString<T>() 함수에 의해 변환된다.

// Pose2D에 대한 변환 함수가 등록된 경우
BT::InputPort<Pose2D>(
    "home_pose",
    "0.0;0.0;0.0",
    "기본 위치 (x;y;theta)")

변환 함수가 등록되지 않은 타입에 대해 문자열 기본값을 지정하면, getInput() 호출 시 변환 실패가 발생한다. 이 경우 블랙보드 키 참조를 통해 기본값을 제공하는 방법을 고려한다.

5. 기본값 설계의 원칙

5.1 안전성 우선

기본값은 시스템의 안전을 해치지 않는 보수적인 값이어야 한다. 특히 물리적 행동에 영향을 미치는 파라미터의 기본값은 최소한의 위험을 가지는 값으로 설정한다.

// 안전한 기본값 설정
BT::InputPort<double>(
    "linear_speed", "0.3",
    "목표 선속도 (m/s, 기본: 0.3)")  // 안전한 저속

BT::InputPort<double>(
    "angular_speed", "0.3",
    "목표 각속도 (rad/s, 기본: 0.3)")  // 안전한 저속

BT::InputPort<double>(
    "timeout_sec", "30.0",
    "타임아웃 (초, 기본: 30.0)")  // 충분한 여유

5.2 일반적 사용 사례의 반영

기본값은 가장 빈번한 사용 사례에 적합한 값이어야 한다.

// ROS2 인터페이스의 관례적 이름
BT::InputPort<std::string>(
    "server_name", "navigate_to_pose",
    "액션 서버 이름")

// Nav2의 관례적 좌표계
BT::InputPort<std::string>(
    "frame_id", "map",
    "좌표계 프레임")

5.3 무해성(Harmlessness)

기본값이 사용되더라도 시스템이 예기치 않은 행동을 수행하지 않아야 한다.

// 적절: 기본 비활성화 (명시적 활성화 필요)
BT::InputPort<bool>(
    "enable_recovery", "false",
    "복구 행동 활성화 여부")

// 부적절: 기본 활성화 (의도치 않은 복구 발생 가능)
BT::InputPort<bool>(
    "enable_recovery", "true",
    "복구 행동 활성화 여부")

5.4 문서화 연동

기본값을 포트의 설명에 포함하여, XML 작성자가 기본값을 쉽게 확인할 수 있게 한다.

BT::InputPort<double>(
    "tolerance",
    "0.1",
    "위치 허용 오차 (미터, 기본: 0.1)")

6. 기본값이 적합한 파라미터와 부적합한 파라미터

파라미터 유형기본값 적합성이유
타임아웃적합일반적 기준값 존재
허용 오차적합도메인별 표준값 존재
ROS2 인터페이스 이름적합관례적 이름 존재
속도 제한적합안전한 기본 속도 설정 가능
좌표계 프레임적합관례적 프레임 존재 (“map”, “base_link”)
목표 위치/자세부적합임무별로 다름, 범용적 기본값 없음
객체 식별자부적합컨텍스트별로 다름
경로 데이터부적합동적으로 생성됨
센서 데이터부적합실시간으로 변경됨

7. 빈 문자열 기본값

빈 문자열("")을 기본값으로 설정하여, 선택적 문자열 파라미터의 미지정을 표현할 수 있다.

BT::InputPort<std::string>(
    "behavior_tree", "",
    "사용할 행동 트리 파일 (빈 문자열: 서버 기본값)")

노드 내부에서 빈 문자열을 검출하여 기본 동작을 적용한다.

BT::NodeStatus onStart() override
{
    std::string bt_file;
    getInput("behavior_tree", bt_file);

    if (bt_file.empty())
    {
        // 기본 행동 트리 사용
    }
    else
    {
        // 지정된 행동 트리 사용
    }
    // ...
}

8. 기본값과 XML 지정의 상호 작용

기본값이 설정된 포트에 대한 XML 지정의 다양한 경우를 정리한다.

// 포트 선언: 기본값 "30.0"
BT::InputPort<double>("timeout_sec", "30.0", "타임아웃 (초)")
XML 지정getInput() 결과설명
timeout_sec="60.0"60.0XML 리터럴 값 사용
timeout_sec="{t}"블랙보드 “t“의 값블랙보드 키 참조
(미지정)30.0기본값 사용

9. 기본값의 변경과 호환성

기본값의 변경은 기존 XML 트리 정의의 동작에 영향을 미칠 수 있다. 기본값에 의존하여 포트를 생략한 XML 트리는 기본값의 변경에 의해 암묵적으로 동작이 변경된다.

// 변경 전: 기본 타임아웃 30초
BT::InputPort<double>("timeout_sec", "30.0", "타임아웃 (초)")

// 변경 후: 기본 타임아웃 60초
BT::InputPort<double>("timeout_sec", "60.0", "타임아웃 (초)")

이 변경에 의해 timeout_sec를 명시하지 않은 모든 XML 트리의 타임아웃이 30초에서 60초로 변경된다. 따라서 기본값의 변경은 하위 호환성(backward compatibility)에 주의하여 수행하여야 한다.

10. 설계 지침

  1. 구성 파라미터에 기본값 제공: 타임아웃, 허용 오차, 인터페이스 이름 등 구성적 파라미터에는 합리적 기본값을 설정하여 XML을 간결하게 한다.

  2. 행동 파라미터에 기본값 지양: 목표 위치, 대상 객체 등 임무별로 달라지는 행동 파라미터에는 기본값을 설정하지 않는다.

  3. 안전한 기본값 설정: 물리적 행동에 영향을 미치는 파라미터의 기본값은 최소 위험의 보수적 값으로 설정한다.

  4. 설명에 기본값 명시: 포트 설명에 기본값을 포함하여, XML 작성자가 생략 시의 동작을 쉽게 파악할 수 있게 한다.

  5. 기본값 변경 시 호환성 고려: 기본값의 변경이 기존 XML 트리에 미치는 영향을 분석하고, 필요 시 변경 사항을 문서화한다(Faconti, 2022).