update: continuous joints

This commit is contained in:
Björn Ellensohn 2023-06-12 10:16:46 +02:00
parent e122488eb9
commit fffcf09b19

View File

@ -162,7 +162,7 @@
</link> </link>
<!-- right wheel joint --> <!-- right wheel joint -->
<joint name="${prefix}right_wheel_joint" type="revolute"> <joint name="${prefix}right_wheel_joint" type="continuous">
<origin xyz="-0.12499999999999993061 -0.58900000000000007905 -0.10500000000000000999" rpy="-1.570796326794896558 -2.2204460492503130808e-16 -1.57079632679489678" /> <origin xyz="-0.12499999999999993061 -0.58900000000000007905 -0.10500000000000000999" rpy="-1.570796326794896558 -2.2204460492503130808e-16 -1.57079632679489678" />
<parent link="${prefix}base_link" /> <parent link="${prefix}base_link" />
<child link="${prefix}right_wheel_link" /> <child link="${prefix}right_wheel_link" />
@ -196,7 +196,7 @@
</link> </link>
<!-- left wheel joint --> <!-- left wheel joint -->
<joint name="${prefix}left_wheel_joint" type="revolute"> <joint name="${prefix}left_wheel_joint" type="continuous">
<origin xyz="0.12500000000000013878 -0.58900000000000007905 -0.10500000000000003775" rpy="1.57079632679489678 -1.1102230246251567869e-16 -1.570796326794896558" /> <origin xyz="0.12500000000000013878 -0.58900000000000007905 -0.10500000000000003775" rpy="1.57079632679489678 -1.1102230246251567869e-16 -1.570796326794896558" />
<parent link="${prefix}base_link" /> <parent link="${prefix}base_link" />
<child link="${prefix}left_wheel_link" /> <child link="${prefix}left_wheel_link" />
@ -230,7 +230,7 @@
</link> </link>
<!-- caster wheel joint --> <!-- caster wheel joint -->
<joint name="${prefix}caster_wheel_joint" type="revolute"> <joint name="${prefix}caster_wheel_joint" type="continuous">
<origin xyz="5.3368019332749957491e-17 -0.29900000000000009903 -0.064999999999999974465" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" /> <origin xyz="5.3368019332749957491e-17 -0.29900000000000009903 -0.064999999999999974465" rpy="-5.5511151231257814695e-17 -0 3.141592653589793116" />
<parent link="${prefix}base_link" /> <parent link="${prefix}base_link" />
<child link="${prefix}caster_wheel_link" /> <child link="${prefix}caster_wheel_link" />
@ -348,7 +348,7 @@
</link> </link>
<!-- laser_joint --> <!-- laser_joint -->
<joint name="${prefix}laser_joint" type="revolute"> <joint name="${prefix}laser_joint" type="continuous">
<origin xyz="8.9609515272227915335e-17 -0.61400000000000021227 -0.019999999999999972661" rpy="-3.141592653589793116 -6.1629758220391519929e-33 1.1102230246251560474e-16" /> <origin xyz="8.9609515272227915335e-17 -0.61400000000000021227 -0.019999999999999972661" rpy="-3.141592653589793116 -6.1629758220391519929e-33 1.1102230246251560474e-16" />
<parent link="${prefix}base_link" /> <parent link="${prefix}base_link" />
<child link="${prefix}laser_link" /> <child link="${prefix}laser_link" />
@ -383,7 +383,7 @@
<!-- Camera Joint --> <!-- Camera Joint -->
<joint name="${prefix}camera_joint" type="revolute"> <joint name="${prefix}camera_joint" type="continuous">
<origin xyz="9.7569399001892381731e-17 -0.6290000000000002256 -0.045000000000000005274" rpy="6.1062266354383530837e-16 1.1102230246251567869e-16 3.141592653589793116" /> <origin xyz="9.7569399001892381731e-17 -0.6290000000000002256 -0.045000000000000005274" rpy="6.1062266354383530837e-16 1.1102230246251567869e-16 3.141592653589793116" />
<parent link="${prefix}base_link" /> <parent link="${prefix}base_link" />
<child link="${prefix}camera_link" /> <child link="${prefix}camera_link" />