ArduPlane + Gazebo (Ignition) – PreArm “Accels inconsistent” with custom fixed-wing model and LiftDrag

I am working on a fixed-wing aircraft model in Gazebo (gz-sim) integrated with ArduPilot SITL.
The model is inspired by and written based on the ArduPilot Talon fixed-wing example, adapting its overall structure, control surfaces, and plugin configuration.

I am currently experiencing issues where the aircraft does not generate sufficient forward acceleration and lift to take off. I suspect the problem is related to thrust modeling and lift/drag axis definitions, rather than control logic.

Can you help me identify where I went wrong and pinpoint the weak points in my setup?

<sdf version='1.11'>
  <model name='asuman_v5'>
    <link name='base_link'>
      <inertial>
        <mass>0.85580198896604698</mass>
        <inertia>
          <ixx>0.018808880958553501</ixx>
          <ixy>0.000246699369689883</ixy>
          <ixz>-3.4286127298079098e-05</ixz>
          <iyy>0.0337043411689434</iyy>
          <iyz>-2.25399149359833e-06</iyz>
          <izz>0.016202861027244699</izz>
        </inertia>
      </inertial>
      <collision name='base_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/base_link.STL</uri>
          </mesh>
        </geometry>
      </collision>
      
      
      <visual name='base_link_visual'>
        <pose>0 0 0 1.57 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/textures/asuman.glb</uri>
          </mesh>
        </geometry>
      </visual>
      
      <sensor name="imu_sensor" type="imu">
        <pose degrees="true">0 0 0 0 0 0</pose>
        <always_on>1</always_on>
        <update_rate>1000.0</update_rate>
      </sensor>
      <sensor name="navsat_sensor" type="navsat">
        <always_on>1</always_on>
        <update_rate>1</update_rate>
      </sensor>
      
      
    </link>
    
    <joint name='elevator_joint' type='revolute'>
      <pose relative_to='base_link'>-0.96499999999999997 -0.19 -0.075662999999999994 1.5708 0 0</pose>
      <parent>base_link</parent>
      <child>elevator_link</child>
      <axis>
        <xyz>0 0 1</xyz>
        <limit>
          <lower>-0.523599</lower>
          <upper>0.523599</upper>
        </limit>
        <dynamics>
          <damping>0.01</damping>
        </dynamics>
      </axis>
    </joint>
    <link name='elevator_link'>
      <pose relative_to='elevator_joint'>0 0 0 0 0 0</pose>
      <inertial>
        <pose>-0.015115594439109901 9.6447061488882894e-05 -0.19022832430567199 0 0 0</pose>
        <mass>0.057479741967468301</mass>
        <inertia>
          <ixx>0.00068187380185478596</ixx>
          <ixy>1.3189780365394301e-08</ixy>
          <ixz>-1.80556406084995e-08</ixz>
          <iyy>0.00068591592053453005</iyy>
          <iyz>8.4662385848795703e-08</iyz>
          <izz>4.3947138398731999e-06</izz>
        </inertia>
      </inertial>
      <collision name='elevator_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/elevator_link.STL</uri>
          </mesh>
        </geometry>
      </collision>
      <visual name='elevator_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/elevator_link.STL</uri>
          </mesh>
        </geometry>
        <material>
          <diffuse>0.990196109 1 1 1</diffuse>
          <ambient>0.990196109 1 1 1</ambient>
        </material>
      </visual>
    </link>
    <joint name='left_aileron_joint' type='revolute'>
      <pose relative_to='base_link'>-0.12109 0.32743 -0.0092040000000000004 1.5651999999999999 0.094591999999999996 3.0767000000000002</pose>
      <parent>base_link</parent>
      <child>left_aileron_link</child>
      <axis>
        <xyz>7.1118999999999995e-05 -0.0013094000000000001 -1</xyz>
        <limit>
          <lower>-0.523599</lower>
          <upper>0.523599</upper>
        </limit>
        <dynamics>
          <damping>0.01</damping>
        </dynamics>
      </axis>
    </joint>
    <link name='left_aileron_link'>
      <pose relative_to='left_aileron_joint'>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0.0140974048167672 -0.0013547828590017401 0.131487275157919 0 0 0</pose>
        <mass>0.051127814127108803</mass>
        <inertia>
          <ixx>0.00028429632953432199</ixx>
          <ixy>5.9183592389288598e-07</ixy>
          <ixz>3.3929204084462002e-07</ixz>
          <iyy>0.00028859845594671597</iyy>
          <iyz>-4.94536947306201e-07</iyz>
          <izz>4.89981386187481e-06</izz>
        </inertia>
      </inertial>
      <collision name='left_aileron_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/left_aileron_link.STL</uri>
          </mesh>
        </geometry>
      </collision>
      <visual name='left_aileron_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/left_aileron_link.STL</uri>
          </mesh>
        </geometry>
        <material>
          <diffuse>0.990196109 1 1 1</diffuse>
          <ambient>0.990196109 1 1 1</ambient>
        </material>
      </visual>
    </link>
    <joint name='propeller_joint' type='revolute'>
      <pose relative_to='base_link'>0.33079710274728602 0 -0.074999992249100006 -1.5999677469079703 0 -3.14159265358979</pose>
      <parent>base_link</parent>
      <child>propeller_link</child>
      <axis>
        <xyz>1 0 0</xyz>
        <limit>
          <lower>-inf</lower>
          <upper>inf</upper>
        </limit>
        <dynamics>
          <spring_reference>0</spring_reference>
          <spring_stiffness>0</spring_stiffness>
        </dynamics>
      </axis>
    </joint>
    <link name='propeller_link'>
      <pose relative_to='propeller_joint'>0 0 0 0 0 0</pose>
      <inertial>
        <pose>-0.0053630881541813502 1.4099030254399699e-07 3.78928112507518e-07 0 0 0</pose>
        <mass>0.0010143569356122701</mass>
        <inertia>
          <ixx>4.5218235483174499e-07</ixx>
          <ixy>2.0485187050766101e-13</ixy>
          <ixz>-2.4531939173851098e-13</ixz>
          <iyy>4.4864425722368299e-07</iyy>
          <iyz>1.41223672722648e-08</iyz>
          <izz>5.95286300084247e-09</izz>
        </inertia>
      </inertial>
      <!--
      <collision name='propeller_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/propeller_link.STL</uri>
          </mesh>
        </geometry>
      </collision>
      -->
      <visual name='propeller_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/propeller_link.STL</uri>
          </mesh>
        </geometry>
        <material>
          <diffuse>0.127450988 0.127450988 0.127450988 1</diffuse>
          <ambient>0.127450988 0.127450988 0.127450988 1</ambient>
        </material>
      </visual>
    </link>
    <joint name='right_aileron_joint' type='revolute'>
      <pose relative_to='base_link'>-0.11967 -0.33074999999999999 -0.0090760000000000007 1.5708 -4.2351647362715017e-22 -3.1415853071795872</pose>
      <parent>base_link</parent>
      <child>right_aileron_link</child>
      <axis>
        <xyz>0.068007999999999999 -0.0072281999999999997 0.99765999999999999</xyz>
        <limit>
          <lower>-0.523599</lower>
          <upper>0.523599</upper>
        </limit>
        <dynamics>
          <damping>0.01</damping>
        </dynamics>
      </axis>
    </joint>
    <link name='right_aileron_link'>
      <pose relative_to='right_aileron_joint'>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0.0040974048167672 -0.0013547828590017401 -0.131487275157919 0 0.08 0</pose>
        <mass>0.051127814127108803</mass>
        <inertia>
          <ixx>0.00028429632953432199</ixx>
          <ixy>5.9183592389288598e-07</ixy>
          <ixz>3.3929204084462002e-07</ixz>
          <iyy>0.00028859845594671597</iyy>
          <iyz>-4.94536947306201e-07</iyz>
          <izz>4.89981386187481e-06</izz>
        </inertia>
      </inertial>
      <collision name='right_aileron_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/right_aileron_link.STL</uri>
          </mesh>
        </geometry>
      </collision>
      <visual name='right_aileron_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/right_aileron_link.STL</uri>
          </mesh>
        </geometry>
        <material>
          <diffuse>0.990196109 1 1 1</diffuse>
          <ambient>0.990196109 1 1 1</ambient>
        </material>
      </visual>
    </link>
    <joint name='rudder_joint' type='revolute'>
      <pose relative_to='base_link'>-0.96499999999999997 0 0 1.5708 -4.2351647362715017e-22 -3.1415853071795872</pose>
      <parent>base_link</parent>
      <child>rudder_link</child>
      <axis>
        <xyz>0 -1 0</xyz>
        <limit>
          <lower>-0.523599</lower>
          <upper>0.523599</upper>
        </limit>
        <dynamics>
          <damping>0.01</damping>
        </dynamics>
      </axis>
    </joint>
    <link name='rudder_link'>
      <pose relative_to='rudder_joint'>0 0 0 0 0 0</pose>
      <inertial>
        <pose>0.014534539892347299 0.0127734305027923 -0.00016522210447695299 0 0 0</pose>
        <mass>0.0220843580567032</mass>
        <inertia>
          <ixx>4.0468391512494997e-05</ixx>
          <ixy>-8.6232350321230395e-07</ixy>
          <ixz>-5.2884964335724902e-09</ixz>
          <iyy>1.6896631121444e-06</iyy>
          <iyz>-2.1874374361294601e-07</iyz>
          <izz>4.1987304369692302e-05</izz>
        </inertia>
      </inertial>
      <collision name='rudder_link_collision'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/rudder_link.STL</uri>
          </mesh>
        </geometry>
      </collision>
      <visual name='rudder_link_visual'>
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <scale>1 1 1</scale>
            <uri>model://asuman_v5/meshes/rudder_link.STL</uri>
          </mesh>
        </geometry>
        <material>
          <diffuse>0.990196109 1 1 1</diffuse>
          <ambient>0.990196109 1 1 1</ambient>
        </material>
      </visual>
    </link>
    
    <plugin filename="gz-sim-joint-state-publisher-system"
      name="gz::sim::systems::JointStatePublisher">
    </plugin>
    
                
    <plugin
      filename="gz-sim-joint-position-controller-system"
      name="gz::sim::systems::JointPositionController">
      <joint_name>left_aileron_joint</joint_name>
      <initial_position>0.0</initial_position>
      <topic>/left_aileron_joint/cmd_pos</topic>
      <p_gain>10</p_gain>
      <i_gain>0.0</i_gain>
      <d_gain>0.0</d_gain>
      <i_max>1</i_max>
      <i_min>-1</i_min>
      <cmd_max>5</cmd_max>
      <cmd_min>-5</cmd_min>
    </plugin>

    <plugin
      filename="gz-sim-joint-position-controller-system"
      name="gz::sim::systems::JointPositionController">
      <joint_name>right_aileron_joint</joint_name>
      <initial_position>0.0</initial_position>
      <topic>/right_aileron_joint/cmd_pos</topic>
      <p_gain>10</p_gain>
      <i_gain>0.0</i_gain>
      <d_gain>0.0</d_gain>
      <i_max>1</i_max>
      <i_min>-1</i_min>
      <cmd_max>5</cmd_max>
      <cmd_min>-5</cmd_min>
    </plugin>
    

    <plugin
      filename="gz-sim-joint-position-controller-system"
      name="gz::sim::systems::JointPositionController">
      <joint_name>elevator_joint</joint_name>
      <initial_position>0.0</initial_position>
      <topic>/elevator_joint/cmd_pos</topic>
      <p_gain>10</p_gain>
      <i_gain>0.0</i_gain>
      <d_gain>0.0</d_gain>
      <i_max>1</i_max>
      <i_min>-1</i_min>
      <cmd_max>5</cmd_max>
      <cmd_min>-5</cmd_min>
    </plugin>
    
    
                
    <plugin
      filename="gz-sim-joint-position-controller-system"
      name="gz::sim::systems::JointPositionController">
      <joint_name>rudder_joint</joint_name>
      <initial_position>0.0</initial_position>
      <topic>/rudder_joint/cmd_pos</topic>
      <p_gain>10</p_gain>
      <i_gain>0.0</i_gain>
      <d_gain>0.0</d_gain>
      <i_max>1</i_max>
      <i_min>-1</i_min>
      <cmd_max>5</cmd_max>
      <cmd_min>-5</cmd_min>
    </plugin>
    
                
   <!-- motor_joint cw -->
   
    <plugin filename="gz-sim-lift-drag-system"
        name="gz::sim::systems::LiftDrag">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.25</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.05</area>
      <air_density>1.2041</air_density>
      <cp>0.084 0 0</cp>
      <forward>0 1 0</forward>
      <upward>-1 0 0</upward>
      <link_name>propeller_link</link_name>
    </plugin>
    <plugin filename="gz-sim-lift-drag-system"
        name="gz::sim::systems::LiftDrag">
      <a0>0.3</a0>
      <alpha_stall>1.4</alpha_stall>
      <cla>4.25</cla>
      <cda>0.10</cda>
      <cma>0.00</cma>
      <cla_stall>-0.025</cla_stall>
      <cda_stall>0.0</cda_stall>
      <cma_stall>0.0</cma_stall>
      <area>0.05</area>
      <air_density>1.2041</air_density>
      <cp>-0.084 0 0</cp>
      <forward>0 -1 0</forward>
      <upward>-1 0 0</upward>
      <link_name>propeller_link</link_name>
    </plugin>
    

    
    
                
    <!-- left wing -->
    <plugin filename="gz-sim-lift-drag-system"
        name="gz::sim::systems::LiftDrag">
      <a0>0.13</a0>
      <cla>3.7</cla>
      <cda>0.06417112299</cda>
      <cma>0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>0 0.27 0.029</cp>
      <area>0.16</area>
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 1 0</upward>
      <link_name>base_link</link_name>
      <control_joint_name>left_aileron_joint</control_joint_name>
      <control_joint_rad_to_cl>-0.75</control_joint_rad_to_cl>
    </plugin>

    <!-- right wing -->
    <plugin filename="gz-sim-lift-drag-system"
        name="gz::sim::systems::LiftDrag">
      <a0>0.13</a0>
      <cla>3.7</cla>
      <cda>0.06417112299</cda>
      <cma>0</cma>
      <alpha_stall>0.3391428111</alpha_stall>
      <cla_stall>-3.85</cla_stall>
      <cda_stall>-0.9233984055</cda_stall>
      <cma_stall>0</cma_stall>
      <cp>0 -0.27 0.029</cp>
      <area>0.16</area>
      <air_density>1.2041</air_density>
      <forward>1 0 0</forward>
      <upward>0 1 0</upward>
      <link_name>base_link</link_name>
      <control_joint_name>right_aileron_joint</control_joint_name>
      <control_joint_rad_to_cl>-0.75</control_joint_rad_to_cl>
    </plugin>
    
    
    
    <plugin name="ArduPilotPlugin"
      filename="ArduPilotPlugin">
      <!-- Port settings. -->
      <fdm_addr>127.0.0.1</fdm_addr>
      <fdm_port_in>9002</fdm_port_in>
      <connectionTimeoutMaxCount>5</connectionTimeoutMaxCount>
      <lock_step>1</lock_step>
      <have_32_channels>0</have_32_channels>

      <!-- Frame transforms.-->
      <modelXYZToAirplaneXForwardZDown>0 0 0 0 0 0</modelXYZToAirplaneXForwardZDown>
      <gazeboXYZToNED>0 0 0 3.141593 0 1.57079632</gazeboXYZToNED>

      <!-- Sensors. -->
      <imuName>base_link::imu_sensor</imuName>
      
      <control channel="0">
        <jointName>right_aileron_joint</jointName>
        <multiplier>-1.0471976</multiplier>         
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>COMMAND</type>
        <cmd_topic>/right_aileron_joint/cmd_pos</cmd_topic>
      </control>
      
      <control channel="1">
        <jointName>elevator_joint</jointName>
        <multiplier>1.0471976</multiplier>         
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>COMMAND</type>
        <cmd_topic>/elevator_joint/cmd_pos</cmd_topic>
      </control>
      
      <control channel="2"> 
        <jointName>propeller_joint</jointName>
        <multiplier>500</multiplier>
        <offset>0</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>

        <type>VELOCITY</type>
        <p_gain>0.20</p_gain>
        <i_gain>0</i_gain>
        <d_gain>0</d_gain>
        <i_max>1</i_max>
        <i_min>-1</i_min>
        <cmd_max>100.0</cmd_max>
        <cmd_min>0</cmd_min>
      </control>

      <control channel="3">
        <jointName>left_aileron_joint</jointName>
        <multiplier>1.0471976</multiplier>         
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>COMMAND</type>
        <cmd_topic>/left_aileron_joint/cmd_pos</cmd_topic>
      </control>

      <control channel="4">
        <jointName>rudder_joint</jointName>
        <multiplier>1.0471976</multiplier>         
        <offset>-0.5</offset>
        <servo_min>1000</servo_min>
        <servo_max>2000</servo_max>
        <type>COMMAND</type>
        <cmd_topic>/rudder_joint/cmd_pos</cmd_topic>
      </control>
    </plugin> 
    
    
   
  </model>
</sdf>