runtime/rbs_bt_executor/bt_trees/grasp_object.xml
Bill Finger 213179adbd feat: enhance pick-and-place functionality with behavior tree support for place operations
- Added `GetPlacePose` skill client library and associated service node to handle place pose retrieval, including preplace and postplace poses.
- Created new behavior trees (`pick_and_place.xml`, `place_object.xml`) for handling pick-and-place operations with enhanced modularity.
- Updated `AssemblyConfig` to include `place_poses` alongside `grasp_poses`, improving flexibility in assembly workflows.
- Refactored YAML parsing and codebase to differentiate between `grasp_poses` and `place_poses` for better clarity and maintainability.
- Updated related XML behavior tree nodes, scripts, and skill structures to integrate `GetPlacePose` functionality.
- Adjusted gripper command maximum effort to `3.0` for improved control.
- Added a new message definition for `GetPlacePose` service in the `rbs_utils_interfaces` package.
- Updated CMakeLists.txt to include the new service and ensure proper build configuration.
2024-12-18 14:14:01 +03:00

63 lines
2.2 KiB
XML

<?xml version='1.0' encoding='utf-8'?>
<root BTCPP_format="4">
<BehaviorTree ID="GraspObject">
<Sequence>
<!-- <Script code="open_gripper_limit:='-0.014'" /> -->
<!-- <Script code="close_gripper_limit:='0.0'" /> -->
<!---->
<!-- <Script code="robot_name:='rbs_arm'" /> -->
<!-- <Script code="object_name:='box'" /> -->
<!---->
<!-- <Script code="grasp_service:='/get_grasp_poses'" /> -->
<!-- <Script code="move_action:='/mtp_jtc'" /> -->
<!-- <Script code="grpper_action:='/gripper_controller/gripper_cmd'" /> -->
<Action ID="GetGraspPose"
object_name="box"
service_name="{grasp_service}"
grasp_pose="{grasp_pose}"
pregrasp_pose="{pregrasp_pose}"
postgrasp_pose="{postgrasp_pose}" />
<Action ID="MoveToPose" pose="{pregrasp_pose}" duration="5.0" robot_name="{robot_name}"
action_name="{move_action}" />
<Action ID="GripperCommand" open_limit="{open_gripper_limit}" close_limit="{close_gripper_limit}" state="open"
action_name="{gripper_action}" />
<Action ID="MoveToPose" pose="{grasp_pose}" duration="2.0" robot_name="{robot_name}"
action_name="{move_action}" />
<Action ID="GripperCommand" open_limit="{open_gripper_limit}" close_limit="{close_gripper_limit}" state="close"
action_name="{gripper_action}" />
<Action ID="MoveToPose" pose="{postgrasp_pose}" duration="2.0" robot_name="{robot_name}"
action_name="{move_action}" />
</Sequence>
</BehaviorTree>
<TreeNodesModel>
<Action ID="GetGraspPose">
<input_port name="object_name" />
<input_port name="service_name" />
<output_port name="grasp_pose" />
<output_port name="pregrasp_pose" />
<output_port name="postgrasp_pose" />
</Action>
<Action ID="MoveToPose">
<input_port name="pose" />
<input_port name="robot_name" />
<input_port name="action_name" />
</Action>
<Action ID="GripperCommand">
<input_port name="open_limit" />
<input_port name="close_limit" />
<input_port name="state" />
<input_port name="action_name"/>
</Action>
</TreeNodesModel>
</root>