AP_Mission: use ahrs singleton

This commit is contained in:
Peter Barker 2018-04-25 09:09:26 +10:00 committed by Randy Mackay
parent 65e4d74b1f
commit a9b94ae13d
3 changed files with 12 additions and 10 deletions

View File

@ -4,6 +4,7 @@
#include "AP_Mission.h"
#include <AP_Terrain/AP_Terrain.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_AHRS/AP_AHRS.h>
const AP_Param::GroupInfo AP_Mission::var_info[] = {
@ -480,7 +481,7 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
cmd.index = 0;
cmd.id = MAV_CMD_NAV_WAYPOINT;
cmd.p1 = 0;
cmd.content.location = _ahrs.get_home();
cmd.content.location = AP::ahrs().get_home();
}else{
// Find out proper location in memory by using the start_byte position + the index
// we can load a command, we don't process it yet
@ -546,7 +547,7 @@ void AP_Mission::write_home_to_storage()
{
Mission_Command home_cmd = {};
home_cmd.id = MAV_CMD_NAV_WAYPOINT;
home_cmd.content.location = _ahrs.get_home();
home_cmd.content.location = AP::ahrs().get_home();
write_cmd_to_storage(0,home_cmd);
}
@ -1715,7 +1716,7 @@ uint16_t AP_Mission::get_landing_sequence_start()
{
struct Location current_loc;
if (!_ahrs.get_position(current_loc)) {
if (!AP::ahrs().get_position(current_loc)) {
return 0;
}

View File

@ -18,7 +18,6 @@
#include <AP_Math/AP_Math.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_AHRS/AP_AHRS.h>
#include <StorageManager/StorageManager.h>
// definitions
@ -281,8 +280,7 @@ public:
FUNCTOR_TYPEDEF(mission_complete_fn_t, void);
// constructor
AP_Mission(AP_AHRS &ahrs, mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn) :
_ahrs(ahrs),
AP_Mission(mission_cmd_fn_t cmd_start_fn, mission_cmd_fn_t cmd_verify_fn, mission_complete_fn_t mission_complete_fn) :
_cmd_start_fn(cmd_start_fn),
_cmd_verify_fn(cmd_verify_fn),
_mission_complete_fn(mission_complete_fn),
@ -546,9 +544,6 @@ private:
/// sanity checks that the masked fields are not NaN's or infinite
static MAV_MISSION_RESULT sanity_check_params(const mavlink_mission_item_int_t& packet);
// references to external libraries
const AP_AHRS& _ahrs; // used only for home position
// parameters
AP_Int16 _cmd_total; // total number of commands in the mission
AP_Int8 _restart; // controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)

View File

@ -5,6 +5,12 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_InertialSensor/AP_InertialSensor.h>
#include <AP_Baro/AP_Baro.h>
#include <AP_GPS/AP_GPS.h>
#include <AP_Compass/AP_Compass.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_AHRS/AP_AHRS_DCM.h>
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
@ -44,7 +50,7 @@ private:
void run_replace_cmd_test();
void run_max_cmd_test();
AP_Mission mission{ahrs,
AP_Mission mission{
FUNCTOR_BIND_MEMBER(&MissionTest::start_cmd, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&MissionTest::verify_cmd, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&MissionTest::mission_complete, void)};