Commit 61311149 authored by Paul Rouanet's avatar Paul Rouanet
Browse files

Add position offsets to joints

parent 6e03cfe7
......@@ -50,6 +50,7 @@
<param name="max_joint_velocity">80.</param>
<param name="safety_damping">0.5</param>
<param name="motor_reversed_polarity">${true}</param>
<param name="position_offset">0.238</param>
</joint>
<joint name="FLHFE">
<command_interface name="position">
......@@ -74,6 +75,7 @@
<param name="max_joint_velocity">80.</param>
<param name="safety_damping">0.5</param>
<param name="motor_reversed_polarity">${true}</param>
<param name="position_offset">-0.308</param>
</joint>
<joint name="FLK">
<command_interface name="position">
......@@ -98,6 +100,7 @@
<param name="max_joint_velocity">80.</param>
<param name="safety_damping">0.5</param>
<param name="motor_reversed_polarity">${true}</param>
<param name="position_offset">0.276</param>
</joint>
<joint name="FRHAA">
<command_interface name="position">
......@@ -122,6 +125,7 @@
<param name="max_joint_velocity">80.</param>
<param name="safety_damping">0.5</param>
<param name="motor_reversed_polarity">${true}</param>
<param name="position_offset">-0.115</param>
</joint>
<joint name="FRHFE">
<command_interface name="position">
......@@ -146,6 +150,7 @@
<param name="max_joint_velocity">80.</param>
<param name="safety_damping">0.5</param>
<param name="motor_reversed_polarity">${false}</param>
<param name="position_offset">-0.584</param>
</joint>
<joint name="FRK">
<command_interface name="position">
......@@ -165,6 +170,7 @@
<param name="max_joint_velocity">80.</param>
<param name="safety_damping">0.5</param>
<param name="motor_reversed_polarity">${false}</param>
<param name="position_offset">0.432</param>
</joint>
<sensor name="IMU">
<state_interface name="gyroscope"/>
......
Supports Markdown
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment