Made Readme readable and updated horizontal fov and pixel counts

This commit is contained in:
scorpio1 2023-02-05 19:20:20 -08:00
parent a710520764
commit 8fcbbcd2c5
1 changed files with 25 additions and 16 deletions

View File

@ -2,6 +2,7 @@ Please read in raw as I figure out how to properly format this
Section 1: Installation
To add camera functionality to the spiri drone, copy the code below into the sdf file of the model you are using, before the last </model> line.
```
<!-- joint for camera -->
<joint name="camera_joint" type="fixed">
@ -94,7 +95,7 @@ To add camera functionality to the spiri drone, copy the code below into the sdf
</sensor> 
</link>
```
Section 2: Modifying the code
@ -102,17 +103,19 @@ This section will go through the code section by section and describe what each
Joint:
This joint connects the camera link to the main robot. The parent is the main robot (base) and the child is the camera link
```
<joint name="camera_joint" type="fixed">
<parent> spiri::base </parent>
<child> camera_link::link </child>
</joint>
```
Link: This defines the actual camera
```
<link name="camera_link">
```
Inertial: This defines the mass and intertial properties. The values are set to be small to not change the model much
```
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.01</mass>
@ -145,21 +148,22 @@ Visual: this defines the look of the camera
      <emissive>0.0 0.0 0.0 1.0</emissive>
    </material>
  </visual>
```
Sensor: This defines how and what the camera outputs. The type multicamera corresponds to a stereo camera
```
<sensor type="multicamera" name="stereo_camera">
```
Update rate: This parameter defines the frame rate of the cameras
```
<update_rate>30.0</update_rate>
```
Next we define the left camera specific parameters
```
<camera name="left">
<horizontal_fov>1.3962634</horizontal_fov>
<horizontal_fov>1.5708</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<width>1280</width>
<height>960</height>
<format>R8G8B8</format>
</image>
<clip>
@ -172,14 +176,16 @@ Next we define the left camera specific parameters
<stddev>0.007</stddev>
</noise>
</camera>
```
These values still need to be updated to match the camera we are actually using
The right camera is similarly defined, along with an offset from the left camera (the pose)
```
<camera name="right">
<pose>0 -0.07 0 0 0 0</pose>
<horizontal_fov>1.3962634</horizontal_fov>
<horizontal_fov>1.5708</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<width>1280</width>
<height>960</height>
<format>R8G8B8</format>
</image>
<clip>
@ -192,7 +198,9 @@ The right camera is similarly defined, along with an offset from the left camera
<stddev>0.007</stddev>
</noise>
</camera>
```
Finally we define some values for ros to use for the topics that we output to, and close everything
```
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
@ -203,3 +211,4 @@ Finally we define some values for ros to use for the topics that we output to, a
</plugin>
</sensor>
</link>
```