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

Add joint number parameters

parent 3e4e19f9
......@@ -22,19 +22,13 @@
<param name="example_param_hw_start_duration_sec">2.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">${slowdown}</param>
<param name="FLHAA">0</param>
<param name="FLHFE">1</param>
<param name="FLK">2</param>
<param name="FRHAA">3</param>
<param name="FRHFE">4</param>
<param name="FRK">5</param>
</xacro:unless>
</xacro:unless>
</hardware>
</xacro:unless>
<joint name="FLHAA">
<command_interface name="position">
<param name="min">-0.2</param>
<param name="min">-0.5</param>
<param name="max">0.5</param>
</command_interface>
<command_interface name="velocity">
......@@ -48,11 +42,12 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<param name="motor_number">0</param>
</joint>
<joint name="FLHFE">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
<param name="min">-1.7</param>
<param name="max">1.7</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
......@@ -64,12 +59,13 @@
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<state_interface name="acceleration"/>*
<param name="motor_number">1</param>
</joint>
<joint name="FLK">
<command_interface name="position">
<param name="min">-1.5</param>
<param name="max">1.5</param>
<param name="min">-3.4</param>
<param name="max">3.4</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
......@@ -82,11 +78,12 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<param name="motor_number">2</param>
</joint>
<joint name="FRHAA">
<command_interface name="position">
<param name="min">-0.5</param>
<param name="max">0.2</param>
<param name="max">0.5</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
......@@ -99,11 +96,12 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<param name="motor_number">3</param>
</joint>
<joint name="FRHFE">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
<param name="min">-1.7</param>
<param name="max">1.7</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
......@@ -116,11 +114,12 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<param name="motor_number">4</param>
</joint>
<joint name="FRK">
<command_interface name="position">
<param name="min">-1.5</param>
<param name="max">1.5</param>
<param name="min">-3.4</param>
<param name="max">3.4</param>
</command_interface>
<command_interface name="velocity">
<param name="min">-1</param>
......@@ -128,6 +127,7 @@
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="acceleration"/>
<param name="motor_number">5</param>
</joint>
</ros2_control>
......
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