Added of code
This commit is contained in:
parent
457a437058
commit
353a20f815
203
README.md
203
README.md
|
@ -0,0 +1,203 @@
|
|||
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">
|
||||
|
||||
<parent> spiri::base </parent>
|
||||
<child> camera_link::link </child>
|
||||
</joint>
|
||||
|
||||
|
||||
<!-- link for camera -->
|
||||
<link name="camera_link">
|
||||
<inertial>
|
||||
<pose>0 0 0 0 0 0</pose>
|
||||
<mass>0.01</mass>
|
||||
<inertia>
|
||||
<ixx>2.1733e-06</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>2.1733e-06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1.8e-07</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
<pose>0 0 0.15 0 0 0</pose>
|
||||
<visual name="camera_visual">
|
||||
<pose>-0.005 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0 0 0 1.0</ambient>
|
||||
<diffuse>0 0 0 1.0</diffuse>
|
||||
<specular>0.0 0.0 0.0 1.0</specular>
|
||||
<emissive>0.0 0.0 0.0 1.0</emissive>
|
||||
</material>
|
||||
</visual>
|
||||
<sensor type="multicamera" name="stereo_camera">
|
||||
<update_rate>30.0</update_rate>
|
||||
<camera name="left">
|
||||
<horizontal_fov>1.3962634</horizontal_fov>
|
||||
<image>
|
||||
<width>800</width>
|
||||
<height>800</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>300</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.007</stddev>
|
||||
</noise>
|
||||
</camera>
|
||||
<camera name="right">
|
||||
<pose>0 -0.07 0 0 0 0</pose>
|
||||
<horizontal_fov>1.3962634</horizontal_fov>
|
||||
<image>
|
||||
<width>800</width>
|
||||
<height>800</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>300</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.007</stddev>
|
||||
</noise>
|
||||
</camera>
|
||||
<plugin name="stereo_camera_controller" filename="libgazebo_ros_multicamera.so">
|
||||
<alwaysOn>true</alwaysOn>
|
||||
<updateRate>0.0</updateRate>
|
||||
<cameraName>multisense_sl/camera</cameraName>
|
||||
<imageTopicName>image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
||||
<frameName>left_camera_optical_frame</frameName>
|
||||
<!--<rightFrameName>right_camera_optical_frame</rightFrameName>-->
|
||||
<hackBaseline>0.07</hackBaseline>
|
||||
<distortionK1>0.0</distortionK1>
|
||||
<distortionK2>0.0</distortionK2>
|
||||
<distortionK3>0.0</distortionK3>
|
||||
<distortionT1>0.0</distortionT1>
|
||||
<distortionT2>0.0</distortionT2>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</link>
|
||||
|
||||
|
||||
|
||||
|
||||
Section 2: Modifying the code
|
||||
This section will go through the code section by section and describe what each part represents
|
||||
|
||||
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>
|
||||
<inertia>
|
||||
<ixx>2.1733e-06</ixx>
|
||||
<ixy>0</ixy>
|
||||
<ixz>0</ixz>
|
||||
<iyy>2.1733e-06</iyy>
|
||||
<iyz>0</iyz>
|
||||
<izz>1.8e-07</izz>
|
||||
</inertia>
|
||||
</inertial>
|
||||
Pose: This defines the position where the cameras will be centered
|
||||
|
||||
<pose>0 0 0.15 0 0 0</pose>
|
||||
|
||||
Visual: this defines the look of the camera
|
||||
|
||||
<visual name="camera_visual">
|
||||
<pose>-0.005 0 0 0 0 0</pose>
|
||||
<geometry>
|
||||
<box>
|
||||
<size>0.01 0.01 0.01</size>
|
||||
</box>
|
||||
</geometry>
|
||||
<material>
|
||||
<ambient>0 0 0 1.0</ambient>
|
||||
<diffuse>0 0 0 1.0</diffuse>
|
||||
<specular>0.0 0.0 0.0 1.0</specular>
|
||||
<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>
|
||||
<image>
|
||||
<width>800</width>
|
||||
<height>800</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>300</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<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>
|
||||
<image>
|
||||
<width>800</width>
|
||||
<height>800</height>
|
||||
<format>R8G8B8</format>
|
||||
</image>
|
||||
<clip>
|
||||
<near>0.02</near>
|
||||
<far>300</far>
|
||||
</clip>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<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>
|
||||
<cameraName>multisense_sl/camera</cameraName>
|
||||
<imageTopicName>image_raw</imageTopicName>
|
||||
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
|
||||
<frameName>left_camera_optical_frame</frameName>
|
||||
</plugin>
|
||||
</sensor>
|
||||
</link>
|
Loading…
Reference in New Issue