AP_Airspeed: correct example; need instantiated AHRS for windspeed_max
This commit is contained in:
parent
f15459f25e
commit
f407e0dd55
@ -18,6 +18,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_Airspeed/AP_Airspeed.h>
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
@ -30,6 +31,9 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
float temperature;
|
||||
|
||||
// create an AHRS object for get_airspeed_max
|
||||
AP_AHRS_DCM ahrs;
|
||||
|
||||
// create airspeed object
|
||||
AP_Airspeed airspeed;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user