Adding camera to existing default IRIS quadcopter
Hi,
I'm trying to add a camera to the existing default iris quadcopter in gazebo. I'm following this guide/tutorial . To the iris.sdf
file I added:
<joint name="camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${camera_link} 0 ${height3 - axel_offset*2}" rpy="0 0 0"/>
<parent link="link3"/>
<child link="camera_link"/>
</joint>
<!-- Camera -->
<link name="camera_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_link} ${camera_link} ${camera_link}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_link} ${camera_link} ${camera_link}"/>
</geometry>
<material name="red"/>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
And to the iris.xarco
file I added
<xacro:property name="camera_link" value="0.05" /> <!-- Size of square 'camera' box -->
But for some reason when I try to run the simulation, I don't see the added red box (camera). I'm really new to gazebo, I only have been able to fly the drone autonomously controlled via a ROS-node, but thats all. Anyone who could help me?
Thanks!
Asked by MaxWell on 2017-10-31 06:17:31 UTC
Answers
For anyone facing this difficulty, i would recommend first to go through this : http://gazebosim.org/tutorials?tut=ros_gzplugins#Camera
And this is the change you need to do in your iris.sdf. (just add the following)
<link name='cam_link'>
<pose frame=''>-0.118317 0.002195 0.004205 -0 -0 -3.12703</pose>
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<pose frame=''>0 0 0 0 -0 0</pose>
</inertial>
<self_collide>0</self_collide>
<kinematic>0</kinematic>
<sensor name='camera1' type='camera'>
<camera name="head">
<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>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>1</visualize>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<updateRate>0.0</updateRate>
<cameraName>iris/camera</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>camera_link</frameName>
<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>
Asked by kzbr on 2018-07-31 16:26:12 UTC
Comments
Hi, is missing I tkink. I added xml part to iris.sdf but It gives an error like "libgazebo_ros_camera.so not found". How can I resolv problem?
Asked by saucompeng on 2019-02-28 03:49:33 UTC
Comments