Fixed Wing UAV - osrf/mbzirc GitHub Wiki

By default, the MBZIRC simulator comes with support for fixed wing UAVs. There is one fixed wing model available and it may be controlled using an attitude controller.

Spawning a fixed-wing UAV

First, lets start the coast world.

ros2 launch mbzirc_ros competition_local.launch.py ign_args:="-v 4 -r coast.sdf"

Next we will be spawning the fixed wing on the runway.

ros2 launch mbzirc_ign spawn.launch.py name:=zephyr world:=coast model:=mbzirc_fixed_wing type:=uav x:=-1500 y:=0 z:=5

This should spawn a fixed-wing UAV on the runway.

Controlling the UAV

Take-Off

The built-in controller has a service for you to get the plane to take off. To call it call the following ROS service:

ros2 service call /zephyr/cmd/tol mavros_msgs/CommandTOL "{min_pitch: 0.2, altitude: 40.0}"

The controller uses the mavros_msgs/CommandTOL interface, however note that only min_pitch and altitude are controlled. The latitude, longitude and yaw fields are ignored. This is due to the GPS-denied nature of the competition and the fact that yaw and roll are coupled in the current model.

Steady state flight

The built in controller listens on {vehicle_name}/cmd/attitude for mavros_msgs/AttitudeTarget messages to perform attitude control. Note that only Pitch and Roll are controlled. Yaw is a secondary side effect of roll in the current fixed wing model and thus not controlled (roll the aircraft to achieve a desired yaw rate). An example of such control would be as follows:

ros2 topic pub /zephyr/cmd/attitude mavros_msgs/AttitudeTarget "{orientation: {w: 0.7071, x: -0.7071}, thrust: 1000}"

fixed wing takeoff