NAV_TAKEOFF not triggered by two handed reverse overhead throw

I have a moderately large flying wing that I find difficult to launch via the one hand method without creating a yaw that leads to a roll and crash, so I prefer to launch it with the two handed overhead method as demonstrated at 5:00 in this video:

However, throwing it like this doesn’t satisfy the TAKEOFF_THR parameters for some reason, while the one handed method does. My parameters are:
TKOFF_THR_MINACC : 15 m/s/s
TKOFF_THR_DELAY : 2 ds
TKOFF_THR_MINSPD : 0 m/s
I’ve resorted to faking the one handed throw to get the motor to spin up, then throwing for real, which generally works. However I would like to avoid holding the plane while it thinks it’s taken off and is at max throttle, both for safety concerns and to avoid integral windup.

I also initially also had this issue with INAV, but was able to solve it in that case by setting the nav_fw_launch_max_angle parameter to greater than 90°. Is there a similar parameter in Ardupilot that can be adjusted to fix my issue?

Have you tried lowering TKOFF_THR_MINACC ?
Also check TKOFF_ACCEL_CNT

TKOFF_ACCEL_CNT is set to one.
I have lowered TKOFF_THR_MINACC to 13 m/s/s, but I don’t think that’s the problem.
As you can see in this log file demonstrating the problem, I make three failed attempts to start the launch with the backwards overhead throw. Each of those attempts triggers a message of “Armed AUTO, xaccel = ##.# m/s/s, waiting 0.2 sec” indicating the TKOFF_THR_MINACC was exceeded, however there is also a message of “Bad launch Auto”. It is only when I switch to the side arm throw for the fourth launch that the Auto takeoff is triggered and the motor spins up.

https://drive.google.com/file/d/15s7b9KL-CP3vUceXNm2QcXXHKfuz8qEm/view?usp=sharing

This is beyond my knowledge, but a few pointers

  1. the log cannot be downloaded without login in to Google and requesting access, can you make it publicly available?
  2. the code for that message checks for specific constraints Check in the logs for this values and it might indicate that the orientation of you FC is incorrect.
(ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 ||
            (!fly_inverted() && labs(ahrs.roll_sensor) > 3000))

I’m using min speed and min acceleration set to 0, and dedicated swotch as tkof mode.

  1. Arm
  2. Tkof switch up (or switch to AUTO, if you have autolaunch in your mission)
  3. Throw it overhead!

Thanks for letting me know that the log isn’t publicly available, it should work now. I think the code you highlighted is what’s causing my problems

    bool do_takeoff_attitude_check = !(g2.flight_options & FlightOptions::DISABLE_TOFF_ATTITUDE_CHK);

... 

    if (do_takeoff_attitude_check) {
        // Check aircraft attitude for bad launch
        if (ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 ||
            (!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) {
            gcs().send_text(MAV_SEVERITY_WARNING, "Bad launch AUTO");
            takeoff_state.accel_event_counter = 0;
            goto no_launch;
        }
    }

Working upwards through “do_takeoff_attitude_check” led me to FLIGHT_OPTIONS and I found that setting bit 2 to true to disable the attitude check solved my problems. It seems that the documentation needs to be updated, while the page on FLIGHT_OPTIONS does describe this functionality, neither the page on Automatic Takeoff nor the page for Takeoff Mode describes the attitude check behavior nor the ability to turn it off via flight options.

This solution isn’t perfect, as it also disables the minimum pitch limit so that were I to drop the plane nose down it would erroneously arm and attempt to take off. A parameter to adjust the pitch limits would be nice, however the roll limits would likely still need to be effectively disabled for the overhead throw style as roll and heading vary wildly when the plane is pitched up 90° due to gimbal lock.

2 Likes

Another option would be to change the behavior on a failed attitude check. In a proper reverse overhead throw though the main acceleration event comes while the plane is vertical the plane should still be released fairly level within a short period of time.
Right now if the attitude check is failed it immediately sets the acceleration counter to 0 and aborts the the launch. However the plane will be in the correct orientation within a few deciseconds. If instead a failed attitude check only aborts the launch after the TKOFF_THR_DELAY has been exceeded then the overhead launch could be performed while retaining some of the safety features of the current attitude check.

This altitude check info is very interesting. I had a similar problem with my Bixler 2/PixRacer - I’ve been throwing it higher and higher because the Bixler notoriously pitches down when the motor starts. Autostart would randomly seem to work sometimes and not work other times. Now I’m wondering if it didn’t work the times I managed to trigger the altitude check mentioned by @Didymo . I’ll check my logs but also try FLIGHT_OPTIONS = 4.