Open phamelin opened 4 years ago
Looking further into this problem, I now think that the problem isn't from AP_HAL::millis(), which I would have been very surprised. I think that the non-monotonic behavior comes from uart time timestamp compensation (see commit https://github.com/ArduPilot/ardupilot/commit/3fe4b9c0f8310c3ad6c48ca5f98749a6bd8cd070). Indeed, not all NMEA messages use this timestamp compensation so I think this may cause non-monotomic message timestamps. I will check on real hardware to confirm the problem. Stay tuned.
The problem has been confirmed on real hardware. To validate, I made sure that the delta_time is always positive, i.e.:
if(tnow > timing[instance].last_message_time_ms)
timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms;
else
timing[instance].delta_time_ms = 0;
If this approach is good enough I can submit a pull request.
Can you test master for this issue - may have been fixed by https://github.com/ArduPilot/ardupilot/pull/15600
On 23 Oct 2020, at 5:19 am, Philippe notifications@github.com wrote:
The problem has been confirmed on real hardware. To validate, I made sure that the delta_time is always positive, i.e.:
if(tnow > timing[instance].last_message_time_ms) timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms; else timing[instance].delta_time_ms = 0; If this approach is good enough I can submit a pull request.
— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub, or unsubscribe.
I don't think this could solve the problem. The negative delta time comes from uart timestamp compensation (https://github.com/ArduPilot/ardupilot/commit/3fe4b9c0f8310c3ad6c48ca5f98749a6bd8cd070), which seems to give inacurrate results when the GPS frequency is 10Hz or more. If the driver polling frequency is the same as the GPS rate, two messages could be read at the same time slice and hence have the same timestamp. If the later has a string longer than the first one, then this cause a negative delta time.
Can you test master for this issue - may have been fixed by #15600 … On 23 Oct 2020, at 5:19 am, Philippe @.***> wrote: The problem has been confirmed on real hardware. To validate, I made sure that the delta_time is always positive, i.e.: if(tnow > timing[instance].last_message_time_ms) timing[instance].delta_time_ms = tnow - timing[instance].last_message_time_ms; else timing[instance].delta_time_ms = 0; If this approach is good enough I can submit a pull request. — You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub, or unsubscribe.
Bug report
Issue details
During some flights I had 'Bad GPS signal health' messages in Mission Planner. I narrowed down the problem to this line in AP_GPS.cpp:
where
last_message_delta_time_ms
returns values near (2^16-1). Also, in the dataflash log the recordeddelta_time_ms
(GPA.Delta
) shows spurious spikes around (2^16-1). The delta is computed inAP_GPS.cpp
as follow:So, it looks like there's an overflow on the computation of
delta_time_ms
. Indeed, the dataflash log shows non-monotonic values oflast_message_time_ms
(GPA.SMS
), which cause the overflow. From my understanding, the only way this could happen is ifAP_HAL::millis()
is not monotonic.Version ArduCopter 4.0.3
Platform [X] Copter
Airframe type Octa quad
Hardware type Pixhawk Cube Black
Logs 2020-06-20 10-30-45.zip