Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use Pro-RRT directly under MoveToJointState and MoveToWaypoint #63

Merged
merged 1 commit into from
Dec 30, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
44 changes: 26 additions & 18 deletions src/fanuc_sim/objectives/move_to_joint_state.xml
Original file line number Diff line number Diff line change
@@ -1,37 +1,45 @@
<?xml version="1.0" encoding="UTF-8" ?>
<?xml version="1.0" encoding="utf-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Move to Joint State">
<BehaviorTree
ID="Move to Joint State"
_description="Move to a specified joint state"
_subtreeOnly="true"
>
<Control ID="Sequence">
<Action ID="ActivateControllers" controller_names="{controller_names}" />
<Action
ID="InitializeMTCTask"
task_id="move_to_joint_state"
controller_names="/joint_trajectory_controller"
task="{move_to_waypoint_task}"
ID="PlanToJointGoal"
joint_goal="{target_joint_state}"
keep_orientation_tolerance="{keep_orientation_tolerance}"
link_padding="{link_padding}"
keep_orientation="{keep_orientation}"
acceleration_scale_factor="{acceleration_scale_factor}"
velocity_scale_factor="{velocity_scale_factor}"
planning_group_name="{joint_group_name}"
/>
<Action ID="SetupMTCCurrentState" task="{move_to_waypoint_task}" />
<Action
ID="SetupMTCMoveToJointState"
joint_state="{target_joint_state}"
name="SetupMTCMoveToJointState_First"
planning_group_name="manipulator"
task="{move_to_waypoint_task}"
planner_interface="moveit_default"
ID="ExecuteFollowJointTrajectory"
execute_follow_joint_trajectory_action_name="{controller_action_server}"
/>
<Action
ID="PlanMTCTask"
solution="{move_to_waypoint_solution}"
task="{move_to_waypoint_task}"
/>
<Action ID="ExecuteMTCTask" solution="{move_to_waypoint_solution}" />
</Control>
</BehaviorTree>
<TreeNodesModel>
<SubTree ID="Move to Joint State">
<input_port name="target_joint_state" default="{target_joint_state}" />
<input_port name="joint_group_name" default="manipulator" />
<input_port name="link_padding" default="0.01" />
<input_port name="keep_orientation_tolerance" default="0.05" />
<input_port name="keep_orientation" default="false" />
<input_port name="velocity_scale_factor" default="1.0" />
<input_port name="acceleration_scale_factor" default="1.0" />
<input_port
name="controller_names"
default="joint_trajectory_controller"
/>
<input_port
name="controller_action_server"
default="/joint_trajectory_controller/follow_joint_trajectory"
/>
<MetadataFields>
<Metadata subcategory="Motion - Execute" />
</MetadataFields>
47 changes: 22 additions & 25 deletions src/fanuc_sim/objectives/move_to_waypoint.xml
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
<?xml version="1.0" encoding="utf-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Move to Waypoint">
<BehaviorTree
ID="Move to Waypoint"
@@ -11,42 +12,38 @@
waypoint_name="{waypoint_name}"
joint_group_name="{joint_group_name}"
/>
<Action
ID="InitializeMTCTask"
task_id="move_to_named_pose"
<SubTree
ID="Move to Joint State"
_collapsed="true"
velocity_scale_factor="{velocity_scale_factor}"
acceleration_scale_factor="{acceleration_scale_factor}"
link_padding="{link_padding}"
keep_orientation_tolerance="{keep_orientation_tolerance}"
keep_orientation="{keep_orientation}"
target_joint_state="{target_joint_state}"
controller_names="{controller_names}"
task="{move_to_waypoint_task}"
/>
<Action ID="SetupMTCCurrentState" task="{move_to_waypoint_task}" />
<Action
ID="SetupMTCMoveToJointState"
joint_state="{target_joint_state}"
name="SetupMTCMoveToJointState"
planning_group_name="{joint_group_name}"
planner_interface="{planner_interface}"
constraints="{constraints}"
task="{move_to_waypoint_task}"
/>
<Action
ID="PlanMTCTask"
solution="{move_to_waypoint_solution}"
task="{move_to_waypoint_task}"
/>
<Action
ID="BlockingExecuteMTCTask"
solution="{move_to_waypoint_solution}"
joint_group_name="{joint_group_name}"
controller_action_server="{controller_action_server}"
/>
</Control>
</BehaviorTree>
<TreeNodesModel>
<SubTree ID="Move to Waypoint">
<input_port name="waypoint_name" default="Point A" />
<input_port name="waypoint_name" default="" />
<input_port name="joint_group_name" default="manipulator" />
<input_port name="planner_interface" default="moveit_default" />
<input_port name="link_padding" default="0.01" />
<input_port name="keep_orientation_tolerance" default="0.05" />
<input_port name="keep_orientation" default="false" />
<input_port name="velocity_scale_factor" default="1.0" />
<input_port name="acceleration_scale_factor" default="1.0" />
<input_port
name="controller_names"
default="/joint_trajectory_controller"
/>
<input_port
name="controller_action_server"
default="/joint_trajectory_controller/follow_joint_trajectory"
/>
<MetadataFields>
<Metadata subcategory="Motion - Execute" />
</MetadataFields>
3 changes: 3 additions & 0 deletions src/lab_sim/config/moveit/picknik_ur.srdf
Original file line number Diff line number Diff line change
@@ -195,4 +195,7 @@
<disable_collisions link1="wrist_2_link" link2="wrist_3_link" reason="Adjacent"/>
<disable_collisions link1="wrist_2_link" link2="wrist_mounted_camera_link" reason="Never"/>
<disable_collisions link1="wrist_3_link" link2="wrist_mounted_camera_link" reason="Never"/>
<disable_collisions link1="robotiq_85_right_finger_link" link2="robotiq_85_right_finger_tip_link" reason="Never"/>
<disable_collisions link1="robotiq_85_left_finger_link" link2="robotiq_85_left_finger_tip_link" reason="Never"/>
<disable_collisions link1="base_link_inertia" link2="shoulder_link" reason="Never"/>
</robot>
36 changes: 9 additions & 27 deletions src/lab_sim/objectives/3_waypoint_pick_and_place.xml
Original file line number Diff line number Diff line change
@@ -13,9 +13,7 @@
ID="Move to Waypoint"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
<Action
ID="MoveGripperAction"
@@ -31,9 +29,7 @@
ID="Move to Waypoint"
waypoint_name="Pick Cube"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
<Action
ID="MoveGripperAction"
@@ -44,16 +40,12 @@
ID="Move to Waypoint"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
<SubTree
ID="Move to Waypoint"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
waypoint_name="Place Cube"
/>
<Action
@@ -65,9 +57,7 @@
ID="Move to Waypoint"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
</Control>
<!--Pick object from where it was placed, put it down on the original location, and go back to center pose-->
@@ -76,9 +66,7 @@
ID="Move to Waypoint"
waypoint_name="Place Cube"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
<Action
ID="MoveGripperAction"
@@ -89,17 +77,13 @@
ID="Move to Waypoint"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
<SubTree
ID="Move to Waypoint"
waypoint_name="Pick Cube"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
<Action
ID="MoveGripperAction"
@@ -110,9 +94,7 @@
ID="Move to Waypoint"
waypoint_name="Look at Table"
joint_group_name="manipulator"
controller_names="/joint_trajectory_controller /robotiq_gripper_controller"
planner_interface="moveit_default"
constraints="{constraints}"
controller_names="/joint_trajectory_controller"
/>
</Control>
</Control>
Loading