mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_NavEKF2: DAL interface compatibility change
This commit is contained in:
parent
296fb567ca
commit
ac00776184
@ -1607,7 +1607,7 @@ void NavEKF2::requestYawReset(void)
|
|||||||
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
|
// Writes the default equivalent airspeed in m/s to be used in forward flight if a measured airspeed is required and not available.
|
||||||
void NavEKF2::writeDefaultAirSpeed(float airspeed)
|
void NavEKF2::writeDefaultAirSpeed(float airspeed)
|
||||||
{
|
{
|
||||||
AP::dal().log_writeDefaultAirSpeed2(airspeed);
|
AP::dal().log_writeDefaultAirSpeed2(airspeed,0.0f);
|
||||||
|
|
||||||
if (core) {
|
if (core) {
|
||||||
for (uint8_t i=0; i<num_cores; i++) {
|
for (uint8_t i=0; i<num_cores; i++) {
|
||||||
|
Loading…
Reference in New Issue
Block a user