updated wheel joint position in relation to lidar

This commit is contained in:
Björn Ellensohn 2023-08-17 10:27:48 +02:00
parent a574c53d65
commit 8a4c668a11

View File

@ -78,7 +78,7 @@
<joint name="chassis_joint" type="fixed"> <joint name="chassis_joint" type="fixed">
<parent link="base_link"/> <parent link="base_link"/>
<child link="chassis"/> <child link="chassis"/>
<origin xyz="${-chassis_length/2 + 0.070} 0 ${wheel_offset_z}"/> <origin xyz="${-chassis_length/2 + 0.075} 0 ${wheel_offset_z}"/>
</joint> </joint>
<link name="chassis"> <link name="chassis">
@ -109,7 +109,7 @@
<joint name="left_wheel_joint" type="continuous"> <joint name="left_wheel_joint" type="continuous">
<parent link="chassis"/> <parent link="chassis"/>
<child link="left_wheel"/> <child link="left_wheel"/>
<origin xyz="${chassis_length/2 - 0.070} ${wheel_offset_y/2 + wheel_thickness/2 + 0.01} 0" rpy="-${pi/2} 0 0" /> <origin xyz="${chassis_length/2 - 0.075} ${wheel_offset_y/2 + wheel_thickness/2 + 0.01} 0" rpy="-${pi/2} 0 0" />
<axis xyz="0 0 1"/> <axis xyz="0 0 1"/>
</joint> </joint>
@ -142,7 +142,7 @@
<joint name="right_wheel_joint" type="continuous"> <joint name="right_wheel_joint" type="continuous">
<parent link="chassis"/> <parent link="chassis"/>
<child link="right_wheel"/> <child link="right_wheel"/>
<origin xyz="${chassis_length/2 - 0.070} -${wheel_offset_y/2 + wheel_thickness/2 + 0.01} 0" rpy="${pi/2} 0 0" /> <origin xyz="${chassis_length/2 - 0.075} -${wheel_offset_y/2 + wheel_thickness/2 + 0.01} 0" rpy="${pi/2} 0 0" />
<axis xyz="0 0 -1"/> <axis xyz="0 0 -1"/>
</joint> </joint>
@ -229,7 +229,7 @@
<joint name="lidar_joint" type="fixed"> <joint name="lidar_joint" type="fixed">
<parent link="base_link"/> <parent link="base_link"/>
<child link="laser_frame"/> <child link="laser_frame"/>
<origin xyz="${0.070-0.155} 0 ${chassis_height + 0.030}" rpy="0 0 ${pi}"/> <origin xyz="${0.075 - 0.15285} 0 ${chassis_height + 0.030}" rpy="0 0 ${pi}"/>
</joint> </joint>