Hello guys,
We had today full day parachute test day by using Pixhawk 1 based quad. We made four manual ejects with method: Loiter - Stabilize - Throttle down - 1s wait - manual eject. Everything was very good.
Then the afternoon test session we focused on automatic eject and it ended to crash, total crash. We flew with Loiter at altitude approx 100m and disabled one motor with external kill switch which Pixhawk was not aware of. The first two drops were quite good and the third didn’t auto-eject at all. Our pilot was instructed to eject manually in case it seems to have a too long delay but he was too late. Parachute ejected and deployed in full just same time copter impacted to the mother Earth soil. Pretty much nothing is left except GoPro. But it doesn’t matter, that is just metal and carbon. Nobody was hurt and was not even close. We have a remote place to make these tests just because of this.
The problem is that I tried to take logs out today after the first test session and Mission Planner resulted in an error. So now after this crash I don’t even try. But I’m willing to send board to someone who can dig logs out of it. Skycat.pro pays the shipping.
We have EagleTree datalogger aboard and those logs are available. From logs I learned following (10 min check with quite high adrenaline still):
a copter can accelerate towards the ground faster than it would with free fall. Based on ET logs 44m in 2 seconds from a hover.
A copter falls too long distance before eject
When a copter is clearly in trouble, eject decision should be made quicker
A guess why the last drop failed is that the “problem counter/timer” can be zeroed if the copter suddenly seems to be in control for a fraction of a second. Is that possible in theory? Eagle Tree logs shows some kind of deceleration before the 2-second limit.
An argument against guess above is that the first eject was done way before 2-second limit and it indicates 2-second counter is not there anymore.
We have plenty of videos of the crash and those are uploaded to Youtube once are edited. If devs ask privately, I could send original footage via Dropbox. Videos are ground video camera, onboard GoPro and Mavic at the top of the copter. This reveals everything from the start to the end. Another onboard camera is dead.
If you can’t download the logs with Mission Planner, try taking the SD card out of the Pixhawk and getting the logs directly with an SD card reader. They will be in the /APM/Logs/ folder.
The card seems to be empty or corrupted. This screenshot shows all the visible data card contains. However, it has 61,6MB of something. Visible and hidden folders are 16,1KB of the total amount of data.
Could devs share the information in which conditions FW4.02 must be met to trigger parachute eject, and are there any possibility that if conditions are almost met that autopilot cancels the eject process eventhough copter is falling?
I want to underline that it did eject twice and the third time it didn’t eject. Or if it did eject automatically it did so simultaneously with our pilot manual eject, which was approx 0.5s too late.
This last drop was different than earlier ones. It had one partially-in-control moment where descent velocity slowed down a little. This is now guesswork because logs are not available, at least not easily.
Thanks! Those were quite clearly commented. I’m not programmer but believe I got something out of it, but for sure not whole image.
I saw there is 1 second counter for over 30 degrees error. What if copter rolls and rolling time is below 1s, does it reset timer when copter is at correct orientation (within tolerance of 30 degrees)?
EagleTree on this setup measures air pressure and G-forces only.
From barometer data I noticed copter “climbed” while fall. It must be “wing effect”. At some point frame of the copter acts as wing in air and creates lower pressure than surrounding air making it look alike climbing.
I linked the wrong part of the code, I fixed it in my post. The correct code is very similar, though.
From this part:
// check for angle error over 30 degrees
const float angle_error = attitude_control->get_att_error_angle_deg();
if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {
if (control_loss_count > 0) {
control_loss_count--;
}
return;
}
It looks like it doesn’t reset the timer, but it does subtract from it, so yes it’s possible for the parachute to not deploy if the copter spends some of the time with a level attitude, which is the known issue I linked above.
This could be a cuplrit as well. From this code:
// record baro alt if we have just started losing control
if (control_loss_count == 1) {
baro_alt_start = baro_alt;
// exit if baro altitude change indicates we are not falling
} else if (baro_alt >= baro_alt_start) {
control_loss_count = 0;
return;
If the control loss counter goes back down to 1 because the level attitude checker subtracted from the counter, then the falling checker will reset the starting baro altitude, so it might not realize it’s falling until later.
Does it measure G’s in multiple axes, or just total magnitude?
Great you are on it! Copter fall can be tricky and full of surprises. We have done drops for years and learn new everytime.
I get EagleTree logs for this thread. G-forces are measured in all three axes.
Videos are very explanatory what happened but I wait them to be edited (commented). It is a risk to release this kind of videos because of intended use against of drones. It was a normal test session and the risk was taken. This time delay just surprised our pilot.
How to use:
File --> Open recorder file
Data --> 2DChart
X-axis = time
Y-axis = Altitude and G-force x3
Box zooming zooms to the box. Reversed box zooming reverses the zoom. The third session was failed automatic eject and two first are successful automatic ejects. However, delay is very long.
On the third flight, the drone does seem to fall while staying level for much of the time (Y axis is positive down). Looks like it did do a flip which lasted 1.5 seconds, but I can’t say if it was longer than 1 second while the drone was outside of the acceptable control range, but it would be close.
Anyways, I’ll add this discussion thread to the Ardupilot issue for triggering parachute during a level descent.
EDIT: Looking at it again, I think the drone crashed just after the flip. The altitude data is clearly confused somehow, and the slow drift down to 0 is probably a correction happening while the drone is already sitting on the ground.
In that case, yeah, the drone pretty much just pancaked into the ground, which is a known case that the Ardupilot parachute trigger doesn’t handle yet.
I remember chute_delay_ms was set as low as possible, but I check it if the Pixhawk still connects to MP.
Eject delay for parachute launcher itself for 6S which this was is approx. 0.06s - 0.10s. Parachute in this video is IFC-96-SUL which is quite large (2.45m in diameter) and takes it’s time to deploy too. The copter weights 6kg and one motor was set to full stop (1ms PWM). On crash test parachute was even larger, IFC-120-SULR (Ø3m)