Skip to content

Commit

Permalink
current_to_effortの修正
Browse files Browse the repository at this point in the history
  • Loading branch information
Kuwamai committed Nov 1, 2023
1 parent 803b022 commit c93e8f9
Showing 1 changed file with 11 additions and 11 deletions.
22 changes: 11 additions & 11 deletions urdf/sciurus17.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">3.60</param>
</joint>

<joint name="${NAME_JOINT_NECK_1}">
Expand All @@ -31,7 +31,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">1.79</param>
</joint>

<joint name="${NAME_JOINT_NECK_2}">
Expand All @@ -42,7 +42,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">1.79</param>
</joint>

<joint name="${NAME_JOINT_ARM_R_1}">
Expand All @@ -53,7 +53,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">3.60</param>
</joint>

<joint name="${NAME_JOINT_ARM_R_2}">
Expand All @@ -64,7 +64,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">3.60</param>
</joint>

<joint name="${NAME_JOINT_ARM_R_3}">
Expand All @@ -86,7 +86,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">2.00</param>
</joint>

<joint name="${NAME_JOINT_ARM_R_5}">
Expand Down Expand Up @@ -130,7 +130,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">1.79</param>
</joint>

<joint name="${NAME_JOINT_ARM_L_1}">
Expand All @@ -141,7 +141,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">3.60</param>
</joint>

<joint name="${NAME_JOINT_ARM_L_2}">
Expand All @@ -152,7 +152,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">3.60</param>
</joint>

<joint name="${NAME_JOINT_ARM_L_3}">
Expand All @@ -174,7 +174,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">2.00</param>
</joint>

<joint name="${NAME_JOINT_ARM_L_5}">
Expand Down Expand Up @@ -218,7 +218,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
<param name="current_to_effort">2.20</param>
<param name="current_to_effort">1.79</param>
</joint>

</ros2_control>
Expand Down

0 comments on commit c93e8f9

Please sign in to comment.