1317.19 PDDL 도메인과 PlanSys2의 연계 방식
1. 연계의 개요
PlanSys2에서 PDDL 도메인은 시스템의 핵심 입력으로서, 로봇이 수행할 수 있는 행동의 추상적 모델을 정의한다. PDDL 도메인 파일은 Domain Expert 노드에 로드되어 시스템 전반에 공유되며, 도메인에 정의된 각 액션은 ROS2 액션 노드와 일대일로 대응한다.
2. 도메인 파일의 배치와 관리
2.1 ROS2 패키지 구조
my_robot_planning/
├── CMakeLists.txt
├── package.xml
├── pddl/
│ ├── domain.pddl ;; PDDL 도메인 파일
│ └── test_problem.pddl ;; 테스트용 문제 파일
├── src/
│ ├── move_action_node.cpp ;; 액션 노드 구현
│ ├── pick_action_node.cpp
│ └── controller_node.cpp ;; 임무 관리 노드
├── launch/
│ └── planning.launch.py ;; 런치 파일
└── config/
└── plansys2_params.yaml ;; 파라미터 설정
2.2 CMakeLists.txt에서의 설치
install(DIRECTORY pddl/ DESTINATION share/${PROJECT_NAME}/pddl)
install(DIRECTORY launch/ DESTINATION share/${PROJECT_NAME}/launch)
install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}/config)
3. 도메인 파일 로딩
Domain Expert 노드가 파라미터로 지정된 도메인 파일을 로드한다:
# 런치 파일에서 도메인 파일 경로 설정
import os
from ament_index_python.packages import get_package_share_directory
pkg_dir = get_package_share_directory('my_robot_planning')
domain_file = os.path.join(pkg_dir, 'pddl', 'domain.pddl')
Node(
package='plansys2_bringup',
executable='plansys2_node',
parameters=[{'model_file': domain_file}]
)
4. PDDL 액션과 ROS2 노드의 매핑
도메인에 정의된 각 PDDL 액션에 대해, 동일한 이름의 ActionExecutorClient 노드를 구현해야 한다:
;; PDDL 도메인의 액션
(:durative-action move
:parameters (?r - robot ?from ?to - waypoint)
...)
(:durative-action pick
:parameters (?r - robot ?obj - object ?loc - waypoint)
...)
// 대응하는 C++ 액션 노드
class MoveAction : public plansys2::ActionExecutorClient {
MoveAction() : ActionExecutorClient("move", 500ms) {}
// "move"가 PDDL 액션 이름과 일치
};
class PickAction : public plansys2::ActionExecutorClient {
PickAction() : ActionExecutorClient("pick", 500ms) {}
// "pick"이 PDDL 액션 이름과 일치
};
5. 세계 상태의 초기화
문제 파일을 별도로 로드하는 대신, Problem Expert의 API를 통해 프로그래밍적으로 세계 상태를 초기화한다:
void initializeWorldState() {
auto problem_client = std::make_shared<plansys2::ProblemExpertClient>();
// 객체 등록
problem_client->addInstance(plansys2::Instance{"robot1", "robot"});
problem_client->addInstance(plansys2::Instance{"wp1", "waypoint"});
problem_client->addInstance(plansys2::Instance{"wp2", "waypoint"});
problem_client->addInstance(plansys2::Instance{"box1", "object"});
// 초기 상태 설정
problem_client->addPredicate(plansys2::Predicate("(robot_at robot1 wp1)"));
problem_client->addPredicate(plansys2::Predicate("(connected wp1 wp2)"));
problem_client->addPredicate(plansys2::Predicate("(object_at box1 wp2)"));
problem_client->addPredicate(plansys2::Predicate("(gripper_free robot1)"));
// 수치 함수 초기화
problem_client->addFunction(plansys2::Function("(= (battery_level robot1) 100)"));
problem_client->addFunction(plansys2::Function("(= (distance wp1 wp2) 10)"));
}
6. 도메인 변경과 재로딩
도메인 파일을 변경한 경우, Domain Expert 노드를 재구성하여 새 도메인을 로드할 수 있다:
# 라이프사이클을 통한 재로딩
ros2 lifecycle set /domain_expert deactivate
ros2 lifecycle set /domain_expert cleanup
ros2 param set /domain_expert model_file "/new/path/to/domain.pddl"
ros2 lifecycle set /domain_expert configure
ros2 lifecycle set /domain_expert activate
7. 참고 문헌
- Gonzalez, F., Martin, F., Matellán, V., & Rodriguez, F. J. (2021). “PlanSys2: A Planning System Framework for ROS2.” IEEE ICARSC.