|
4 | 4 | <xacro:arg name="ee_id" default="franka_hand" /> |
5 | 5 | <xacro:arg name="rpy_ee" default="0 0 -0.785" /> |
6 | 6 |
|
| 7 | + <!-- Load Franka Duo Mount --> |
| 8 | + <xacro:include filename="$(find franka_description)/robots/fr3_duo/fr3_duo_mount/fr3_duo_mount.xacro"/> |
| 9 | + <xacro:property name="mount_kinematics" value="${xacro.load_yaml('$(find franka_description)/robots/fr3_duo/fr3_duo_mount/kinematics.yaml')}" /> |
| 10 | + |
7 | 11 | <!-- Load Franka robot --> |
8 | 12 | <xacro:include filename="$(find franka_description)/robots/common/franka_robot.xacro"/> |
| 13 | + |
9 | 14 | <link name="world" /> |
| 15 | + |
| 16 | + <xacro:mount name="fr3_duo" |
| 17 | + parent="world" |
| 18 | + inertials="${xacro.load_yaml('$(find franka_description)/robots/fr3_duo/fr3_duo_mount/inertials.yaml')}"> |
| 19 | + <origin xyz="0.0 0.0 0.305115" rpy="0 0 0" /> |
| 20 | + </xacro:mount> |
| 21 | + |
10 | 22 | <joint name="right_mount_joint" type="fixed"> |
11 | | - <parent link="world"/> |
| 23 | + <parent link="mount_link"/> |
12 | 24 | <child link = "right_mount"/> |
13 | | - <origin xyz="0.035 -0.050681 0.356" rpy="0.8936 -0.1746 0.4636"/> |
| 25 | + <origin xyz="${mount_kinematics['right']['kinematic']['x']} ${mount_kinematics['right']['kinematic']['y']} ${mount_kinematics['right']['kinematic']['z']}" |
| 26 | + rpy="${mount_kinematics['right']['kinematic']['roll']} ${mount_kinematics['right']['kinematic']['pitch']} ${mount_kinematics['right']['kinematic']['yaw']}"/> |
14 | 27 | </joint> |
| 28 | + |
15 | 29 | <xacro:franka_robot arm_id="fr3" |
16 | 30 | joint_limits="${xacro.load_yaml('$(find franka_description)/robots/fr3/joint_limits.yaml')}" |
17 | 31 | inertials="${xacro.load_yaml('$(find franka_description)/robots/fr3/inertials.yaml')}" |
18 | 32 | kinematics="${xacro.load_yaml('$(find franka_description)/robots/fr3/kinematics.yaml')}" |
19 | 33 | dynamics="${xacro.load_yaml('$(find franka_description)/robots/fr3/dynamics.yaml')}" |
20 | 34 | gazebo="false" |
21 | 35 | hand="true" |
| 36 | + tcp_xyz="0 0 0.1034" |
22 | 37 | ee_id="$(arg ee_id)" |
23 | 38 | with_sc="false" |
24 | 39 | ros2_control="false" |
|
27 | 42 | fake_sensor_commands="false" |
28 | 43 | gazebo_effort="false" |
29 | 44 | no_prefix="false" |
30 | | - arm_prefix="right" |
31 | | - connected_to= "right_mount"> |
| 45 | + arm_prefix="right_" |
| 46 | + connected_to= "right_mount"> <!-- This also creates the link right_mount --> |
32 | 47 | </xacro:franka_robot> |
33 | 48 |
|
34 | 49 | <!-- This link aligns the axes of the grasp frame to our required convention for motion planning tasks. --> |
|
40 | 55 | </joint> |
41 | 56 |
|
42 | 57 | <joint name="left_mount_joint" type="fixed"> |
43 | | - <parent link="world"/> |
| 58 | + <parent link="mount_link"/> |
44 | 59 | <child link = "left_mount"/> |
45 | | - <origin xyz="0.035 0.050681 0.356" rpy="-0.8936 -0.1746 -0.4636"/> |
| 60 | + <origin xyz="${mount_kinematics['left']['kinematic']['x']} ${mount_kinematics['left']['kinematic']['y']} ${mount_kinematics['left']['kinematic']['z']}" |
| 61 | + rpy="${mount_kinematics['left']['kinematic']['roll']} ${mount_kinematics['left']['kinematic']['pitch']} ${mount_kinematics['left']['kinematic']['yaw']}"/> |
46 | 62 | </joint> |
47 | 63 |
|
48 | 64 | <xacro:franka_robot arm_id="fr3" |
|
52 | 68 | dynamics="${xacro.load_yaml('$(find franka_description)/robots/fr3/dynamics.yaml')}" |
53 | 69 | gazebo="false" |
54 | 70 | hand="true" |
| 71 | + tcp_xyz="0 0 0.1034" |
55 | 72 | ee_id="$(arg ee_id)" |
56 | 73 | with_sc="false" |
57 | 74 | ros2_control="false" |
|
60 | 77 | fake_sensor_commands="false" |
61 | 78 | gazebo_effort="false" |
62 | 79 | no_prefix="false" |
63 | | - arm_prefix="left" |
64 | | - connected_to= "left_mount"> |
| 80 | + arm_prefix="left_" |
| 81 | + connected_to= "left_mount"> <!-- This also creates the link left_mount --> |
65 | 82 | </xacro:franka_robot> |
66 | 83 |
|
67 | 84 | <!-- This link aligns the axes of the grasp frame to our required convention for motion planning tasks. --> |
|
0 commit comments