1296.28 단일 책임 원칙의 적용

1. 단일 책임 원칙의 정의

단일 책임 원칙(Single Responsibility Principle, SRP)은 소프트웨어 모듈이 단 하나의 변경 이유(reason to change)만을 가져야 한다는 설계 원칙이다(Martin, 2003). 행동 트리의 액션 노드에 이 원칙을 적용하면, 하나의 액션 노드는 하나의 명확히 정의된 원자적 행동(atomic action)만을 캡슐화하여야 하며, 그 행동의 변경만이 해당 노드의 수정 이유가 되어야 한다.

행동 트리의 모듈성(modularity)은 각 노드가 독립적인 행동 단위로 기능할 때 달성된다(Colledanchise & Ögren, 2018). 단일 책임 원칙은 이 모듈성의 핵심적 실현 수단이다.

2. 행동 트리에서의 단일 책임

행동 트리에서 단일 책임의 범위는 “하나의 물리적 행동” 또는 “하나의 논리적 결정“으로 정의된다. 복합적 행동은 제어 노드(Sequence, Fallback, Parallel)에 의한 조합으로 표현되어야 하며, 단일 액션 노드 내부에서 다수의 행동을 순차적으로 수행하는 것은 단일 책임 원칙의 위반에 해당한다.

2.1 책임의 경계 판단 기준

액션 노드의 책임 경계를 판단하기 위한 기준을 제시한다.

  1. 독립적 실행 가능성: 해당 행동이 다른 행동과 독립적으로 의미를 가지는가?
  2. 독립적 실패 가능성: 해당 행동이 다른 행동과 무관하게 독립적으로 실패할 수 있는가?
  3. 독립적 취소 가능성: 해당 행동이 다른 행동과 무관하게 독립적으로 취소(Halt)될 수 있는가?
  4. 재사용 가능성: 해당 행동이 다른 트리 구조에서 단독으로 재사용될 수 있는가?

이 기준 중 하나라도 충족되는 행동은 별도의 액션 노드로 분리하여야 한다.

3. 위반 사례 분석

3.1 사례 1: 다중 물리적 행동의 결합

class ScanAndNavigate : public BT::StatefulActionNode
{
    enum class Phase { SCANNING, NAVIGATING };
    Phase phase_;

    BT::NodeStatus onStart() override
    {
        startLidarScan();
        phase_ = Phase::SCANNING;
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override
    {
        if (phase_ == Phase::SCANNING)
        {
            if (isScanComplete())
            {
                auto target = extractTargetFromScan();
                sendNavigationGoal(target);
                phase_ = Phase::NAVIGATING;
            }
            return BT::NodeStatus::RUNNING;
        }

        // Phase::NAVIGATING
        return isNavigationComplete()
            ? BT::NodeStatus::SUCCESS
            : BT::NodeStatus::RUNNING;
    }

    void onHalted() override
    {
        if (phase_ == Phase::SCANNING)
            stopLidarScan();
        else
            cancelNavigation();
    }
};

이 구현은 다음의 문제를 가진다.

  • 재사용 불가: 스캔만 필요한 경우에도 내비게이션 로직이 포함된 노드를 사용하여야 한다.
  • 테스트 복잡도 증가: 스캔과 내비게이션의 조합에 의한 상태 공간이 확대된다.
  • 변경 전파: 내비게이션 로직의 변경이 스캔 로직에 영향을 미칠 수 있다.
  • Halt 처리 복잡화: 현재 단계에 따라 Halt 처리가 달라진다.

3.2 사례 2: 행동과 판단의 혼합

class ConditionalMovement : public BT::StatefulActionNode
{
    BT::NodeStatus onStart() override
    {
        double battery_level;
        getInput("battery_level", battery_level);

        // 조건 판단과 행동이 혼합
        if (battery_level < 20.0)
        {
            sendNavigationGoal(charging_station_);
        }
        else
        {
            sendNavigationGoal(next_waypoint_);
        }
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override
    {
        return isNavigationComplete()
            ? BT::NodeStatus::SUCCESS
            : BT::NodeStatus::RUNNING;
    }

    void onHalted() override { cancelNavigation(); }
};

이 구현에서 배터리 수준에 따른 목표 결정은 조건 노드(Condition Node)의 책임이며, 내비게이션 행동과 분리되어야 한다.

4. 준수 사례

4.1 분리된 행동 노드

위의 위반 사례 1을 단일 책임 원칙에 따라 재설계한다.

class PerformLidarScan : public BT::StatefulActionNode
{
public:
    PerformLidarScan(const std::string& name,
                      const BT::NodeConfig& config)
        : StatefulActionNode(name, config) {}

    static BT::PortsList providedPorts()
    {
        return {
            BT::OutputPort<Pose>("detected_target",
                "스캔에서 검출된 목표 위치")
        };
    }

    BT::NodeStatus onStart() override
    {
        startLidarScan();
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override
    {
        if (isScanComplete())
        {
            auto target = extractTargetFromScan();
            setOutput("detected_target", target);
            return BT::NodeStatus::SUCCESS;
        }
        return BT::NodeStatus::RUNNING;
    }

    void onHalted() override { stopLidarScan(); }
};

class NavigateToTarget : public BT::StatefulActionNode
{
public:
    NavigateToTarget(const std::string& name,
                      const BT::NodeConfig& config)
        : StatefulActionNode(name, config) {}

    static BT::PortsList providedPorts()
    {
        return {
            BT::InputPort<Pose>("target_pose",
                "내비게이션 목표 위치")
        };
    }

    BT::NodeStatus onStart() override
    {
        Pose target;
        if (!getInput("target_pose", target))
            return BT::NodeStatus::FAILURE;

        sendNavigationGoal(target);
        return BT::NodeStatus::RUNNING;
    }

    BT::NodeStatus onRunning() override
    {
        return isNavigationComplete()
            ? BT::NodeStatus::SUCCESS
            : BT::NodeStatus::RUNNING;
    }

    void onHalted() override { cancelNavigation(); }
};

두 노드는 Sequence 제어 노드에 의해 조합된다.

<Sequence>
    <PerformLidarScan detected_target="{target}" />
    <NavigateToTarget target_pose="{target}" />
</Sequence>

4.2 분리의 이점

비교 항목결합된 노드분리된 노드
재사용성낮음높음
테스트 용이성낮음 (복합 상태)높음 (단일 행동)
Halt 처리조건부 (단계별)단순 (단일 행동)
변경 영향 범위광범위국소적
코드 가독성낮음 (다단계 상태 기계)높음 (단일 목적)
트리 구조 유연성낮음 (고정된 순서)높음 (제어 노드로 조합)

5. 행동의 세분화 수준

단일 책임 원칙의 적용에서 행동의 세분화 수준(granularity)은 중요한 설계 결정이다. 과도한 세분화는 트리의 깊이를 증가시키고, 불충분한 세분화는 재사용성을 저하시킨다.

5.1 과도한 세분화의 예

<!-- 하나의 ROS2 액션 호출을 과도하게 분해 -->
<Sequence>
    <CreateGoalMessage goal="{goal}" />
    <SendGoalToServer goal="{goal}" handle="{handle}" />
    <WaitForGoalAcceptance handle="{handle}" />
    <WaitForResult handle="{handle}" result="{result}" />
    <ProcessResult result="{result}" />
</Sequence>

ROS2 액션의 목표 전송, 수락 대기, 결과 대기는 단일 액션 호출의 내부 단계이며, 이를 별도 노드로 분리하는 것은 과도한 세분화이다. 이 단계들은 독립적으로 재사용될 가능성이 낮고, 항상 동일한 순서로 실행되므로 단일 노드로 캡슐화하는 것이 적합하다.

5.2 적절한 세분화의 예

<Sequence>
    <ComputePathToPose goal="{goal}" path="{path}" />
    <FollowPath path="{path}" />
</Sequence>

경로 계산과 경로 추종은 각각 독립적인 ROS2 액션 서버에 대응하며, 독립적으로 재사용 가능하고, 독립적으로 실패할 수 있으므로 별도 노드로 분리하는 것이 적절하다.

5.3 세분화 수준의 판단 지침

기준분리 권장통합 권장
독립적 ROS2 인터페이스 대응O
독립적 실패 모드 존재O
다른 컨텍스트에서 단독 사용 가능O
항상 동일 순서로 실행O
단일 ROS2 호출의 내부 단계O
분리 시 데이터 전달 복잡도 과도O

6. 제어 노드에 의한 행동 조합

단일 책임 원칙에 의해 분리된 액션 노드는 제어 노드에 의해 복합적 행동으로 조합된다. 이 조합은 트리의 XML 정의에서 이루어지므로, 코드의 수정 없이 행동의 순서, 조건, 병렬성을 변경할 수 있다.

6.1 Sequence에 의한 순차 조합

<Sequence>
    <DetectObject object_id="{id}" />
    <NavigateToPose target_pose="{id_pose}" />
    <PickupObject object_id="{id}" />
    <NavigateToPose target_pose="{drop_pose}" />
    <PlaceObject object_id="{id}" />
</Sequence>

각 노드가 단일 행동만을 수행하므로, 중간에 행동을 삽입하거나 순서를 변경하는 것이 코드 수정 없이 가능하다.

6.2 Fallback에 의한 대안 조합

<Fallback>
    <NavigateToPose target_pose="{primary_route}" />
    <NavigateToPose target_pose="{alternative_route}" />
    <BackUp distance="1.0" />
</Fallback>

동일한 NavigateToPose 노드가 서로 다른 입력으로 재사용된다. 단일 책임 원칙에 의해 노드가 범용적으로 설계되었기 때문에 가능한 재사용이다.

7. 단일 책임 원칙과 트리 구조의 관계

단일 책임 원칙의 적용은 행동 트리의 구조적 특성에 직접적으로 영향을 미친다.

7.1 트리 깊이와 너비의 균형

단일 책임 원칙에 의해 행동이 세분화되면 트리의 리프 노드 수가 증가한다. 이에 따라 제어 노드의 수도 증가하여 트리의 깊이 또는 너비가 확대된다. 적절한 세분화 수준의 선택은 트리의 구조적 복잡도를 관리하는 데 필수적이다.

7.2 서브트리에 의한 캡슐화

빈번히 사용되는 노드 조합은 서브트리(subtree)로 캡슐화하여 재사용할 수 있다. 서브트리는 단일 책임 원칙에 의해 분리된 노드의 특정 조합을 하나의 재사용 가능한 단위로 묶는 메커니즘이다.

<!-- 서브트리 정의 -->
<BehaviorTree ID="PickAndPlace">
    <Sequence>
        <DetectObject object_id="{target}" />
        <NavigateToPose target_pose="{object_pose}" />
        <PickupObject object_id="{target}" />
        <NavigateToPose target_pose="{place_pose}" />
        <PlaceObject object_id="{target}" />
    </Sequence>
</BehaviorTree>

<!-- 서브트리 사용 -->
<SubTree ID="PickAndPlace" target="box_1"
         place_pose="{destination}" />

서브트리에 의한 캡슐화는 단일 책임 원칙에 의한 세분화와 사용 편의성 간의 균형을 달성하는 수단이다.

8. 설계 지침

  1. 하나의 노드, 하나의 ROS2 인터페이스: 가능한 한 하나의 액션 노드가 하나의 ROS2 인터페이스(액션, 서비스, 토픽)에 대응하도록 설계한다.

  2. 조건 판단의 분리: 행동의 실행 여부를 결정하는 조건 판단은 조건 노드(Condition Node)로 분리하고, 액션 노드에는 행동의 실행만을 담당시킨다.

  3. 변경 이유의 단일성 검증: 노드의 수정이 필요한 시나리오를 열거하여, 수정 이유가 둘 이상인 경우 노드를 분리한다.

  4. 적절한 세분화 수준: 독립적 재사용, 독립적 실패, 독립적 취소가 의미 있는 경우에만 분리하고, 과도한 세분화를 지양한다.

  5. 서브트리 활용: 분리된 노드의 빈번한 조합은 서브트리로 캡슐화하여 재사용성과 사용 편의성을 양립시킨다(Colledanchise & Ögren, 2018).