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:
Lucas De Marchi 2017-09-11 16:07:33 -07:00 committed by Francisco Ferreira
parent a2b67ed615
commit 903ef4d065
1 changed files with 14 additions and 13 deletions

View File

@ -12,25 +12,26 @@
const AP_HAL::HAL &hal = AP_HAL::get_HAL();
// INS and Baro declaration
AP_InertialSensor ins;
Compass compass;
AP_GPS gps;
AP_Baro barometer;
AP_SerialManager serial_manager;
static AP_InertialSensor ins = AP_InertialSensor::create();
static Compass compass = Compass::create();
static AP_GPS gps = AP_GPS::create();
static AP_Baro barometer = AP_Baro::create();
static AP_SerialManager serial_manager = AP_SerialManager::create();
class DummyVehicle {
public:
RangeFinder rangefinder {serial_manager, ROTATION_PITCH_270};
AP_AHRS_NavEKF ahrs{ins, barometer, gps, rangefinder, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
NavEKF2 EKF2{&ahrs, barometer, rangefinder};
NavEKF3 EKF3{&ahrs, barometer, rangefinder};
RangeFinder rangefinder = RangeFinder::create(serial_manager, ROTATION_PITCH_270);
NavEKF2 EKF2 = NavEKF2::create(&ahrs, barometer, rangefinder);
NavEKF3 EKF3 = NavEKF3::create(&ahrs, barometer, rangefinder);
AP_AHRS_NavEKF ahrs = AP_AHRS_NavEKF::create(ins, barometer, gps, EKF2, EKF3,
AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF);
};
static DummyVehicle vehicle;
AP_AHRS_NavEKF ahrs(vehicle.ahrs);
AP_SmartRTL smart_rtl {ahrs, true};
AP_AHRS_NavEKF &ahrs(vehicle.ahrs);
AP_SmartRTL smart_rtl{ahrs, true};
AP_BoardConfig board_config = AP_BoardConfig::create();
void setup();
void loop();
@ -40,7 +41,7 @@ void check_path(const std::vector<Vector3f> &correct_path, const char* test_name
void setup()
{
hal.console->printf("SmartRTL test\n");
AP_BoardConfig{}.init();
board_config.init();
smart_rtl.init();
}