397.23 PDDL 기반 임무 계획 구현

1. 개요

PDDL(Planning Domain Definition Language) 기반 임무 계획 구현은 로봇의 행동 능력과 운영 환경의 특성을 PDDL 도메인 파일 및 문제 파일로 형식화하고, 도메인 독립적(domain-independent) 계획기를 호출하여 목표 달성을 위한 행동 시퀀스를 자동 생성하는 실질적 공학 과정을 다룬다. PDDL은 AI 계획 분야의 표준 표현 언어로서, 계획 도메인의 구조적 기술과 문제 인스턴스의 선언적 정의를 분리함으로써 도메인 모델의 재사용성과 계획기의 교체 용이성을 보장한다. 본 절에서는 로봇 임무 계획 시스템에서 PDDL을 활용하여 계획을 수립하고 실행하는 전체 파이프라인의 구현 방법론을 체계적으로 기술한다.

2. PDDL 기반 임무 계획의 전체 파이프라인

PDDL 기반 임무 계획 시스템의 전체 구현 파이프라인은 다음의 여섯 단계로 구성된다.

\text{도메인 모델링} \rightarrow \text{문제 인스턴스 생성} \rightarrow \text{계획 수립} \rightarrow \text{계획 해석} \rightarrow \text{행동 실행} \rightarrow \text{모니터링 및 피드백}

각 단계는 독립적 모듈로 구현되며, 모듈 간의 인터페이스는 PDDL 파일과 행동 시퀀스를 매개로 정의된다. 이러한 파이프라인 구조는 계획기의 교체, 도메인의 확장, 실행 환경의 변경에 유연하게 대응할 수 있는 아키텍처를 제공한다.

2.1 도메인 모델링(Domain Modeling)

도메인 모델링 단계에서는 로봇이 동작하는 환경의 물리적·논리적 특성과 로봇의 행동 능력을 PDDL 도메인 파일로 형식화한다. 도메인 파일은 (define (domain ...)) 구문으로 시작하며, 타입(types), 상수(constants), 술어(predicates), 함수(functions), 행동(actions), 파생 술어(derived predicates) 등의 요소를 포함한다.

2.1.1 술어 설계(Predicate Design)

술어 설계는 도메인의 상태 공간을 기술하기 위한 관계형 속성(relational attributes)을 식별하고 정의하는 과정이다. 로봇 임무 도메인에서 일반적으로 사용되는 술어의 범주와 예시는 다음과 같다.

술어 범주예시의미
위치 관계(at ?r - robot ?l - location)로봇 ?r의 현재 위치가 ?l
연결 관계(connected ?l1 ?l2 - location)위치 ?l1에서 ?l2로의 직접 이동 가능성
물체 파지(holding ?r - robot ?o - object)로봇 ?r이 물체 ?o를 파지 중임
물체 위치(object-at ?o - object ?l - location)물체 ?o가 위치 ?l에 존재함
그리퍼 상태(gripper-free ?r - robot)로봇 ?r의 그리퍼가 비어 있음
작업 완료(inspected ?o - object)물체 ?o에 대한 검사가 완료됨
영역 탐사(explored ?l - location)위치 ?l의 탐사가 완료됨
충전 상태(charged ?r - robot)로봇 ?r의 배터리가 충분함
통신 가능(comm-available ?l - location)위치 ?l에서 통신이 가능함

술어 설계 시에는 **상태 표현의 완전성(completeness)**과 기저화(grounding) 효율성 사이의 균형을 고려하여야 한다. 술어의 수가 과도하게 많으면 기저화된 명제의 수가 기하급수적으로 증가하여 계획 수립 시간이 급격히 증가한다. 반면에 술어가 부족하면 도메인의 중요한 상태를 표현할 수 없어 잘못된 계획이 생성될 수 있다.

2.1.2 타입 계층 설계(Type Hierarchy Design)

타입 계층 설계는 도메인 내의 객체를 의미론적으로 분류하는 체계를 수립하는 과정이다. 적절한 타입 시스템은 계획기의 기저화 공간을 축소하여 탐색 효율을 크게 향상시킨다. PDDL의 :typing 기능을 활용한 타입 계층의 예시는 다음과 같다.

(:types
  robot - locatable
  mobile-robot manipulator-robot aerial-robot - robot
  location - object
  waypoint charging-station inspection-point - location
  payload - locatable
  sensor actuator gripper - equipment
  task - object
)

상위 타입 locatable을 도입하면, 위치를 가질 수 있는 모든 엔티티(로봇, 페이로드 등)에 대해 공통 술어를 정의할 수 있다. 타입 간의 상속(inheritance) 관계는 행동 스키마의 매개변수 타입 제약에 반영되어, 계획기가 의미론적으로 무효한 행동 인스턴스를 사전에 배제할 수 있게 한다.

2.1.3 행동 스키마 설계(Action Schema Design)

행동 스키마는 로봇이 수행할 수 있는 각 행동의 매개변수(parameters), 전제 조건(preconditions), 효과(effects)를 선언적으로 정의한다. 다음은 로봇 이동 행동의 PDDL 행동 스키마 예시이다.

(:action move
  :parameters (?r - mobile-robot ?from - location ?to - location)
  :precondition (and
    (at ?r ?from)
    (connected ?from ?to)
    (not (occupied ?to))
    (>= (battery-level ?r) (travel-cost ?from ?to))
  )
  :effect (and
    (not (at ?r ?from))
    (at ?r ?to)
    (decrease (battery-level ?r) (travel-cost ?from ?to))
    (increase (total-distance ?r) (distance ?from ?to))
  )
)

행동 스키마 설계 시 다음의 원칙을 준수하여야 한다.

  1. 원자성(Atomicity): 각 행동은 하위 수준의 제어 모듈에 의해 실행 가능한 단일 단위여야 한다. 과도하게 세분화된 행동은 계획의 길이를 불필요하게 증가시키고, 과도하게 추상화된 행동은 계획의 유연성을 저하시킨다.
  2. 완전성(Completeness): 임무 목표를 달성하기 위해 필요한 모든 행동이 도메인에 포함되어야 한다. 누락된 행동이 있을 경우 계획기는 해를 찾지 못하거나 부정확한 계획을 생성한다.
  3. 전제 조건의 충분성(Precondition Sufficiency): 행동의 물리적 실행 가능성을 보장하는 모든 조건이 전제 조건에 명시되어야 한다. 불충분한 전제 조건은 실행 시 실패를 유발한다.
  4. 효과의 정확성(Effect Accuracy): 행동의 효과는 실제 물리적 결과를 정확히 반영하여야 한다. 효과의 누락이나 오류는 후속 행동의 전제 조건 불일치를 초래한다.

2.1.4 수치 유창어(Numeric Fluents) 설계

PDDL 2.1(Fox & Long, 2003) 이상에서 지원되는 수치 유창어를 활용하면, 배터리 잔량, 이동 거리, 시간 소모 등의 연속적 자원을 모델링할 수 있다. 수치 유창어는 (:functions ...) 블록에서 정의한다.

(:functions
  (battery-level ?r - robot)           ;; 배터리 잔량 (0-100)
  (travel-cost ?from ?to - location)   ;; 이동에 필요한 에너지
  (distance ?from ?to - location)      ;; 위치 간 거리
  (total-distance ?r - robot)          ;; 로봇의 총 이동 거리
  (payload-weight ?r - robot)          ;; 현재 적재 중량
  (max-payload ?r - robot)             ;; 최대 적재 용량
  (total-cost)                         ;; 전체 비용 메트릭
)

수치 유창어의 도입은 자원 제약을 명시적으로 모델링할 수 있는 장점이 있으나, 계획 수립의 복잡도를 증가시키므로 수치 연산을 지원하는 계획기(예: Metric-FF, OPTIC)가 필요하다.

2.2 문제 인스턴스 생성(Problem Instance Generation)

문제 인스턴스 생성 단계에서는 현재의 환경 상태와 임무 요구사항을 기반으로 PDDL 문제 파일을 자동 또는 반자동으로 생성한다. 문제 파일은 (define (problem ...)) 구문으로 시작하며, 도메인에 대한 참조, 객체 선언, 초기 상태, 목표 조건, 최적화 메트릭을 포함한다.

2.2.1 환경 상태 변환(State Abstraction)

로봇의 센서 데이터와 내부 상태 표현을 PDDL 초기 상태((:init ...))로 변환하는 과정은 상태 추상화(state abstraction) 계층을 통해 수행된다. 연속적 센서 데이터를 이산적 명제로 변환하는 이 과정에서 정보 손실이 발생하므로, 추상화 해상도의 적절한 설정이 중요하다.

로봇의 위치를 GPS 좌표에서 명명된 위치(named location)로 변환하는 과정은 다음과 같이 형식화할 수 있다.

\phi_{\text{loc}} : \mathbb{R}^3 \rightarrow \mathcal{L}, \quad \phi_{\text{loc}}(x, y, z) = \arg\min_{l \in \mathcal{L}} \| (x, y, z) - \mathbf{p}_l \|_2

여기서 \mathcal{L}은 명명된 위치의 집합이고, \mathbf{p}_l은 위치 l의 대표 좌표이다. 이 함수는 로봇의 연속적 위치를 가장 가까운 이산 위치로 매핑한다.

2.2.2 동적 문제 생성기(Dynamic Problem Generator)

로봇 시스템에서는 환경 상태가 지속적으로 변하므로, 계획이 필요할 때마다 현재 상태를 반영한 문제 파일을 동적으로 생성하는 모듈이 필수적이다. 다음은 동적 문제 생성기의 구현 예시이다.

class PDDLProblemGenerator:
    """PDDL 문제 파일을 동적으로 생성하는 클래스"""
    
    def __init__(self, domain_name, location_map):
        self.domain_name = domain_name
        self.location_map = location_map
    
    def generate(self, robot_state, env_state, mission_goal):
        """현재 상태를 기반으로 PDDL 문제 파일을 생성한다."""
        objects = self._generate_objects(robot_state, env_state)
        init_facts = self._generate_init(robot_state, env_state)
        goal_expr = self._generate_goal(mission_goal)
        
        problem_str = f"""(define (problem mission-{robot_state.mission_id})
  (:domain {self.domain_name})
  (:objects
    {objects}
  )
  (:init
    {init_facts}
  )
  (:goal {goal_expr})
  (:metric minimize (total-cost))
)"""
        return problem_str
    
    def _generate_init(self, robot_state, env_state):
        """초기 상태 명제를 생성한다."""
        facts = []
        
        # 로봇 위치 추상화
        loc = self.location_map.nearest(robot_state.position)
        facts.append(f"(at {robot_state.id} {loc})")
        
        # 그리퍼 상태 변환
        if robot_state.gripper_empty:
            facts.append(f"(gripper-free {robot_state.id})")
        else:
            facts.append(
                f"(holding {robot_state.id} "
                f"{robot_state.held_object})"
            )
        
        # 환경 객체 상태 변환
        for obj in env_state.objects:
            obj_loc = self.location_map.nearest(obj.position)
            facts.append(f"(object-at {obj.id} {obj_loc})")
        
        # 위상적 연결 관계 설정
        for edge in env_state.topology.edges:
            facts.append(
                f"(connected {edge.from_loc} {edge.to_loc})"
            )
            facts.append(
                f"(= (travel-cost {edge.from_loc} "
                f"{edge.to_loc}) {edge.cost})"
            )
        
        # 수치 유창어 초기화
        facts.append(
            f"(= (battery-level {robot_state.id}) "
            f"{robot_state.battery_soc})"
        )
        facts.append(
            f"(= (payload-weight {robot_state.id}) "
            f"{robot_state.current_payload})"
        )
        
        return "\n    ".join(facts)
    
    def _generate_goal(self, mission_goal):
        """임무 목표를 PDDL 목표 표현식으로 변환한다."""
        if mission_goal.type == "delivery":
            return (
                f"(and "
                f"(object-at {mission_goal.object_id} "
                f"{mission_goal.target_location}))"
            )
        elif mission_goal.type == "patrol":
            explored = " ".join(
                f"(explored {loc})"
                for loc in mission_goal.patrol_points
            )
            return f"(and {explored})"
        elif mission_goal.type == "inspection":
            inspected = " ".join(
                f"(inspected {obj})"
                for obj in mission_goal.inspection_targets
            )
            return f"(and {inspected})"
        else:
            return mission_goal.to_pddl()
    
    def _generate_objects(self, robot_state, env_state):
        """객체 선언 문자열을 생성한다."""
        lines = []
        lines.append(
            f"{robot_state.id} - {robot_state.robot_type}"
        )
        for loc in env_state.locations:
            lines.append(f"{loc.id} - {loc.type}")
        for obj in env_state.objects:
            lines.append(f"{obj.id} - {obj.type}")
        return "\n    ".join(lines)

2.2.3 목표 조건의 설정(Goal Specification)

목표 조건은 상위 시스템 또는 운영자로부터 전달된 임무 요구사항을 PDDL의 (:goal ...) 절로 변환하여 설정한다. 목표는 단순 명제의 논리 결합(conjunction)으로 표현되는 경우가 가장 일반적이나, PDDL 2.2 이상에서는 파생 술어(derived predicates)를 활용한 복잡한 목표 조건의 정의도 가능하다.

단일 목표 조건의 예시는 다음과 같다.

(:goal (and
  (object-at package1 delivery-point-A)
  (object-at package2 delivery-point-B)
  (at robot1 home-base)
))

3. 계획기 호출 및 통합

3.1 도메인 독립적 계획기의 선택

PDDL 기반 임무 계획의 핵심은 적절한 도메인 독립적 계획기의 선택과 시스템으로의 통합이다. 계획기는 PDDL 도메인과 문제 파일을 입력으로 받아 목표를 달성하는 행동 시퀀스를 출력한다. 주요 계획기와 그 특성은 다음과 같다.

계획기주요 특성지원 PDDL 수준적합한 용도
Fast Downward삭제 완화 휴리스틱, SAS+ 내부 표현, 다양한 탐색 전략 플러그인PDDL 2.2대규모 명제적 계획 문제의 최적 또는 준최적 해 탐색
LAMA랜드마크(landmark) 기반 비용 인식 휴리스틱PDDL 2.2만족형(satisficing) 계획, 빠른 해 생성
POPF부분 순서 전방 탐색, 시간 계획 지원PDDL 2.1시간 제약이 있는 임무 계획
OPTIC수치 유창어 + 시간 계획 동시 지원PDDL 2.1자원 최적화를 포함하는 시간 임무
Metric-FF수치 유창어 확장, 강화된 삭제 완화 휴리스틱PDDL 2.1수치적 자원 제약이 있는 계획
LPG-td확률적 지역 탐색, 행동 그래프 기반PDDL 2.2대규모 계획, 다중 해 생성
MadagascarSAT 변환 기반 병렬 계획PDDL 1.0+짧은 계획의 최적 병렬 스케줄 탐색

계획기 선택 시 고려해야 할 요소는 도메인의 PDDL 기능 요구 수준(수치 유창어, 시간 행동, 조건부 효과 등), 해의 품질 요구사항(최적 vs 만족형), 계획 수립 시간 제약, 그리고 **문제 규모의 확장성(scalability)**이다.

3.2 계획기 호출 인터페이스

계획기는 일반적으로 명령 줄 인터페이스(CLI)를 통해 독립 프로세스로 호출된다. 다음은 Fast Downward 계획기를 호출하는 표준 방식이다.

./fast-downward.py domain.pddl problem.pddl \
  --search "astar(lmcut())"

만족형(satisficing) 해를 빠르게 얻으려면 탐욕적 최적 우선 탐색(greedy best-first search)을 사용할 수 있다.

./fast-downward.py domain.pddl problem.pddl \
  --search "eager_greedy([ff()])"

프로그래매틱 통합을 위해서는 계획기를 서브프로세스로 호출하고, 출력을 파싱하여 행동 시퀀스를 추출하는 래퍼(wrapper) 모듈을 구현한다. 다음은 범용 계획기 인터페이스의 구현 예시이다.

import subprocess
import re
import os
import tempfile

class PDDLPlannerInterface:
    """PDDL 계획기와의 프로그래매틱 인터페이스"""
    
    def __init__(self, planner_path, search_config,
                 timeout=120):
        self.planner_path = planner_path
        self.search_config = search_config
        self.timeout = timeout
    
    def solve(self, domain_file, problem_file):
        """
        계획 수립을 요청하고 결과를 반환한다.
        
        Returns:
            plan: [(action_name, [param1, ...]), ...] 
                  또는 None (실패 시)
        """
        try:
            result = subprocess.run(
                [self.planner_path, domain_file, 
                 problem_file, "--search",
                 self.search_config],
                capture_output=True, text=True,
                timeout=self.timeout
            )
            
            if result.returncode == 0:
                plan_file = self._find_plan_file(
                    problem_file
                )
                if plan_file:
                    return self._parse_plan_file(plan_file)
            
            return self._parse_plan_stdout(result.stdout)
            
        except subprocess.TimeoutExpired:
            return None
    
    def _find_plan_file(self, problem_file):
        """생성된 계획 파일을 탐색한다."""
        directory = os.path.dirname(problem_file)
        for fname in os.listdir(directory):
            if fname.startswith("sas_plan"):
                return os.path.join(directory, fname)
        return None
    
    def _parse_plan_file(self, plan_file):
        """계획 파일에서 행동 시퀀스를 추출한다."""
        plan = []
        with open(plan_file, 'r') as f:
            for line in f:
                line = line.strip()
                if line.startswith(';'):
                    continue
                match = re.match(r'\((.+)\)', line)
                if match:
                    parts = match.group(1).split()
                    plan.append((parts[0], parts[1:]))
        return plan
    
    def _parse_plan_stdout(self, output):
        """표준 출력에서 행동 시퀀스를 추출한다."""
        plan = []
        in_plan = False
        for line in output.strip().split('\n'):
            line = line.strip()
            if 'Solution found' in line:
                in_plan = True
                continue
            if in_plan:
                match = re.match(r'\((.+)\)', line)
                if match:
                    parts = match.group(1).split()
                    plan.append((parts[0], parts[1:]))
        return plan if plan else None

3.3 계획 유효성 검증(Plan Validation)

계획기가 생성한 계획의 정확성을 독립적으로 검증하기 위해 VAL(Howey et al., 2004) 등의 계획 검증기를 활용할 수 있다. 계획 검증기는 도메인, 문제, 계획 파일을 입력받아 계획의 각 행동이 전제 조건을 충족하며 목표가 최종적으로 달성되는지 확인한다.

./validate domain.pddl problem.pddl sas_plan

계획 검증은 특히 도메인 모델에 오류가 있을 가능성이 있는 개발 단계에서 필수적이다. 검증기는 전제 조건 위반, 효과 불일치, 목표 미달성 등의 오류를 구체적으로 보고하여 디버깅을 지원한다.

4. 계획 해석 및 행동 디스패치

4.1 계획 해석기(Plan Interpreter)

계획기가 출력한 행동 시퀀스는 기호적(symbolic) 수준의 추상적 표현이므로, 이를 로봇이 실행할 수 있는 구체적 물리적 명령으로 변환하여야 한다. 이 과정을 계획 해석(plan interpretation) 또는 **기호-실행 변환(symbol-to-execution mapping)**이라 한다.

계획기의 출력 형태는 일반적으로 다음과 같은 기저 행동(ground action)의 순서열이다.

(move robot1 waypointA waypointB)
(pick-up robot1 box1 waypointB)
(move robot1 waypointB waypointC)
(put-down robot1 box1 waypointC)
(inspect robot1 box1 waypointC)

각 기저 행동은 행동 이름과 기저화된 매개변수로 구성된다. 계획 해석기는 이 기호적 표현을 로봇 제어 계층이 이해할 수 있는 실행 명령으로 변환하는 중간 계층(middleware)의 역할을 수행한다.

4.2 행동 디스패처(Action Dispatcher)

행동 디스패처는 기호적 행동을 대응하는 하위 수준의 실행 모듈에 위임하는 컴포넌트이다. 전략 패턴(strategy pattern)을 적용하여 각 PDDL 행동에 대한 실행기(executor)를 등록하고, 런타임에 적절한 실행기를 선택하여 호출하는 방식으로 구현한다.

from abc import ABC, abstractmethod
from dataclasses import dataclass
from typing import List, Dict, Optional
from enum import Enum

class ExecutionStatus(Enum):
    SUCCESS = "success"
    FAILURE = "failure"
    PREEMPTED = "preempted"

@dataclass
class ExecutionResult:
    status: ExecutionStatus
    action_name: str
    params: List[str]
    message: str = ""
    duration: float = 0.0

class ActionExecutorBase(ABC):
    """행동 실행기의 추상 기반 클래스"""
    
    @abstractmethod
    def execute(self, params: List[str]) -> ExecutionResult:
        """행동을 물리적으로 실행한다."""
        pass
    
    @abstractmethod
    def validate_params(self, params: List[str]) -> bool:
        """매개변수의 유효성을 검증한다."""
        pass

class ActionDispatcher:
    """기호적 행동을 실행 모듈로 디스패치하는 클래스"""
    
    def __init__(self):
        self._executors: Dict[str, ActionExecutorBase] = {}
    
    def register(self, action_name: str,
                 executor: ActionExecutorBase):
        """행동 이름에 대한 실행기를 등록한다."""
        self._executors[action_name] = executor
    
    def dispatch(self, action_name: str,
                 params: List[str]) -> ExecutionResult:
        """행동을 적절한 실행기로 디스패치한다."""
        executor = self._executors.get(action_name)
        if executor is None:
            return ExecutionResult(
                status=ExecutionStatus.FAILURE,
                action_name=action_name,
                params=params,
                message=f"등록되지 않은 행동: {action_name}"
            )
        
        if not executor.validate_params(params):
            return ExecutionResult(
                status=ExecutionStatus.FAILURE,
                action_name=action_name,
                params=params,
                message="매개변수 유효성 검증 실패"
            )
        
        return executor.execute(params)

4.3 실행 모듈의 구현

각 실행 모듈은 기호적 매개변수를 로봇의 물리적 명령으로 변환한다. 예를 들어, move 행동의 실행기는 기호적 위치 이름을 실제 좌표로 변환하고, 경로 계획기(path planner)를 호출하여 장애물 회피 경로를 생성한 후 이동 제어를 수행한다.

class MoveExecutor(ActionExecutorBase):
    """이동 행동 실행기"""
    
    def __init__(self, location_db, path_planner,
                 motion_controller):
        self.location_db = location_db
        self.path_planner = path_planner
        self.motion_controller = motion_controller
    
    def validate_params(self, params):
        if len(params) != 3:
            return False
        _, from_loc, to_loc = params
        return (self.location_db.exists(from_loc) and
                self.location_db.exists(to_loc))
    
    def execute(self, params):
        """
        params: [robot_id, from_location, to_location]
        """
        robot_id, from_loc, to_loc = params
        
        # 기호적 위치를 실제 좌표로 변환
        target_pose = self.location_db.get_pose(to_loc)
        current_pose = self.motion_controller.get_current_pose()
        
        # 경로 계획
        path = self.path_planner.plan(
            current_pose, target_pose
        )
        if path is None:
            return ExecutionResult(
                status=ExecutionStatus.FAILURE,
                action_name='move',
                params=params,
                message="경로 계획 실패"
            )
        
        # 경로 추종 실행
        success = self.motion_controller.follow_path(path)
        
        return ExecutionResult(
            status=(ExecutionStatus.SUCCESS if success 
                    else ExecutionStatus.FAILURE),
            action_name='move',
            params=params,
            message="이동 완료" if success else "이동 실패"
        )

물체 파지(pick-up) 행동의 실행기는 물체의 위치를 인식하고, 매니퓰레이터의 역기구학(inverse kinematics)을 계산하여 파지 동작을 수행한다.

class PickUpExecutor(ActionExecutorBase):
    """물체 파지 행동 실행기"""
    
    def __init__(self, perception_module, manipulator,
                 location_db):
        self.perception = perception_module
        self.manipulator = manipulator
        self.location_db = location_db
    
    def validate_params(self, params):
        return len(params) == 3
    
    def execute(self, params):
        """
        params: [robot_id, object_id, location]
        """
        robot_id, object_id, location = params
        
        # 물체 인식 및 파지 자세 계산
        grasp_pose = self.perception.detect_grasp_pose(
            object_id
        )
        if grasp_pose is None:
            return ExecutionResult(
                status=ExecutionStatus.FAILURE,
                action_name='pick-up',
                params=params,
                message=f"물체 {object_id} 감지 실패"
            )
        
        # 매니퓰레이터 이동 및 파지
        success = self.manipulator.grasp(grasp_pose)
        
        return ExecutionResult(
            status=(ExecutionStatus.SUCCESS if success
                    else ExecutionStatus.FAILURE),
            action_name='pick-up',
            params=params
        )

5. 실행 모니터링과 재계획

5.1 실행 모니터링(Execution Monitoring)

PDDL 기반 임무 계획의 실제 구현에서는 계획의 실행 과정을 지속적으로 모니터링하여야 한다. 고전적 계획의 결정론적 가정과 실제 환경의 불확실성 사이의 간극(gap)을 관리하는 것이 핵심 과제이다.

실행 모니터링의 주요 기능은 다음과 같다.

전제 조건 검증(Precondition Verification): 각 행동을 실행하기 전에 해당 행동의 전제 조건이 현재 세계 상태에서 여전히 충족되는지 확인한다. 환경의 동적 변화로 인해 전제 조건이 위반된 경우 실행을 중단하고 재계획을 요청한다.

효과 검증(Effect Verification): 행동 실행 후 예상된 효과가 실제로 달성되었는지 센서 관측을 통해 확인한다. 예상치 못한 효과의 불일치(discrepancy)가 발생하면 세계 모델을 갱신하고 재계획을 트리거한다.

진행 상태 추적(Progress Tracking): 전체 계획에서 현재 실행 중인 행동의 인덱스와 남은 행동의 수를 추적하여, 임무 수행의 전체적 진행률을 관리한다.

이상 탐지(Anomaly Detection): 센서 데이터를 지속적으로 분석하여 계획에 포함되지 않은 예기치 못한 상황(장애물 출현, 물체 이동, 환경 변화 등)을 탐지한다.

from dataclasses import dataclass
from enum import Enum
from typing import Optional

class ReplanReason(Enum):
    PRECONDITION_VIOLATION = "precondition_violation"
    EXECUTION_FAILURE = "execution_failure"
    EXTERNAL_EVENT = "external_event"
    GOAL_CHANGE = "goal_change"

@dataclass
class ReplanRequest:
    reason: ReplanReason
    failed_step: int
    current_state: dict
    new_goal: Optional[str] = None

class PlanExecutionMonitor:
    """계획 실행 모니터링 및 관리 클래스"""
    
    def __init__(self, world_model, plan, 
                 precondition_checker):
        self.world_model = world_model
        self.plan = plan
        self.precondition_checker = precondition_checker
        self.current_step = 0
        self.execution_log = []
    
    def execute_plan(self):
        """계획을 순차 실행하며 모니터링한다."""
        dispatcher = ActionDispatcher()
        
        while self.current_step < len(self.plan):
            action_name, params = self.plan[
                self.current_step
            ]
            
            # 1. 세계 모델 갱신 (센서 관측)
            self.world_model.update_from_sensors()
            
            # 2. 이상 탐지
            anomalies = self.world_model.detect_anomalies()
            if anomalies:
                return ReplanRequest(
                    reason=ReplanReason.EXTERNAL_EVENT,
                    failed_step=self.current_step,
                    current_state=(
                        self.world_model.get_state()
                    )
                )
            
            # 3. 전제 조건 검증
            if not self.precondition_checker.check(
                action_name, params,
                self.world_model.get_state()
            ):
                return ReplanRequest(
                    reason=(
                        ReplanReason.PRECONDITION_VIOLATION
                    ),
                    failed_step=self.current_step,
                    current_state=(
                        self.world_model.get_state()
                    )
                )
            
            # 4. 행동 실행
            result = dispatcher.dispatch(
                action_name, params
            )
            self.execution_log.append(result)
            
            # 5. 실행 결과 검증
            if result.status != ExecutionStatus.SUCCESS:
                return ReplanRequest(
                    reason=(
                        ReplanReason.EXECUTION_FAILURE
                    ),
                    failed_step=self.current_step,
                    current_state=(
                        self.world_model.get_state()
                    )
                )
            
            # 6. 효과 적용 및 검증
            expected_effects = (
                self.precondition_checker
                .get_expected_effects(
                    action_name, params
                )
            )
            actual_state = (
                self.world_model.observe_state()
            )
            if not self._verify_effects(
                expected_effects, actual_state
            ):
                self.world_model.reconcile(actual_state)
                return ReplanRequest(
                    reason=(
                        ReplanReason.EXECUTION_FAILURE
                    ),
                    failed_step=self.current_step,
                    current_state=(
                        self.world_model.get_state()
                    )
                )
            
            self.world_model.apply_effects(
                action_name, params
            )
            self.current_step += 1
        
        return None  # 계획 완료
    
    def _verify_effects(self, expected, actual):
        """예상 효과와 실제 상태를 비교 검증한다."""
        for effect in expected:
            if effect.positive:
                if not actual.holds(effect.predicate):
                    return False
            else:
                if actual.holds(effect.predicate):
                    return False
        return True

5.2 재계획 전략(Replanning Strategy)

재계획은 다음의 상황에서 트리거된다.

  1. 전제 조건 위반: 다음 행동의 전제 조건이 현재 환경 상태에서 충족되지 않는 경우
  2. 행동 실행 실패: 행동의 물리적 실행이 실패한 경우(예: 장애물에 의한 이동 불가, 파지 실패)
  3. 외부 이벤트: 환경의 예기치 않은 변화가 감지된 경우(예: 새로운 장애물 출현, 물체의 예기치 않은 이동)
  4. 목표 변경: 운영자에 의한 임무 목표의 동적 변경

재계획 시에는 현재의 세계 상태를 새로운 초기 상태로 설정하고, 변경되지 않은 목표를 유지하여 새로운 PDDL 문제 인스턴스를 생성한 후 계획기를 재호출한다. 이 과정을 형식화하면 다음과 같다.

\Pi' = \text{Planner}(\mathcal{D}, \langle s_{\text{current}}, G' \rangle)

여기서 \mathcal{D}는 도메인 모델, s_{\text{current}}는 현재 세계 상태, G'는 갱신된 목표 조건이며, \Pi'는 새로 생성된 계획이다.

재계획의 빈도가 과도하면 시스템의 반응성이 저하되므로, 재계획 빈도 제어(replanning rate limiting) 메커니즘을 도입하여 최소 재계획 간격을 설정하는 것이 바람직하다.

6. ROS2 환경에서의 PDDL 기반 구현

6.1 PlanSys2 아키텍처

ROS2(Robot Operating System 2) 환경에서 PDDL 기반 임무 계획을 구현하는 대표적 프레임워크는 PlanSys2(Martín et al., 2021)이다. PlanSys2는 다음의 네 가지 핵심 노드(node)로 구성된다.

Domain Expert Node: PDDL 도메인 파일을 로드하고 관리하는 노드이다. 런타임에 도메인의 타입, 술어, 행동 등의 정보를 조회할 수 있는 서비스 인터페이스를 제공한다.

Problem Expert Node: PDDL 문제 인스턴스를 동적으로 관리하는 노드이다. 객체의 추가/삭제, 초기 상태의 갱신, 목표 조건의 설정 및 변경 등의 기능을 서비스 인터페이스를 통해 제공한다.

Planner Node: PDDL 도메인과 문제를 입력받아 외부 계획기를 호출하고, 생성된 계획을 반환하는 노드이다. POPF, TFD, Fast Downward 등의 계획기를 플러그인 방식으로 교체할 수 있다.

Executor Node: 생성된 계획의 행동을 순차적 또는 병렬적으로 실행하는 노드이다. 각 PDDL 행동에 대응하는 ROS2 액션 서버(Action Server)를 호출하여 행동을 물리적으로 실행한다. 동시 실행 가능한 행동의 병렬 디스패치도 지원한다.

PlanSys2의 아키텍처를 도식화하면 다음과 같다.

┌──────────────────────────────────────────────┐
│              PlanSys2 Architecture            │
├──────────────┬──────────────┬────────────────┤
│ Domain Expert│Problem Expert│  Planner Node  │
│    Node      │    Node      │                │
│              │              │  [POPF/TFD/    │
│  domain.pddl│  objects     │   Fast Downward]│
│  predicates  │  init state  │                │
│  actions     │  goal        │                │
└──────┬───────┴──────┬───────┴───────┬────────┘
       │              │               │
       └──────────────┼───────────────┘
                      │
              ┌───────▼────────┐
              │  Executor Node │
              │                │
              │  Plan → Actions│
              └───┬────┬───┬──┘
                  │    │   │
          ┌───────┘    │   └───────┐
          ▼            ▼           ▼
    ┌──────────┐ ┌──────────┐ ┌──────────┐
    │  Move    │ │ Pick-Up  │ │ Inspect  │
    │  Action  │ │  Action  │ │  Action  │
    │  Server  │ │  Server  │ │  Server  │
    └──────────┘ └──────────┘ └──────────┘

6.2 PlanSys2 기반 구현 흐름

PlanSys2를 활용한 PDDL 기반 임무 계획의 구현 흐름은 다음과 같다.

  1. PDDL 도메인 파일을 Domain Expert Node에 로드한다.
  2. 현재 환경 상태를 기반으로 객체와 초기 상태를 Problem Expert Node에 설정한다.
  3. 임무 목표를 Problem Expert Node에 설정한다.
  4. Planner Node에 계획 수립을 요청한다.
  5. Executor Node가 생성된 계획의 행동을 순차적으로 실행한다.
  6. 각 행동은 대응하는 ROS2 Action Server를 호출하여 물리적으로 수행된다.
  7. 실행 모니터링 및 피드백을 통해 계획의 진행 상태를 관리한다.

6.3 행동 서버 구현(Action Server Implementation)

PlanSys2에서 각 PDDL 행동에 대응하는 행동 서버는 plansys2::ActionExecutorClient를 상속하여 구현한다. 다음은 이동(move) 행동의 행동 서버 구현 예시이다.

#include "plansys2_executor/ActionExecutorClient.hpp"
#include "nav2_msgs/action/navigate_to_pose.hpp"
#include "rclcpp_action/rclcpp_action.hpp"

class MoveAction : public plansys2::ActionExecutorClient {
public:
    MoveAction()
    : ActionExecutorClient("move", 500ms)
    {
        nav_client_ = rclcpp_action::create_client
            <nav2_msgs::action::NavigateToPose>(
                shared_from_this(), "navigate_to_pose"
            );
    }

protected:
    void do_work() override {
        // 기호적 매개변수 추출
        auto args = get_arguments();
        std::string robot = args[0];
        std::string from = args[1];
        std::string to = args[2];
        
        if (!navigation_started_) {
            // 위치 데이터베이스에서 좌표 조회
            auto target = location_db_.lookup(to);
            
            // Nav2 네비게이션 목표 전송
            auto goal_msg = nav2_msgs::action
                ::NavigateToPose::Goal();
            goal_msg.pose.header.frame_id = "map";
            goal_msg.pose.pose.position.x = target.x;
            goal_msg.pose.pose.position.y = target.y;
            goal_msg.pose.pose.orientation = 
                target.orientation;
            
            nav_client_->async_send_goal(goal_msg);
            navigation_started_ = true;
        }
        
        // 진행률 갱신
        send_feedback(progress_, "Moving to " + to);
        
        if (navigation_complete()) {
            finish(true, 1.0, "Navigation succeeded");
        }
    }

private:
    rclcpp_action::Client
        <nav2_msgs::action::NavigateToPose>::SharedPtr 
        nav_client_;
    LocationDatabase location_db_;
    bool navigation_started_ = false;
    float progress_ = 0.0;
};

7. 구현 시 핵심 고려사항

7.1 기호-물리 간극(Symbol-Physical Gap)

PDDL 기반 계획에서 가장 중요한 구현 과제 중 하나는 기호적 표현과 물리적 세계 사이의 간극을 관리하는 것이다. 기호적 행동 (move robot1 roomA roomB)의 성공은 하위 수준의 경로 계획기, 장애물 감지기, 이동 제어기의 정상 동작에 의존한다. 이 계층 간의 인터페이스를 견고하게 설계하여야 한다.

기호-물리 간극의 관리를 위한 핵심 설계 원칙은 다음과 같다.

  • 양방향 매핑의 일관성: 기호적 상태에서 물리적 명령으로의 변환(하향 매핑)과 센서 관측에서 기호적 상태로의 변환(상향 매핑)이 일관성을 유지하여야 한다.
  • 실패 전파의 명확성: 하위 수준의 실행 실패가 기호적 수준에서 명확하게 인식되어야 한다.
  • 추상화 경계의 명시성: 각 계층의 책임 범위와 인터페이스가 명확하게 정의되어야 한다.

7.2 상태 추정의 정확성(State Estimation Accuracy)

PDDL의 닫힌 세계 가정(Closed World Assumption, CWA)은 완전하고 정확한 세계 모델을 전제로 한다. 즉, 초기 상태에 명시되지 않은 모든 명제는 거짓으로 간주된다. 실제 로봇 시스템에서는 센서의 불확실성, 동적 환경 변화, 통신 지연 등으로 인해 세계 모델의 정확성이 보장되지 않는다. 따라서 다음의 보완 기법이 필요하다.

  1. 센서 융합(Sensor Fusion): 다중 센서의 관측치를 통합하여 상태 추정의 정확성을 향상시킨다.
  2. 확률적 상태 추정: 칼만 필터(Kalman Filter)나 파티클 필터(Particle Filter) 등의 확률적 추정 기법을 활용하여 상태의 불확실성을 관리한다.
  3. 상태-명제 변환의 임계값 설정: 연속적 상태를 이산적 명제로 변환할 때 히스테리시스(hysteresis)를 적용하여 상태 토글링(toggling)을 방지한다.

7.3 계획 수립 시간의 관리(Planning Time Management)

계획기의 응답 시간은 문제의 크기(객체 수, 행동 수)와 탐색 공간의 복잡도에 따라 크게 달라진다. 실시간 로봇 시스템에서는 다음의 전략을 통해 계획 수립 시간을 관리한다.

  • 타임아웃(Timeout) 설정: 계획기에 최대 허용 시간을 설정하고, 시간 초과 시 현재까지의 최선해(best-so-far solution)를 반환하거나 만족형(satisficing) 해를 채택한다.
  • 점진적 계획(Anytime Planning): LAMA 등의 점진적 계획기를 사용하여, 시간이 허용되는 만큼 점진적으로 계획의 품질을 개선한다.
  • 도메인 축소(Domain Reduction): 현재 임무와 관련 없는 객체와 술어를 문제 파일에서 제거하여 탐색 공간을 축소한다.
  • 계획 캐싱(Plan Caching): 유사한 문제 인스턴스에 대한 이전 계획을 캐싱하고, 새로운 문제가 캐싱된 문제와 유사한 경우 캐싱된 계획을 초기해로 활용한다.

7.4 도메인 모델의 유지보수(Domain Model Maintenance)

PDDL 도메인 모델은 로봇의 행동 능력이 변경되거나 환경의 구조가 달라질 때마다 갱신되어야 한다. 도메인 모델의 정확성과 완전성을 보장하기 위한 방법론은 다음과 같다.

  1. 단위 검증(Unit Validation): 각 행동 스키마에 대해 개별적으로 전제 조건-효과의 정확성을 검증하는 테스트 문제를 작성한다.
  2. 회귀 검증(Regression Testing): 도메인 모델의 변경 후 기존의 테스트 문제에 대한 계획 수립이 여전히 정상적으로 수행되는지 확인한다.
  3. 버전 관리(Version Control): 도메인 파일의 변경 이력을 체계적으로 관리하여, 문제 발생 시 이전 버전으로의 롤백(rollback)이 가능하게 한다.
  4. 자동화된 도메인 학습(Automated Domain Learning): 실행 로그와 환경 관측으로부터 도메인 모델을 자동으로 갱신하는 기법(예: ARMS, LOCM)의 적용을 고려한다.

8. 참고 문헌

  • Helmert, M. (2006). “The Fast Downward Planning System.” Journal of Artificial Intelligence Research, 26, 191–246.
  • Richter, S., & Westphal, M. (2010). “The LAMA Planner: Guiding Cost-Based Anytime Planning with Landmarks.” Journal of Artificial Intelligence Research, 39, 127–177.
  • Coles, A. J., Coles, A. I., Fox, M., & Long, D. (2010). “Forward-Chaining Partial-Order Planning.” Proceedings of the 20th International Conference on Automated Planning and Scheduling (ICAPS 2010), 42–49.
  • Martín, F., Cañas, J. M., Fuentetaja, R., & Rodríguez, Á. (2021). “PlanSys2: A Planning System Framework for ROS2.” IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 2021), 9742–9749.
  • Fox, M., & Long, D. (2003). “PDDL2.1: An Extension to PDDL for Expressing Temporal Planning Domains.” Journal of Artificial Intelligence Research, 20, 61–124.
  • Ghallab, M., Nau, D., & Traverso, P. (2004). Automated Planning: Theory and Practice. Morgan Kaufmann.
  • Howey, R., Long, D., & Fox, M. (2004). “VAL: Automatic Plan Validation, Continuous Effects and Mixed Initiative Planning Using PDDL.” Proceedings of the 16th IEEE International Conference on Tools with Artificial Intelligence (ICTAI 2004), 294–301.
  • Hoffmann, J. (2001). “FF: The Fast-Forward Planning System.” AI Magazine, 22(3), 57–62.
  • Cresswell, S., McCluskey, T. L., & West, M. M. (2013). “Acquiring Planning Domain Models Using LOCM.” The Knowledge Engineering Review, 28(2), 195–213.

v0.2.0