Skip to content
Snippets Groups Projects
Commit ca2f97de authored by Luca Marchionni's avatar Luca Marchionni
Browse files

Invert torso joints order. Check base_link

parent afa97cfc
No related branches found
No related tags found
No related merge requests found
...@@ -77,13 +77,13 @@ ...@@ -77,13 +77,13 @@
</link> </link>
<joint name="${name}_1_joint" type="revolute"> <joint name="${name}_1_joint" type="revolute">
<parent link="${name}_2_link"/> <parent link="base_link"/>
<child link="${name}_1_link"/> <child link="${name}_1_link"/>
<origin xyz="0.0 0.0 0.0" <origin xyz="0.0 0.0 0.0722"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 1 0" /> <axis xyz="0 0 1" />
<limit lower="${-45.0 * deg_to_rad}" upper="${15.0 * deg_to_rad}" <limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}"
effort="${torso_max_effort}" velocity="${torso_max_vel}"/> effort="${torso_max_effort}" velocity="${torso_max_vel}" />
<dynamics damping="1.0" friction="1.0"/> <dynamics damping="1.0" friction="1.0"/>
<!-- <safety_controller k_position="20" <!-- <safety_controller k_position="20"
...@@ -122,12 +122,12 @@ ...@@ -122,12 +122,12 @@
<joint name="${name}_2_joint" type="revolute"> <joint name="${name}_2_joint" type="revolute">
<parent link="${name}_1_link"/> <parent link="${name}_1_link"/>
<child link="base_link"/> <child link="${name}_2_link"/>
<origin xyz="0.0 0.0 -0.0722" <origin xyz="0.0 0.0 0.0"
rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/> rpy="${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad} ${0.00000 * deg_to_rad}"/>
<axis xyz="0 0 1" /> <axis xyz="0 1 0" />
<limit lower="${-75.00000 * deg_to_rad}" upper="${75.00000 * deg_to_rad}" <limit lower="${-15.0 * deg_to_rad}" upper="${45.0 * deg_to_rad}"
effort="${torso_max_effort}" velocity="${torso_max_vel}" /> effort="${torso_max_effort}" velocity="${torso_max_vel}"/>
<dynamics friction="1.0" damping="1.0"/> <dynamics friction="1.0" damping="1.0"/>
<!-- <safety_controller k_position="20" <!-- <safety_controller k_position="20"
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment