ArduPilot / SITL_Models

Models of aircraft for SITL
82 stars 116 forks source link

Gazebo: add X-UAV Mini Talon V-Tail #98

Open srmainwaring opened 1 year ago

srmainwaring commented 1 year ago

An X-UAV Mini Talon V-Tail plane

mini-talon-auto2

Usage

Gazebo and the plugins should be installed as per the ArduPilot Gazebo Plugin instructions.

Update the GZ_SIM_RESOURCE_PATH to include these models:

export GZ_SIM_RESOURCE_PATH=$GZ_SIM_RESOURCE_PATH:\
$HOME/SITL_Models/Gazebo/models:\
$HOME/SITL_Models/Gazebo/worlds

Run Gazebo

gz sim -v4 -r vtail_runway.sdf

Run ArduPilot SITL

sim_vehicle.py -v ArduPlane -f JSON --add-param-file=$HOME/SITL_Models/Gazebo/config/mini_talon_vtail.param --console --map

Tasks

imamim commented 11 months ago

Hello, thank you for your work. As you shared, I tested the mini-talon model in the Gazebo Garden simulation with my own Dronekit test code. I will explain both the process and the results below:

Setup

Test

As a result of my testing, I am sharing a few graphics and BIN files as follows:

There is a resultant path: result_map

Also we can look at TECS Controller and Attitude Controller and L1 controller for Loitering:

Height Attitude_Control Speed

Which this seems as Roll Controller and L1 controller give a good performance. But in the TECS controller and Pitch controller cause an oscillation. It cannot be said that the performance of the pitch controller is good either. Additionally, since the height adjustment is not made properly, there is probably an oscillation in the speed output.

You can access the log file from the link below. I think the problem is obvious, but I don't know how to proceed. I'm looking forward to your help :)

Log File

srmainwaring commented 10 months ago

Hi @imamim, thanks for the detailed analysis. The model was put together to help some students looking to simulate a plane for a competition: https://discuss.ardupilot.org/t/v-tail-gazebo-sitl-qgroundcontrol/103198 and so contained the basic model and integration but was not fully tuned.

IIRC the simulated prop thrust may be on the low side, so some of the physics params in the SDF file may need tweaking to address that before the ArduPilot tune is completed.

As there is no airspeed sensor the FCU is using the default TRIM_THROTTLE = 45 in automatic modes which is going to be too low to maintain altitude - this could explain the pitch oscillations you are seeing.

I'll take another look and see if I can get the issues you note resolved and the PR merged.

julled commented 4 months ago

@srmainwaring very cool you added this model! Do you still plan to improve the model parameters to make it more stable?