Moved lidar and camera to more real position

This commit is contained in:
wittenator 2023-12-02 19:26:02 +01:00
parent fa851fa483
commit fa467d8857
2 changed files with 4 additions and 3 deletions

View File

@ -4,7 +4,7 @@
<joint name="camera_joint" type="fixed">
<parent link="laser_frame"/>
<child link="camera_link"/>
<origin xyz="0 -0.2 0" rpy="0 0 0"/>
<origin xyz="0 0.05 -0.03" rpy="0 0 ${-20*deg_to_rad}"/>
</joint>
<link name="camera_link">
@ -33,7 +33,8 @@
<ignition_frame_id>camera_link_optical</ignition_frame_id>
<topic>semantic</topic>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<horizontal_fov>${84.7*deg_to_rad}</horizontal_fov>
<vertical_fov>${66.1*deg_to_rad}</vertical_fov>
<image>
<width>640</width>
<height>480</height>

View File

@ -6,7 +6,7 @@
<joint name="laser_joint" type="fixed">
<parent link="chassis"/>
<child link="laser_frame"/>
<origin xyz="-1.1 0.0 1.0" rpy="0 0 0"/>
<origin xyz="-1.1070259 0.0 1.0059250" rpy="0 0 0"/>
</joint>