Adding camera to Alti Transition QuadPlane
I have tried to add a gazebo camera to the above-mentioned quad plane by editing the model.sdf file of alti_transition_quad. But whenever I am trying to run the plane in Gazebo using gz sim -v4 -r alti_transition_runway.sdf, I can't see the camera over there. I have tried the same exact process in gazebo-iris and it worked perfectly. Below I am attaching the lines that I added into the model.sdf file. For the gazebo-iris model, I used to execute cmake and make commands in the ~/ardupilot_gazebo/build as shown in the ardupilot_gazebo repo.
<link name='cam_link'> <inertial> <!-- <pose>0 0 0 0 0 0</pose> --> <!-- <pose>0.05 0 -0.15 -0 1 -3.12703</pose> --> <mass>0.15</mass> <inertia> <ixx>0.00001</ixx> <ixy>0</ixy> <ixz>0</ixz> <iyy>0.00002</iyy> <iyz>0</iyz> <izz>0.00002</izz> </inertia> </inertial> <sensor name="cam_sensor" type="camera"> <camera name="user_camera"> <save enabled="true"> <path>/home/sa-toki/RASIC_Data/Ardupilot_Gazebo_Data_Quad</path> </save> <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> <pose>0 0 -0.15 -0 1.5708 0</pose> <always_on>1</always_on> <update_rate>50</update_rate> <visualize>1</visualize> <plugin name="camera_controller" filename="libgazebo_ros_camera.so"> <cameraName>alti_transition_quad/camera</cameraName> <imageTopicName>image_raw</imageTopicName> <cameraInfoTopicName>camera_info</cameraInfoTopicName> <frameName>cam_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> </link> <joint name='camera_joint' type='revolute'> <child>cam_link</child> <parent>base_link</parent> <axis> <xyz>0 0 1</xyz> <limit> <lower>0</lower> <upper>0</upper> <effort>0</effort> <velocity>0</velocity> </limit> <dynamics> <damping>1.0</damping> </dynamics> </axis> </joint>
@tokilligent the easiest way to add a camera is to use the gimbal_small_3d model from ardupilot_gazebo. This is used in the iris_with_gimbal example, and the README and model explain how to configure the camera for streaming and control as a servo gimbal in ArduPilot.
Add this before the closing </model> tag in alti_transition_quad/model.sdf:
<include>
<uri>model://gimbal_small_3d</uri>
<name>gimbal</name>
<pose degrees="true">0.5 -0.01 -0.205 90 0 90</pose>
</include>
<joint name="gimbal_joint" type="revolute">
<parent>base_link</parent>
<child>gimbal::base_link</child>
<axis>
<limit>
<lower>0</lower>
<upper>0</upper>
</limit>
<xyz>0 0 1</xyz>
</axis>
</joint>
To enable the camera sensor add this to the world alti_transition_runway.sdf below the <world name="runway"> tag
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
The plane equipped with the camera (the image is not centred as the gimbal controller has not been enabled).