diff --git a/src/lab_sim/objectives/stationary_admittance.xml b/src/lab_sim/objectives/stationary_admittance.xml
new file mode 100644
index 00000000..ffa4a008
--- /dev/null
+++ b/src/lab_sim/objectives/stationary_admittance.xml
@@ -0,0 +1,89 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/lab_sim/objectives/stationary_admittance.yaml b/src/lab_sim/objectives/stationary_admittance.yaml
new file mode 100644
index 00000000..9822ff7e
--- /dev/null
+++ b/src/lab_sim/objectives/stationary_admittance.yaml
@@ -0,0 +1,105 @@
+SetAdmittanceParameters:
+ admittance:
+ damping_ratio_position:
+ max: 1000
+ min: 0
+ x: 160
+ y: 160
+ z: 160
+ damping_ratio_rotation:
+ max: 1000
+ min: 0
+ x: 1
+ y: 1
+ z: 1
+ joint_damping:
+ max: 1000
+ min: 0
+ value: 1
+ mass_position:
+ max: 1000
+ min: 0.001
+ x: 4
+ y: 4
+ z: 4
+ mass_rotation:
+ max: 1000
+ min: 0.001
+ x: 1
+ y: 1
+ z: 1
+ selected_axes:
+ rx: true
+ ry: true
+ rz: true
+ x: true
+ y: true
+ z: true
+ stiffness_position:
+ max: 1000
+ min: 0
+ x: 40
+ y: 40
+ z: 40
+ stiffness_rotation:
+ max: 1000
+ min: 0
+ x: 1
+ y: 1
+ z: 1
+ base_frame: base_link
+ control_frame: grasp_link
+ controller_name: ''
+ end_effector_frame: grasp_link
+admittance:
+ damping_ratio_position:
+ max: 1000
+ min: 0
+ x: 160
+ y: 160
+ z: 80
+ damping_ratio_rotation:
+ max: 1000
+ min: 0
+ x: 1
+ y: 1
+ z: 1
+ joint_damping:
+ max: 1000
+ min: 0
+ value: 1
+ mass_position:
+ max: 1000
+ min: 0.001
+ x: 4
+ y: 4
+ z: 4
+ mass_rotation:
+ max: 1000
+ min: 0.001
+ x: 1
+ y: 1
+ z: 1
+ selected_axes:
+ rx: true
+ ry: true
+ rz: true
+ x: true
+ y: true
+ z: true
+ stiffness_position:
+ max: 1000
+ min: 0
+ x: 40
+ y: 40
+ z: 40
+ stiffness_rotation:
+ max: 1000
+ min: 0
+ x: 1
+ y: 1
+ z: 1
+base_frame: base_link
+control_frame: grasp_link
+controller_name: ''
+end_effector_frame: grasp_link
diff --git a/src/lab_sim/test/objectives_integration_test.py b/src/lab_sim/test/objectives_integration_test.py
index 185e09fd..beba7cda 100644
--- a/src/lab_sim/test/objectives_integration_test.py
+++ b/src/lab_sim/test/objectives_integration_test.py
@@ -39,6 +39,7 @@
cancel_objectives = {
"3 Waypoints Pick and Place",
+ "Stationary Admittance",
"Cycle Between Waypoints",
"Grasp Planning",
"Grasp Pose Tuning With April Tag",
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/config/control/franka_ros2_control.yaml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/config/control/franka_ros2_control.yaml
index 389c2f68..e17ed023 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/config/control/franka_ros2_control.yaml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/config/control/franka_ros2_control.yaml
@@ -27,6 +27,7 @@ joint_trajectory_controller:
state_interfaces:
- position
- velocity
+ allow_partial_joints_goal: true
joints:
- left_fr3_joint1
- left_fr3_joint2
@@ -42,7 +43,6 @@ joint_trajectory_controller:
- right_fr3_joint5
- right_fr3_joint6
- right_fr3_joint7
- allow_partial_joints_goal: true
gains:
left_fr3_joint1: { p: 600., d: 30., i: 0., i_clamp: 1. }
left_fr3_joint2: { p: 600., d: 30., i: 0., i_clamp: 1. }
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/franka3.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/franka3.xml
index acb31f15..d3f06047 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/franka3.xml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/franka3.xml
@@ -100,7 +100,7 @@
@@ -411,7 +411,7 @@
@@ -775,7 +775,7 @@
class="fr3"
name="left_fr3_finger_joint1"
joint="left_fr3_finger_joint1"
- kp="5000"
+ kp="1000"
kv="500"
/>
@@ -834,7 +834,7 @@
class="fr3"
name="right_fr3_finger_joint1"
joint="right_fr3_finger_joint1"
- kp="5000"
+ kp="1000"
kv="500"
/>
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/scene.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/scene.xml
index 848b22c2..4e688606 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/scene.xml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/description/mujoco/scene.xml
@@ -2,6 +2,8 @@
+
+
@@ -43,17 +45,64 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -77,6 +126,12 @@
left_fr3_joint7
left_fr3_finger1
left_fr3_finger2
+ block_green_1 [x y z qw qx qy qz]
+ block_green_2 [x y z qw qx qy qz]
+ block_green_3 [x y z qw qx qy qz]
+ block_red_1 [x y z qw qx qy qz]
+ block_red_2 [x y z qw qx qy qz]
+ block_red_3 [x y z qw qx qy qz]
qvel:
right_fr3_joint1
right_fr3_joint2
@@ -96,6 +151,12 @@
left_fr3_joint7
left_fr3_finger1
left_fr3_finger2
+ block_green_1 [x y z r p y]
+ block_green_2 [x y z r p y]
+ block_green_3 [x y z r p y]
+ block_red_1 [x y z r p y]
+ block_red_2 [x y z r p y]
+ block_red_3 [x y z r p y]
ctrl:
right_fr3_joint1
right_fr3_joint2
@@ -113,14 +174,25 @@
left_fr3_joint6
left_fr3_joint7
left_fr3_finger1 - We control only one finger.
-
-->
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/create_point_cloud_vector_from_masks.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/create_point_cloud_vector_from_masks.xml
new file mode 100644
index 00000000..6c52cef8
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/create_point_cloud_vector_from_masks.xml
@@ -0,0 +1,49 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/draw.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/draw.xml
index d9d31011..26988ada 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/draw.xml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/draw.xml
@@ -50,6 +50,7 @@
debug_solution="{debug_solution}"
ik_cartesian_space_density="0.01000"
ik_joint_space_density="0.050000"
+ tip_offset="0;0;0.005;0;0;0"
planning_group_name="{planning_group_name}"
tip_links="{tip_link}"
/>
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_green_block.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_green_block.xml
new file mode 100644
index 00000000..699e340a
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_green_block.xml
@@ -0,0 +1,23 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_red_block.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_red_block.xml
new file mode 100644
index 00000000..6e77dce2
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_red_block.xml
@@ -0,0 +1,23 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_with_prompt.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_with_prompt.xml
new file mode 100644
index 00000000..6aa339e6
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/find_with_prompt.xml
@@ -0,0 +1,55 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/ml_segment_image_from_text_prompt.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/ml_segment_image_from_text_prompt.xml
new file mode 100644
index 00000000..68ff8a22
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/ml_segment_image_from_text_prompt.xml
@@ -0,0 +1,37 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_left_home.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_left_home.xml
index 5079562c..a4974137 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_left_home.xml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_left_home.xml
@@ -19,7 +19,7 @@
link_padding="0.01"
seed="0"
velocity_scale_factor="1.0"
- waypoint_name="Left Home"
+ waypoint_name="Home"
/>
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_right_home.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_right_home.xml
index 15225c32..b0de5efa 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_right_home.xml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/move_right_home.xml
@@ -19,7 +19,7 @@
link_padding="0.01"
seed="0"
velocity_scale_factor="1.0"
- waypoint_name="Right Home"
+ waypoint_name="Home"
/>
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/segment_image_from_no_negative_text_prompt_subtree.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/segment_image_from_no_negative_text_prompt_subtree.xml
new file mode 100644
index 00000000..f99a0b1d
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/segment_image_from_no_negative_text_prompt_subtree.xml
@@ -0,0 +1,64 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/segment_point_cloud_from_text.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/segment_point_cloud_from_text.xml
new file mode 100644
index 00000000..941fc9ea
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/segment_point_cloud_from_text.xml
@@ -0,0 +1,114 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/sort_blocks.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/sort_blocks.xml
new file mode 100644
index 00000000..11673a1a
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/sort_blocks.xml
@@ -0,0 +1,305 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/take_snap.xml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/take_snap.xml
new file mode 100644
index 00000000..672f5f06
--- /dev/null
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/objectives/take_snap.xml
@@ -0,0 +1,33 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/moveit_pro_franka_configs/franka_dual_arm_sim/waypoints/waypoints.yaml b/src/moveit_pro_franka_configs/franka_dual_arm_sim/waypoints/waypoints.yaml
index 28d6c46d..d664a66a 100644
--- a/src/moveit_pro_franka_configs/franka_dual_arm_sim/waypoints/waypoints.yaml
+++ b/src/moveit_pro_franka_configs/franka_dual_arm_sim/waypoints/waypoints.yaml
@@ -1,41 +1,173 @@
-- name: Left Home
+- description: ''
+ favorite: false
joint_group_names:
- left_manipulator
+ - right_manipulator
+ - manipulator
joint_state:
+ effort: []
header:
frame_id: world
stamp:
- sec: 0
nanosec: 0
- name: [left_fr3_joint1, left_fr3_joint2, left_fr3_joint3, left_fr3_joint4, left_fr3_joint5, left_fr3_joint6, left_fr3_joint7]
- position: [0, -0.7854, 0, -2.3562, 0, 1.5707, 0.7853]
+ sec: 0
+ name:
+ - right_fr3_joint1
+ - right_fr3_joint2
+ - right_fr3_joint3
+ - right_fr3_joint4
+ - right_fr3_joint5
+ - right_fr3_joint6
+ - right_fr3_joint7
+ - left_fr3_joint1
+ - left_fr3_joint2
+ - left_fr3_joint3
+ - left_fr3_joint4
+ - left_fr3_joint5
+ - left_fr3_joint6
+ - left_fr3_joint7
+ position:
+ - 0
+ - -0.7854
+ - 0
+ - -2.3562
+ - 0
+ - 1.5707
+ - 0.7853
+ - 0
+ - -0.7854
+ - 0
+ - -2.3562
+ - 0
+ - 1.5707
+ - 0.7853
velocity: []
- effort: []
-- name: Right Home
+ multi_dof_joint_state:
+ header:
+ frame_id: ''
+ stamp:
+ nanosec: 0
+ sec: 0
+ joint_names: []
+ transforms: []
+ twist: []
+ wrench: []
+ name: Home
+- description: ''
+ favorite: false
joint_group_names:
+ - left_manipulator
- right_manipulator
+ - manipulator
joint_state:
+ effort: []
header:
- frame_id: world
+ frame_id: ''
stamp:
- sec: 0
nanosec: 0
- name: [right_fr3_joint1, right_fr3_joint2, right_fr3_joint3, right_fr3_joint4, right_fr3_joint5, right_fr3_joint6, right_fr3_joint7]
- position: [0, -0.7854, 0, -2.3562, 0, 1.5707, 0.7853]
+ sec: 0
+ name:
+ - left_fr3_joint1
+ - left_fr3_joint2
+ - left_fr3_joint3
+ - left_fr3_joint4
+ - left_fr3_joint5
+ - left_fr3_joint6
+ - left_fr3_joint7
+ - left_fr3_finger_joint1
+ - right_fr3_joint1
+ - right_fr3_joint2
+ - right_fr3_joint3
+ - right_fr3_joint4
+ - right_fr3_joint5
+ - right_fr3_joint6
+ - right_fr3_joint7
+ - right_fr3_finger_joint1
+ position:
+ - 0.7631439836051002
+ - -1.7256971279852666
+ - 1.0600563247617216
+ - -2.389989603996341
+ - 1.5875756227741065
+ - 1.946673982728032
+ - 1.228841619420035
+ - -1.206526992588383e-06
+ - -0.0013177742221101801
+ - -0.78657302417956
+ - -0.011311296228273288
+ - -2.363709370359536
+ - -0.0017492815088556665
+ - 1.5691264546747385
+ - 0.7852388406584784
+ - 0.0001266099321349138
velocity: []
- effort: []
-- name: Home
+ multi_dof_joint_state:
+ header:
+ frame_id: ''
+ stamp:
+ nanosec: 0
+ sec: 0
+ joint_names: []
+ transforms: []
+ twist: []
+ wrench: []
+ name: Place Left
+- description: ''
+ favorite: false
joint_group_names:
+ - left_manipulator
+ - right_manipulator
- manipulator
joint_state:
+ effort: []
header:
- frame_id: world
+ frame_id: ''
stamp:
- sec: 0
nanosec: 0
- name: [right_fr3_joint1, right_fr3_joint2, right_fr3_joint3, right_fr3_joint4, right_fr3_joint5, right_fr3_joint6, right_fr3_joint7,
- left_fr3_joint1, left_fr3_joint2, left_fr3_joint3, left_fr3_joint4, left_fr3_joint5, left_fr3_joint6, left_fr3_joint7]
- position: [0, -0.7854, 0, -2.3562, 0, 1.5707, 0.7853,
- 0, -0.7854, 0, -2.3562, 0, 1.5707, 0.7853]
+ sec: 0
+ name:
+ - left_fr3_joint1
+ - left_fr3_joint2
+ - left_fr3_joint3
+ - left_fr3_joint4
+ - left_fr3_joint5
+ - left_fr3_joint6
+ - left_fr3_joint7
+ - left_fr3_finger_joint1
+ - right_fr3_joint1
+ - right_fr3_joint2
+ - right_fr3_joint3
+ - right_fr3_joint4
+ - right_fr3_joint5
+ - right_fr3_joint6
+ - right_fr3_joint7
+ - right_fr3_finger_joint1
+ position:
+ - 0.0007136559011727871
+ - -0.7866070922383005
+ - 0.0058260641539913584
+ - -2.3598693918370577
+ - 0.0004167706563591327
+ - 1.5698542053401963
+ - 0.7853530142146962
+ - -3.102443235020368e-05
+ - -0.9123206417362171
+ - -1.6248200992913444
+ - -0.8998577753262823
+ - -2.488156178512647
+ - -1.4102913730535007
+ - 2.102824648497987
+ - -0.896605178475249
+ - 3.0056037776778505e-07
velocity: []
- effort: []
+ multi_dof_joint_state:
+ header:
+ frame_id: ''
+ stamp:
+ nanosec: 0
+ sec: 0
+ joint_names: []
+ transforms: []
+ twist: []
+ wrench: []
+ name: Place Right