Skip to content
Merged
Show file tree
Hide file tree
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
89 changes: 89 additions & 0 deletions src/lab_sim/objectives/stationary_admittance.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,89 @@
<?xml version="1.0" encoding="UTF-8" ?>
<root BTCPP_format="4" main_tree_to_execute="Stationary Admittance">
<!--//////////-->
<BehaviorTree
ID="Stationary Admittance"
_description="Puts the arm into Cartesian admittance mode"
_favorite="false"
>
<Control ID="Sequence" name="TopLevelSequence">
<SubTree
ID="Move to Waypoint"
_collapsed="true"
controller_names="joint_trajectory_controller"
planner_interface="moveit_default"
waypoint_name="Home"
acceleration_scale_factor="1.0"
controller_action_server="/joint_trajectory_controller/follow_joint_trajectory"
keep_orientation="false"
keep_orientation_tolerance="0.05"
link_padding="0.01"
seed="0"
velocity_scale_factor="1.0"
joint_group_name="manipulator"
/>
<Action
ID="SwitchController"
activate_asap="true"
automatic_deactivation="true"
controller_list_action_name="/controller_manager/list_controllers"
controller_switch_action_name="/controller_manager/switch_controller"
strictness="1"
timeout="-1.000000"
activate_controllers="joint_trajectory_admittance_controller"
/>
<Decorator ID="Delay" delay_msec="2000">
<Action
ID="CallTriggerService"
response_timeout="3.000000"
service_name="/joint_trajectory_admittance_controller/zero_fts/tool0"
wait_for_server_available_timeout="3.000000"
/>
</Decorator>
<Action
ID="SetAdmittanceParameters"
config_file_name="stationary_admittance.yaml"
admittance_parameters_msg="{admittance_parameters_msg}"
/>
<Action
ID="GetCurrentPlanningScene"
planning_scene_msg="{planning_scene}"
/>
<Action
ID="GetRobotJointState"
joint_state="{joint_state}"
planning_scene="{planning_scene}"
planning_group_name="manipulator"
/>
<Action
ID="CreateStationaryTrajectory"
joint_state="{joint_state}"
joint_trajectory_msg="{joint_trajectory_msg}"
trajectory_duration="10"
/>
<Action
ID="LogMessage"
log_level="info"
message="Running admittance mode for 10 seconds"
/>
<Action
ID="ExecuteTrajectoryWithAdmittance"
goal_position_tolerance="10;10;10;10;10;10;10;"
path_position_tolerance="10;10;10;10;10;10;10"
admittance_parameters_msg="{admittance_parameters_msg}"
absolute_force_torque_threshold="45;45;45;10;10;10"
joint_trajectory_msg="{joint_trajectory_msg}"
goal_duration_tolerance="-1.000000"
controller_action_name="/joint_trajectory_admittance_controller/follow_joint_trajectory"
/>
</Control>
</BehaviorTree>
<TreeNodesModel>
<SubTree ID="Stationary Admittance">
<MetadataFields>
<Metadata runnable="true" />
<Metadata subcategory="Application - Advanced Examples" />
</MetadataFields>
</SubTree>
</TreeNodesModel>
</root>
105 changes: 105 additions & 0 deletions src/lab_sim/objectives/stationary_admittance.yaml
Original file line number Diff line number Diff line change
@@ -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
1 change: 1 addition & 0 deletions src/lab_sim/test/objectives_integration_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@

cancel_objectives = {
"3 Waypoints Pick and Place",
"Stationary Admittance",
"Cycle Between Waypoints",
"Grasp Planning",
"Grasp Pose Tuning With April Tag",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ joint_trajectory_controller:
state_interfaces:
- position
- velocity
allow_partial_joints_goal: true
joints:
- left_fr3_joint1
- left_fr3_joint2
Expand All @@ -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. }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@
<body
name="left_arm"
pos="0.035 0.050681 0.356"
quat="0.8730 -0.4380 -0.0229 -0.2215"
quat="0.8657172 -0.4369879 0.0223569 -0.2430545"
>
<body name="left_base" childclass="fr3">
<body name="left_fr3_link0">
Expand Down Expand Up @@ -411,7 +411,7 @@
<body
name="right_arm"
pos="0.035 -0.050681 0.356"
quat="0.8730 0.4380 0.0229 0.2215"
quat="0.8657172 0.4369879 0.0223569 0.2430545"
>
<body name="right_base" childclass="fr3">
<body name="right_fr3_link0">
Expand Down Expand Up @@ -775,7 +775,7 @@
class="fr3"
name="left_fr3_finger_joint1"
joint="left_fr3_finger_joint1"
kp="5000"
kp="1000"
kv="500"
/>

Expand Down Expand Up @@ -834,7 +834,7 @@
class="fr3"
name="right_fr3_finger_joint1"
joint="right_fr3_finger_joint1"
kp="5000"
kp="1000"
kv="500"
/>
</actuator>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,8 @@
<include file="franka3.xml" />

<statistic center="0.2 0.2 0.5" extent="1.8" />
<size nkey="1" />
<size nuser_jnt="0" />

<visual>
<global azimuth="120" elevation="-21" fovy="58" />
Expand Down Expand Up @@ -43,17 +45,64 @@
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane" />
<site
name="scene_camera_optical_frame"
pos="1.5 0.7 1.5"
euler="2.6 -0.8 -2.14"
pos="0.7 0.0 0.65"
xyaxes="0 -1 0 -1 0 0"
/>
<camera
name="scene_camera"
pos="1.5 0.7 1.5"
pos="0.7 0.0 0.65"
fovy="58"
mode="fixed"
resolution="640 480"
euler="-0.54 0.8 2.14"
xyaxes="0 -1 0 1 0 0"
/>
<geom
name="table_front"
type="box"
size="0.4 0.3 0.01"
pos="0.6 0 0.0"
rgba="0.6 0.6 0.6 1"
/>
<geom
name="table_left"
type="box"
size="0.25 0.5 0.01"
pos="0 0.9 0.0"
rgba="0.3 0.7 0.3 1"
/>
<geom
name="table_right"
type="box"
size="0.25 0.5 0.01"
pos="0 -0.9 0.0"
rgba="0.7 0.3 0.3 1"
/>

<body name="block_green_1" pos="0.6 0 0.2">
<freejoint name="block_green_1" />
<geom type="box" size="0.025 0.025 0.025" rgba="0 0.8 0 1" />
</body>
<body name="block_green_2" pos="0.6 0.15 0.2">
<freejoint name="block_green_2" />
<geom type="box" size="0.025 0.025 0.025" rgba="0 0.8 0 1" />
</body>
<body name="block_green_3" pos="0.6 -0.15 0.2">
<freejoint name="block_green_3" />
<geom type="box" size="0.025 0.025 0.025" rgba="0 0.8 0 1" />
</body>

<body name="block_red_1" pos="0.7 0 0.2">
<freejoint name="block_red_1" />
<geom type="box" size="0.025 0.025 0.025" rgba="0.8 0 0 1" />
</body>
<body name="block_red_2" pos="0.7 0.15 0.2">
<freejoint name="block_red_2" />
<geom type="box" size="0.025 0.025 0.025" rgba="0.8 0 0 1" />
</body>
<body name="block_red_3" pos="0.7 -0.15 0.2">
<freejoint name="block_red_3" />
<geom type="box" size="0.025 0.025 0.025" rgba="0.8 0 0 1" />
</body>
</worldbody>

<keyframe>
Expand All @@ -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
Expand All @@ -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
Expand All @@ -113,14 +174,25 @@
left_fr3_joint6
left_fr3_joint7
left_fr3_finger1 - We control only one finger.

-->
<key
name="default"
qpos="0 -0.7854 0 -2.3562 0 1.5707 0.7853 0 0
0 -0.7854 0 -2.3562 0 1.5707 0.7853 0 0"
0 -0.7854 0 -2.3562 0 1.5707 0.7853 0 0
0.6 0 0.2 1 0 0 0
0.6 0.15 0.2 1 0 0 0
0.6 -0.15 0.2 1 0 0 0
0.7 0 0.2 1 0 0 0
0.7 0.15 0.2 1 0 0 0
0.7 -0.15 0.2 1 0 0 0"
qvel="0 0 0 0 0 0 0 0 0
0 0 0 0 0 0 0 0 0"
0 0 0 0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0
0 0 0 0 0 0"
ctrl="0 -0.7854 0 -2.3562 0 1.5707 0.7853 0
0 -0.7854 0 -2.3562 0 1.5707 0.7853 0"
/>
Expand Down
Loading