Skip to content

Commit

Permalink
ArduPlane: Fix default airspeed units
Browse files Browse the repository at this point in the history
  • Loading branch information
Paul Riseborough committed Mar 5, 2020
1 parent 6fc86ba commit 9e2abfa
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduPlane/ArduPlane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,7 @@ void Plane::one_second_loop()
adsb.set_stall_speed_cm(aparm.airspeed_min);
adsb.set_max_speed(aparm.airspeed_max);

ahrs.writeDefaultAirSpeed(0.01f * (float)((aparm.airspeed_min + aparm.airspeed_max)/2));
ahrs.writeDefaultAirSpeed((float)((aparm.airspeed_min + aparm.airspeed_max)/2));

// sync MAVLink system ID
mavlink_system.sysid = g.sysid_this_mav;
Expand Down

0 comments on commit 9e2abfa

Please sign in to comment.