Pose Estimation Skill Megapose6D fixes
This commit is contained in:
parent
ce03b17c48
commit
324ae82c20
9 changed files with 94102 additions and 220619 deletions
|
@ -1,155 +1,17 @@
|
|||
<?xml version="1.0"?>
|
||||
<root main_tree_to_execute="MainTree">
|
||||
<BehaviorTree ID="MainTree">
|
||||
<root main_tree_to_execute="PoseEstimation">
|
||||
<BehaviorTree ID="PoseEstimation">
|
||||
<Sequence>
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box1"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
<Action ID="PoseEstimation"
|
||||
ObjectName="!/home/shalenikol/robossembler_ws/src/robossembler-ros2/rbs_perception/config/str_param.json"
|
||||
ReqKind = "calibrate"
|
||||
server_name="/pose_estimation/change_state"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box2"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
<Action ID="PoseEstimation"
|
||||
ObjectName=""
|
||||
ReqKind = "activate"
|
||||
server_name="/pose_estimation/change_state"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box3"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box4"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box5"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box6"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
|
||||
|
||||
|
||||
</Sequence>
|
||||
</BehaviorTree>
|
||||
|
||||
<TreeNodesModel>
|
||||
<Action ID="MoveToPose">
|
||||
<input_port name="robot_name"/>
|
||||
<input_port name="pose_name"/>
|
||||
</Action>
|
||||
</TreeNodesModel>
|
||||
</root>
|
155
rbs_bt_executor/bt_trees/test_tree_main.xml
Normal file
155
rbs_bt_executor/bt_trees/test_tree_main.xml
Normal file
|
@ -0,0 +1,155 @@
|
|||
<?xml version="1.0"?>
|
||||
<root main_tree_to_execute="MainTree">
|
||||
<BehaviorTree ID="MainTree">
|
||||
<Sequence>
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box1"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box2"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box3"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box4"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box5"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
<Action ID="GetPickPlacePoses"
|
||||
ObjectName="box6"
|
||||
GraspDirection = "y"
|
||||
PlaceDirection = "z"
|
||||
GraspPose="{GraspPose}"
|
||||
PostGraspPose="{PostGraspPose}"
|
||||
PostPostGraspPose="{PostPostGraspPose}"
|
||||
PreGraspPose="{PreGraspPose}"
|
||||
PlacePose="{PlacePose}"
|
||||
PrePlacePose="{PrePlacePose}"
|
||||
PostPlacePose="{PostPlacePose}"
|
||||
server_name="/get_pick_place_pose_service"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PreGraspPose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{GraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "close" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPostGraspPose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PrePlacePose}" server_name="/move_topose" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
<Action ID="GripperControl" pose = "open" server_name="/gripper_control" server_timeout="10" cancel_timeout="5" />
|
||||
<Action ID="MoveToPose" robot_name="ur_manipulator_gripper" pose="{PostPlacePose}" server_name="/move_cartesian" server_timeout="10000" cancel_timeout="5000" />
|
||||
|
||||
|
||||
|
||||
|
||||
</Sequence>
|
||||
</BehaviorTree>
|
||||
|
||||
<TreeNodesModel>
|
||||
<Action ID="MoveToPose">
|
||||
<input_port name="robot_name"/>
|
||||
<input_port name="pose_name"/>
|
||||
</Action>
|
||||
</TreeNodesModel>
|
||||
</root>
|
|
@ -5,12 +5,12 @@
|
|||
<Action ID="PoseEstimation"
|
||||
ObjectName="fork"
|
||||
ReqKind = "configure"
|
||||
server_name="/image_sub2/change_state"
|
||||
server_name="/pose_estimation/change_state"
|
||||
server_timeout="1000"/>
|
||||
<Action ID="PoseEstimation"
|
||||
ObjectName="None"
|
||||
ObjectName=""
|
||||
ReqKind = "activate"
|
||||
server_name="/image_sub2/change_state"
|
||||
server_name="/pose_estimation/change_state"
|
||||
server_timeout="1000"/>
|
||||
</Sequence>
|
||||
</BehaviorTree>
|
|
@ -22,12 +22,10 @@ public:
|
|||
|
||||
while (!_set_params_client->wait_for_service(1s)) {
|
||||
if (!rclcpp::ok()) {
|
||||
RCLCPP_ERROR(_node->get_logger(),
|
||||
"Interrupted while waiting for the service. Exiting.");
|
||||
RCLCPP_ERROR(_node->get_logger(), "Interrupted while waiting for the service. Exiting.");
|
||||
break;
|
||||
}
|
||||
RCLCPP_WARN(_node->get_logger(),
|
||||
"service not available, waiting again...");
|
||||
RCLCPP_WARN(_node->get_logger(), "service not available, waiting again...");
|
||||
}
|
||||
|
||||
_model_name = getInput<std::string>("ObjectName").value();
|
||||
|
@ -71,6 +69,9 @@ private:
|
|||
if (req_type == "configure") {
|
||||
set_mesh_param();
|
||||
transition_id_ = lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE;
|
||||
} else if (req_type == "calibrate") {
|
||||
set_str_param();
|
||||
transition_id_ = lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE;
|
||||
} else if (req_type == "activate") {
|
||||
transition_id_ = lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE;
|
||||
} else if (req_type == "deactivate") {
|
||||
|
@ -78,6 +79,7 @@ private:
|
|||
} else if (req_type == "cleanup") {
|
||||
transition_id_ = lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP;
|
||||
}
|
||||
//calibrate
|
||||
translation.set__id(transition_id_);
|
||||
return translation;
|
||||
}
|
||||
|
@ -91,6 +93,13 @@ private:
|
|||
return model_path;
|
||||
}
|
||||
|
||||
void set_str_param() {
|
||||
RCLCPP_INFO_STREAM(_node->get_logger(), "Set string parameter: <" + _model_name + ">");
|
||||
|
||||
std::vector<rclcpp::Parameter> _parameters{rclcpp::Parameter("mesh_path", _model_name)};
|
||||
_set_params_client->set_parameters(_parameters);
|
||||
}
|
||||
|
||||
void set_mesh_param() {
|
||||
auto _package_name = ament_index_cpp::get_package_share_directory("rbs_perception");
|
||||
_model_path = build_model_path(_model_name, _package_name);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue