From bc498256d9d42392c4934be74843dd2040b3dd59 Mon Sep 17 00:00:00 2001 From: Alireza Ghaderi Date: Wed, 2 Oct 2024 12:28:43 +0000 Subject: [PATCH] added qtailsitter --- config/config.ini | 37 ++++++++++++++++++++++++++++++++++++- setup/setup_px4_sitl.sh | 2 +- 2 files changed, 37 insertions(+), 2 deletions(-) diff --git a/config/config.ini b/config/config.ini index e95ea27..c18f35f 100644 --- a/config/config.ini +++ b/config/config.ini @@ -16,7 +16,7 @@ ; Configuration Name (Displayed in UI) ; Change this name to switch between different aircraft configurations (e.g., ehang184 or Cessna172). -config_name = TB2 +config_name = Alia250 ;------------------------------------------------------------------------------------------ @@ -212,3 +212,38 @@ channel6 = sim/flightmodel/controls/wing1r_flap1def, float, 0, [0 40] # Type: float # Range: [0 40] (degrees of deflection) channel7 = sim/flightmodel/controls/wing1l_flap1def, float, 0, [0 40] + +;------------------------------------------------------------------------------------------ +[QuadTailsitter] + +; Configuration for the control surface-less Quad Tailsitter. +; This mapping defines the four motor outputs from PX4 to the corresponding X-Plane datarefs. +; The aircraft uses four high KV motors for control via differential thrust. + +; Motor 1 (PX4 Channel 0 mapped to X-Plane Engine 1) +; Dataref: sim/flightmodel/engine/ENGN_thro_use[0] +; Type: floatArray +; Range: [0 1] (idle to full throttle) +; Description: Controls the throttle of Motor 1. +channel0 = sim/flightmodel/engine/ENGN_thro_use, floatArray, [0], [0 1] + +; Motor 2 (PX4 Channel 1 mapped to X-Plane Engine 2) +; Dataref: sim/flightmodel/engine/ENGN_thro_use[1] +; Type: floatArray +; Range: [0 1] (idle to full throttle) +; Description: Controls the throttle of Motor 2. +channel1 = sim/flightmodel/engine/ENGN_thro_use, floatArray, [1], [0 1] + +; Motor 3 (PX4 Channel 2 mapped to X-Plane Engine 3) +; Dataref: sim/flightmodel/engine/ENGN_thro_use[2] +; Type: floatArray +; Range: [0 1] (idle to full throttle) +; Description: Controls the throttle of Motor 3. +channel2 = sim/flightmodel/engine/ENGN_thro_use, floatArray, [2], [0 1] + +; Motor 4 (PX4 Channel 3 mapped to X-Plane Engine 4) +; Dataref: sim/flightmodel/engine/ENGN_thro_use[3] +; Type: floatArray +; Range: [0 1] (idle to full throttle) +; Description: Controls the throttle of Motor 4. +channel3 = sim/flightmodel/engine/ENGN_thro_use, floatArray, [3], [0 1] \ No newline at end of file diff --git a/setup/setup_px4_sitl.sh b/setup/setup_px4_sitl.sh index 70ee5e9..228c80f 100644 --- a/setup/setup_px4_sitl.sh +++ b/setup/setup_px4_sitl.sh @@ -83,7 +83,7 @@ DEFAULT_CONFIG_FILE="$HOME/.px4sitl_config" DEFAULT_FALLBACK_IP="127.0.0.1" SCRIPT_NAME="px4xplane_script.sh" MAVLINK2REST_IP="127.0.0.1" -PLATFORM_CHOICES=("xplane_ehang184" "xplane_alia250" "xplane_cessna172" "xplane_tb2") +PLATFORM_CHOICES=("xplane_ehang184" "xplane_alia250" "xplane_cessna172" "xplane_tb2" "xplane_qtailsitter) # === MAVLink Router Configuration === USE_MAVLINK_ROUTER=true # Set to true to enable MAVLink Router installation and setup