mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: fix example by instantiating a GCS object
This commit is contained in:
parent
5992cc8782
commit
1ff3cd442d
|
@ -11,9 +11,14 @@
|
|||
#include <AP_Compass/AP_Compass.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_AHRS/AP_AHRS_DCM.h>
|
||||
#include <GCS_MAVLink/GCS_Dummy.h>
|
||||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
const struct AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
class MissionTest {
|
||||
public:
|
||||
void setup();
|
||||
|
@ -25,6 +30,7 @@ private:
|
|||
AP_GPS gps;
|
||||
Compass compass;
|
||||
AP_AHRS_DCM ahrs{};
|
||||
GCS_Dummy _gcs;
|
||||
|
||||
// global constants that control how many verify calls must be made for a command before it completes
|
||||
uint8_t verify_nav_cmd_iterations_to_complete = 3;
|
||||
|
|
Loading…
Reference in New Issue