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
14 changes: 14 additions & 0 deletions robots/franka/franka.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -222,6 +222,20 @@
<inertia ixx="0.3" ixy="0.0" ixz="0.0" iyy="0.3" iyz="0.0" izz="0.3" />
</inertial>
</link>
<!-- Fixed Joint from link 8 to EE -->
<joint name="panda_ee_joint" type="fixed">
<parent link="panda_link8" />
<child link="panda_ee" />
<origin rpy="0 0 -0.785398163397" xyz="0 0 0.103" />
</joint>
<!-- Panda EE (official) -->
<link name="panda_ee">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0" />
<mass value="1e-10" />
<inertia ixx="1e-6" ixy="0.0" ixz="0.0" iyy="1e-6" iyz="0.0" izz="1e-6" />
</inertial>
</link>
<!-- Fixed Joint Hand from link 8 to hand -->
<joint name="panda_hand_joint" type="fixed">
<parent link="panda_link8" />
Expand Down
2 changes: 1 addition & 1 deletion src/examples/franka.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ int main()

// add a PD-controller to the arm
// set desired positions
Eigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 4., 0., -M_PI / 4, 0., M_PI / 2., 0., 0.});
Eigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 4., 0., -M_PI / 4., 0., M_PI / 2., 0., 0.});

// add the controller to the robot
auto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);
Expand Down