🔨fix merge, add new BT, change domain
This commit is contained in:
parent
5df3632c80
commit
a27edeada9
3 changed files with 49 additions and 20 deletions
|
@ -59,14 +59,11 @@ endforeach()
|
|||
add_executable(move_controller_node src/move_controller_node.cpp)
|
||||
ament_target_dependencies(move_controller_node ${dependencies})
|
||||
|
||||
add_executable(move_action_node src/move_action_node.cpp)
|
||||
ament_target_dependencies(move_action_node ${dependencies})
|
||||
|
||||
install(DIRECTORY launch pddl behavior_trees_xml config DESTINATION share/${PROJECT_NAME})
|
||||
|
||||
install(TARGETS
|
||||
move_controller_node
|
||||
move_action_node
|
||||
${plugin_libs}
|
||||
ARCHIVE DESTINATION lib
|
||||
LIBRARY DESTINATION lib
|
||||
|
|
|
@ -0,0 +1,42 @@
|
|||
<?xml version="1.0"?>
|
||||
<root main_tree_to_execute="GraspPart">
|
||||
<!-- ////////// -->
|
||||
<BehaviorTree ID="GraspPart">
|
||||
<Fallback name="root_Fallback">
|
||||
<Sequence name="GraspSkill">
|
||||
<ReactiveFallback name="PartEstimate">
|
||||
<Condition ID="PartInScene"/>
|
||||
<Action ID="FindPart" PartName="{arg1}" PartPose="{arg0}"/>
|
||||
</ReactiveFallback>
|
||||
<Fallback name="Move">
|
||||
<Condition ID="PathFree"/>
|
||||
<Action ID="MoveToPoint" arm_group="${arg2}" goal="${arg0}"/>
|
||||
</Fallback>
|
||||
<Action ID="GraspPart" arm_group="${arg3}"/>
|
||||
<Action ID="MoveToPoint" arm_group="{arg2}" goal="{arg4}"/>
|
||||
</Sequence>
|
||||
</Fallback>
|
||||
</BehaviorTree>
|
||||
<!-- ////////// -->
|
||||
<TreeNodesModel>
|
||||
<Action ID="FindPart">
|
||||
<inout_port name="PartName"/>
|
||||
<output_port name="PartPose"/>
|
||||
</Action>
|
||||
<Action ID="GraspPart">
|
||||
<input_port name="arm_group"/>
|
||||
</Action>
|
||||
<Action ID="MoveToPoint">
|
||||
<input_port name="arm_group"/>
|
||||
<input_port name="goal"/>
|
||||
</Action>
|
||||
<Condition ID="PartInScene"/>
|
||||
<Condition ID="PathFree"/>
|
||||
<Action ID="SpawnPart">
|
||||
<inout_port name="PartName"/>
|
||||
<input_port name="PartPose"/>
|
||||
</Action>
|
||||
</TreeNodesModel>
|
||||
<!-- ////////// -->
|
||||
</root>
|
||||
|
|
@ -5,13 +5,13 @@
|
|||
(:types
|
||||
robot
|
||||
zone
|
||||
part
|
||||
);; end Types ;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||
|
||||
;; Predicates ;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||
(:predicates
|
||||
(robot_move ?r - robot ?z - zone)
|
||||
(pose-estimated ?p - part)
|
||||
|
||||
(robot_move ?r - robot ?z - zone)
|
||||
|
||||
);; end Predicates ;;;;;;;;;;;;;;;;;;;;
|
||||
|
||||
;; Functions ;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||
|
@ -19,21 +19,11 @@
|
|||
|
||||
);; end Functions ;;;;;;;;;;;;;;;;;;;;
|
||||
|
||||
(:durative-action get_part_state
|
||||
:parameters (?p - part)
|
||||
:duration ( = ?duration 1)
|
||||
:condition (at start (not (pose-estimated ?p)))
|
||||
:effect (at end (pose-estimated ?p))
|
||||
)
|
||||
|
||||
|
||||
;; Actions ;;;;;;;;;;;;;;;;;;;;;;;;;;;;
|
||||
(:durative-action move
|
||||
:parameters (?r - robot ?z - zone ?p - part)
|
||||
:parameters (?r - robot ?z - zone)
|
||||
:duration ( = ?duration 1)
|
||||
:condition (at start (pose-estimated ?p))
|
||||
:effect (at end (robot_move ?r ?z))
|
||||
);(at start (pose-estimated ?p))
|
||||
:effect (and (at end(robot_move ?r ?z)))
|
||||
)
|
||||
|
||||
|
||||
;; end Domain ;;;;;;;;;;;;;;;;;;;;;;;;
|
||||
);; end Domain ;;;;;;;;;;;;;;;;;;;;;;;;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue