mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_SmartRTL: update example to new API and fix object copy
ahrs should be a reference to DummyVehicle::ahrs, otherwise it will act on a different object. This also corrects the member initialization order: only pass a copy or reference of an object to a constructor if it has already been initialized.
This commit is contained in:
parent
a2b67ed615
commit
903ef4d065
@ -12,25 +12,26 @@
|
|||||||
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||||
|
|
||||||
// INS and Baro declaration
|
// INS and Baro declaration
|
||||||
AP_InertialSensor ins;
|
static AP_InertialSensor ins = AP_InertialSensor::create();
|
||||||
Compass compass;
|
static Compass compass = Compass::create();
|
||||||
AP_GPS gps;
|
static AP_GPS gps = AP_GPS::create();
|
||||||
AP_Baro barometer;
|
static AP_Baro barometer = AP_Baro::create();
|
||||||
AP_SerialManager serial_manager;
|
static AP_SerialManager serial_manager = AP_SerialManager::create();
|
||||||
|
|
||||||
class DummyVehicle {
|
class DummyVehicle {
|
||||||
public:
|
public:
|
||||||
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
|
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
|
||||||
AP_AHRS_NavEKF ahrs{ins, barometer, gps, rangefinder, EKF2, EKF3,
|
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
|
||||||
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
|
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
|
||||||
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
|
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3,
|
||||||
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
|
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF);
|
||||||
};
|
};
|
||||||
|
|
||||||
static DummyVehicle vehicle;
|
static DummyVehicle vehicle;
|
||||||
|
|
||||||
AP_AHRS_NavEKF ahrs(vehicle.ahrs);
|
AP_AHRS_NavEKF &ahrs(vehicle.ahrs);
|
||||||
AP_SmartRTL smart_rtl{ahrs, true};
|
AP_SmartRTL smart_rtl{ahrs, true};
|
||||||
|
AP_BoardConfig board_config = AP_BoardConfig::create();
|
||||||
|
|
||||||
void setup();
|
void setup();
|
||||||
void loop();
|
void loop();
|
||||||
@ -40,7 +41,7 @@ void check_path(const std::vector<Vector3f> &correct_path, const char* test_name
|
|||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
hal.console->printf("SmartRTL test\n");
|
hal.console->printf("SmartRTL test\n");
|
||||||
AP_BoardConfig{}.init();
|
board_config.init();
|
||||||
smart_rtl.init();
|
smart_rtl.init();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user