Open andyp1per opened 8 months ago
@rmackay9 FYI
This is the line:
@andyp1per Can you upload the log? What mode were you in? Were you taking off or landing?
Hi, yes, knowing the flight mode and exact code being used would be good. Like the comment says it should only be caused by a bug in one of the flight modes. It's Leonard's code but I specifically asked for that internal error to be added to avoid code bugs leading to the dangerous possibility of the takeoff detector failing.
In acro, doing a flip
I did a bit more poking about, it seems to me its miss match between thresholds.
To detect landing we have all these thresholds: https://github.com/ArduPilot/ardupilot/blob/3ff790159f99f0a87902a6ec052612da15b4eee6/ArduCopter/land_detector.cpp#L119
Then for the check that caused this panic we check these thresholds: https://github.com/ArduPilot/ardupilot/blob/3ff790159f99f0a87902a6ec052612da15b4eee6/ArduCopter/land_detector.cpp#L56
The key difference is we will detect landing if the motor is at the lower limit, there we check that the throttle is above the get_non_takeoff_throttle
so the code presumes that you cannot be at the lower limit with a throttle above get_non_takeoff_throttle
if that ever happens and you also happen to be very still then your guaranteed to hit this panic.
We don't hit this often because the vehicle is not often still.
get_non_takeoff_throttle
is defined as:
https://github.com/ArduPilot/ardupilot/blob/3ff790159f99f0a87902a6ec052612da15b4eee6/ArduCopter/Attitude.cpp#L104
In this case hover throttle is 0.13. So it only need a throttle of above 0.065 while at the lower throttle limit to trigger this. The lower hover throttle on this model make that more likely.
This has air mode enabled in acro meaning at zero input throttle it will boost up output throttle for control authority, making the condition more likely again.
Unfortunately we don't log the throttle limit flags in acro, but we do see the land complete maybe flag tripping a couple of times, so I guess it was building and got reset by a bit of movement.
So, I think this is more or less expected with such a vehicle. Although we don't get reports of the internal error IRL. So it could just be that people don't tend to leave the vehicle sat armed on the ground at zero throttle for long enough, but of course this is something that is very easy to do in realfight. It could also be that the "vehicle still moving" thresholds stop the landing detection in that case on real vehicles.
I tend to think we should wait until we get a report form a real vehicle before we make any changes. Although now we know the cause I suspect we could reproduce relatively easily on a vehicle with a similar setup to this one.
@IamPete1 nice analysis, thanks!
Got this while running running in real-flight. I think an internal panic is unfriendly and we should probably remove this line
1 0x00000000081856c8 in AP_InternalError::error (this=0x852ef38, e=AP_InternalError::error_t::flow_of_control, line=59) at ../../libraries/AP_InternalError/AP_InternalError.cpp:28
2 0x000000000807e401 in Copter::update_land_detector (this=0x851bf40) at ../../ArduCopter/land_detector.cpp:59
3 0x000000000807e2c5 in Copter::update_land_and_crash_detectors (this=0x851bf40) at ../../ArduCopter/land_detector.cpp:23
4 0x000000000806d8ff in Functor::method_wrapper<Copter, &Copter::update_land_and_crash_detectors> (obj=0x851bf40 ) at ../../libraries/AP_HAL/utility/functor.h:88
5 0x000000000811c1a0 in Functor::operator() (this=0x84ed460 <Copter::scheduler_tasks+288>) at ../../libraries/AP_HAL/utility/functor.h:54
6 0x000000000817ce99 in AP_Scheduler::run (this=0x851c0f0 <copter+432>, time_available=2500) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:261
7 0x000000000817d316 in AP_Scheduler::loop (this=0x851c0f0 <copter+432>) at ../../libraries/AP_Scheduler/AP_Scheduler.cpp:389
8 0x0000000008182ed7 in AP_Vehicle::loop (this=0x851bf40) at ../../libraries/AP_Vehicle/AP_Vehicle.cpp:508
9 0x00000000082aa298 in HAL_SITL::run (this=0x8536220, argc=12, argv=0x7ffffffeda18, callbacks=0x851bf40 ) at ../../libraries/AP_HAL_SITL/HAL_SITL_Class.cpp:284
10 0x000000000806d36e in main (argc=12, argv=0x7ffffffeda18) at ../../ArduCopter/Copter.cpp:856
(gdb)
Bug report
Issue details
Please describe the problem
Version What version was the issue encountered with
Platform [ ] All [ ] AntennaTracker [X ] Copter [ ] Plane [ ] Rover [ ] Submarine
Airframe type Rise255
Hardware type RealFlight
Logs Please provide a link to any relevant logs that show the issue