Skip to content

Commit 727abfb

Browse files
committed
cx_pddl_bringup: simplify tutorial further
Combine first and next selection
1 parent 5048d34 commit 727abfb

2 files changed

Lines changed: 28 additions & 26 deletions

File tree

extensions/pddl/cx_pddl_bringup/clips/cx_pddl_bringup/cx_pddl_clips_agent.clp

Lines changed: 16 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
(defrule cx-pddl-clips-agent-pddl-add-instance
2525
" Setup PDDL instance with an active goal to plan for "
2626
(pddl-manager (ros-comm-init TRUE))
27-
=>
27+
=>
2828
(bind ?share-dir (ament-index-get-package-share-directory "cx_pddl_bringup"))
2929
(assert
3030
(pddl-instance
@@ -38,68 +38,58 @@
3838
(pddl-goal-fluent (instance test) (goal active-goal) (name on) (params a b))
3939
(pddl-goal-fluent (instance test) (goal active-goal) (name on) (params b c))
4040
(pddl-set-goals (instance test) (goal active-goal))
41-
(pddl-plan (instance test) (goal active-goal) (plan-type TEMPORAL))
41+
(pddl-plan (id test-plan) (instance test) (goal active-goal) (plan-type TEMPORAL))
4242
)
4343
)
4444

4545

4646
(defrule cx-pddl-clips-agent-select-action
4747
" Start executing the first action of the resulting plan "
48-
(not (plan-start ?t))
49-
?pa <- (pddl-action (planned-start-time ?t) (state IDLE))
50-
(not (pddl-action (planned-start-time ?ot&:(< ?ot ?t))))
51-
=>
48+
?plan <- (pddl-plan (id ?plan-id) (plan-start ?p-start))
49+
(not (pddl-action (state EXECUTING|SELECTED)))
50+
?pa <- (pddl-action (plan ?plan-id) (planned-start-time ?t) (state IDLE))
51+
(not (pddl-action (plan ?plan-id) (state IDLE) (planned-start-time ?ot&:(< ?ot ?t))))
52+
=>
53+
(if (= ?p-start 0.0) then (modify ?plan (plan-start (now))))
5254
(modify ?pa (state SELECTED))
53-
(assert (plan-start (now)))
5455
)
5556

5657
(defrule cx-pddl-clips-agent-check-action
5758
" Before executing an action check the condition to make sure it is feasible "
5859
(pddl-action (id ?id) (state SELECTED) (name ?name) (params $?params))
5960
(not (pddl-action-condition (action ?id)))
60-
=>
61+
=>
6162
(assert (pddl-action-condition (instance test) (action ?id)))
6263
)
6364

6465
(defrule cx-pddl-clips-agent-executable-action
6566
" Condition is satisfied, go ahead with execution "
66-
(plan-start ?t)
67+
(pddl-plan (id ?plan-id) (plan-start ?t))
6768
(pddl-action-condition (action ?action-id) (state CONDITION-SAT))
68-
?pa <- (pddl-action (id ?action-id) (name ?name) (params $?params) (state SELECTED))
69-
=>
69+
?pa <- (pddl-action (id ?action-id) (plan ?plan-id) (name ?name) (params $?params) (state SELECTED))
70+
=>
7071
(modify ?pa (state EXECUTING) (actual-start-time (- (now) ?t)))
7172
)
7273

7374
(defrule cx-pddl-clips-agent-execution-done
7475
" After the duration has elapsed, the action is done "
7576
(time ?now)
76-
(plan-start ?t)
77-
?pa <- (pddl-action (id ?id) (state EXECUTING) (planned-duration ?d) (name ?name)
77+
(pddl-plan (id ?plan-id) (plan-start ?t))
78+
?pa <- (pddl-action (id ?id) (plan ?plan-id) (state EXECUTING) (planned-duration ?d) (name ?name)
7879
(actual-start-time ?s&:(< (+ ?s ?d ?t) ?now)))
79-
=>
80+
=>
8081
(bind ?duration (- (now) (+ ?s ?t)))
8182
(printout info "Executed action " ?name " in " ?duration " seconds" crlf)
8283
(modify ?pa (state DONE) (actual-duration ?duration))
8384
(assert (pddl-action-get-effect (action ?id) (apply TRUE)))
8485
)
8586

86-
(defrule cx-pddl-clips-agent-select-next-action
87-
" Once an action is done, select one with lowest planned start time next "
88-
(not (pddl-action (state EXECUTING|SELECTED)))
89-
(not (pddl-action-get-effect (state ~DONE)))
90-
(not (pddl-fluent-change))
91-
?pa <- (pddl-action (planned-start-time ?t) (state IDLE))
92-
(not (pddl-action (state IDLE) (planned-start-time ?ot&:(< ?ot ?t))))
93-
=>
94-
(modify ?pa (state SELECTED))
95-
)
96-
9787
(defrule cx-pddl-clips-agent-print-exec-times
9888
" Once everything is done, print out planned vs actual times "
9989
(pddl-action)
10090
(not (pddl-action (state ~DONE)))
10191
(not (printed))
102-
=>
92+
=>
10393
(printout blue "Execution done" crlf)
10494
(do-for-all-facts ((?pa pddl-action)) TRUE
10595
(printout green "action " ?pa:name " "

extensions/pddl/cx_pddl_bringup/clips/cx_pddl_bringup/deftemplate-overrides.clp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,3 +28,15 @@
2828
(slot actual-duration (type FLOAT))
2929
(slot state (type SYMBOL) (allowed-values IDLE SELECTED EXECUTING DONE))
3030
)
31+
32+
(deftemplate pddl-plan
33+
(slot instance (type SYMBOL))
34+
(slot id (type SYMBOL))
35+
(slot goal (type SYMBOL))
36+
(slot goal-ptr (type EXTERNAL-ADDRESS))
37+
(slot plan-type (type SYMBOL) (allowed-values CLASSICAL TEMPORAL) (default CLASSICAL))
38+
(slot goal-handle (type EXTERNAL-ADDRESS))
39+
(slot type (type SYMBOL) (allowed-values TEMPORAL CLASSICAL))
40+
(slot state (type SYMBOL) (allowed-values PENDING WAITING PLANNING REQUEST-CANCELING CANCELING CANCELED SUCCESS FAILURE) (default PENDING))
41+
(slot plan-start (type FLOAT) (default 0.0))
42+
)

0 commit comments

Comments
 (0)