Skip to content

Commit 73cad93

Browse files
committed
Add payload testing scenario
1 parent a7d1a89 commit 73cad93

4 files changed

+102
-0
lines changed

models/iiwa7_with_wsg_welded.dmd.yaml

+7
Original file line numberDiff line numberDiff line change
@@ -25,3 +25,10 @@ directives:
2525
X_PC:
2626
translation: [0.0, 0.0, 0.1]
2727
rotation: !Rpy { deg: [90.0, 0.0, 90.0]}
28+
29+
- add_frame:
30+
name: wsg_body_frame
31+
X_PF:
32+
base_frame: iiwa::iiwa_link_7
33+
translation: [0.0, 0.0, 0.1]
34+
rotation: !Rpy { deg: [90.0, 0.0, 90.0]}

models/iiwa_with_box_payload.dmd.yaml

+43
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
directives:
2+
- add_model:
3+
name: iiwa_base_metal_plate
4+
file: package://robot_payload_id/iiwa_base_metal_plate.sdf
5+
- add_weld:
6+
parent: world
7+
child: iiwa_base_metal_plate::iiwa_base_metal_plate_base_link
8+
X_PC:
9+
translation: [-0.005, 0.0, 0.00635]
10+
11+
- add_model:
12+
name: iiwa
13+
file: package://drake/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf
14+
default_joint_positions:
15+
iiwa_joint_1: [0]
16+
iiwa_joint_2: [0.1]
17+
iiwa_joint_3: [0]
18+
iiwa_joint_4: [-1.2]
19+
iiwa_joint_5: [0]
20+
iiwa_joint_6: [1.6]
21+
iiwa_joint_7: [0]
22+
- add_weld:
23+
parent: world
24+
child: iiwa::iiwa_link_0
25+
X_PC:
26+
translation: [0.0, 0.0, 0.0127]
27+
28+
- add_model:
29+
name: payload_box
30+
file: package://robot_payload_id/payload_box.sdf
31+
- add_weld:
32+
parent: iiwa::iiwa_link_7
33+
child: payload_box::payload_box_link
34+
X_PC:
35+
translation: [0.1, 0.0, 0.3]
36+
rotation: !Rpy { deg: [90.0, 0.0, 30.0]}
37+
38+
- add_frame:
39+
name: payload_frame
40+
X_PF:
41+
base_frame: iiwa::iiwa_link_7
42+
translation: [0.1, 0.0, 0.3]
43+
rotation: !Rpy { deg: [90.0, 0.0, 30.0]}
+14
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
directives:
2+
- add_directives:
3+
file: package://robot_payload_id/iiwa_with_box_payload.dmd.yaml
4+
plant_config:
5+
time_step: 1e-3 # 1e-3 for torque_only mode and 5e-3 otherwise
6+
contact_model: "hydroelastic_with_fallback"
7+
discrete_contact_approximation: "sap"
8+
model_drivers:
9+
iiwa: !IiwaDriver
10+
lcm_bus: "default"
11+
control_mode: torque_only
12+
lcm_buses:
13+
default:
14+
lcm_url: ""

models/payload_box.sdf

+38
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
<?xml version="1.0"?>
2+
<sdf version="1.7">
3+
<model name="payload_box">
4+
<link name="payload_box_link">
5+
<inertial>
6+
<pose>0 0 0.07 0 0 0</pose>
7+
<mass>3.863</mass>
8+
<inertia>
9+
<ixx>0.5</ixx>
10+
<ixy>0</ixy>
11+
<ixz>0</ixz>
12+
<iyy>0.5</iyy>
13+
<iyz>0</iyz>
14+
<izz>0.5</izz>
15+
</inertia>
16+
</inertial>
17+
<visual name="visual">
18+
<pose>0 0 0 0 0 0</pose>
19+
<geometry>
20+
<box>
21+
<size>.1 .1 .26</size>
22+
</box>
23+
</geometry>
24+
<material>
25+
<diffuse>0.7 0.7 0.7 1.0</diffuse>
26+
</material>
27+
</visual>
28+
<collision name="collision">
29+
<pose>0 0 0 0 0 0</pose>
30+
<geometry>
31+
<box>
32+
<size>.1 .1 .26</size>
33+
</box>
34+
</geometry>
35+
</collision>
36+
</link>
37+
</model>
38+
</sdf>

0 commit comments

Comments
 (0)