Copter: move home state into AP_AHRS

This commit is contained in:
Peter Barker 2018-03-16 12:23:28 +11:00 committed by Randy Mackay
parent 9d0da4a71f
commit 45f2312bfe
9 changed files with 11 additions and 49 deletions

View File

@ -702,11 +702,6 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return AP_Arming::arm_checks(arming_from_gcs); return AP_Arming::arm_checks(arming_from_gcs);
} }
enum HomeState AP_Arming_Copter::home_status() const
{
return copter.ap.home_state;
}
void AP_Arming_Copter::set_pre_arm_check(bool b) void AP_Arming_Copter::set_pre_arm_check(bool b)
{ {
copter.ap.pre_arm_check = b; copter.ap.pre_arm_check = b;

View File

@ -47,8 +47,6 @@ protected:
void set_pre_arm_check(bool b); void set_pre_arm_check(bool b);
enum HomeState home_status() const override;
private: private:
const AP_InertialNav_NavEKF &_inav; const AP_InertialNav_NavEKF &_inav;

View File

@ -1,27 +1,5 @@
#include "Copter.h" #include "Copter.h"
// set_home_state - update home state
void Copter::set_home_state(enum HomeState new_home_state)
{
// if no change, exit immediately
if (ap.home_state == new_home_state)
return;
// update state
ap.home_state = new_home_state;
// log if home has been set
if (new_home_state == HOME_SET_NOT_LOCKED || new_home_state == HOME_SET_AND_LOCKED) {
Log_Write_Event(DATA_SET_HOME);
}
}
// home_is_set - returns true if home positions has been set (to GPS location, armed location or EKF origin)
bool Copter::home_is_set()
{
return (ap.home_state == HOME_SET_NOT_LOCKED || ap.home_state == HOME_SET_AND_LOCKED);
}
// --------------------------------------------- // ---------------------------------------------
void Copter::set_auto_armed(bool b) void Copter::set_auto_armed(bool b)
{ {

View File

@ -315,7 +315,6 @@ private:
uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock uint8_t throttle_zero : 1; // 15 // true if the throttle stick is at zero, debounced, determines if pilot intends shut-down when not using motor interlock
uint8_t system_time_set : 1; // 16 // true if the system time has been set from the GPS uint8_t system_time_set : 1; // 16 // true if the system time has been set from the GPS
uint8_t gps_glitching : 1; // 17 // true if the gps is glitching uint8_t gps_glitching : 1; // 17 // true if the gps is glitching
enum HomeState home_state : 2; // 18,19 // home status (unset, set, locked)
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
uint8_t motor_emergency_stop : 1; // 21 // motor estop switch, shuts off motors when enabled uint8_t motor_emergency_stop : 1; // 21 // motor estop switch, shuts off motors when enabled
uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position
@ -630,8 +629,6 @@ private:
static const struct LogStructure log_structure[]; static const struct LogStructure log_structure[];
// AP_State.cpp // AP_State.cpp
void set_home_state(enum HomeState new_home_state);
bool home_is_set();
void set_auto_armed(bool b); void set_auto_armed(bool b);
void set_simple_mode(uint8_t b); void set_simple_mode(uint8_t b);
void set_failsafe_radio(bool b); void set_failsafe_radio(bool b);

View File

@ -860,7 +860,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
new_home_loc.alt = packet.z * 100; new_home_loc.alt = packet.z * 100;
// handle relative altitude // handle relative altitude
if (packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT || packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) { if (packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT || packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
if (copter.ap.home_state == HOME_UNSET) { if (!AP::ahrs().home_is_set()) {
// cannot use relative altitude if home is not set // cannot use relative altitude if home is not set
break; break;
} }
@ -1126,7 +1126,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
break; break;
case MAV_CMD_GET_HOME_POSITION: case MAV_CMD_GET_HOME_POSITION:
if (copter.ap.home_state != HOME_UNSET) { if (AP::ahrs().home_is_set()) {
send_home(copter.ahrs.get_home()); send_home(copter.ahrs.get_home());
Location ekf_origin; Location ekf_origin;
if (copter.ahrs.get_origin(ekf_origin)) { if (copter.ahrs.get_origin(ekf_origin)) {

View File

@ -378,7 +378,7 @@ void Copter::Log_Write_Home_And_Origin()
} }
// log ahrs home if set // log ahrs home if set
if (ap.home_state != HOME_UNSET) { if (ahrs.home_is_set()) {
DataFlash.Log_Write_Origin(LogOriginType::ahrs_home, ahrs.get_home()); DataFlash.Log_Write_Origin(LogOriginType::ahrs_home, ahrs.get_home());
} }
} }

View File

@ -1,17 +1,10 @@
#include "Copter.h" #include "Copter.h"
/*
* the home_state has a number of possible values (see enum HomeState in defines.h's)
* HOME_UNSET = home is not set, no GPS positions yet received
* HOME_SET_NOT_LOCKED = home is set to EKF origin or armed location (can be moved)
* HOME_SET_AND_LOCKED = home has been set by user, cannot be moved except by user initiated do-set-home command
*/
// checks if we should update ahrs/RTL home position from the EKF // checks if we should update ahrs/RTL home position from the EKF
void Copter::update_home_from_EKF() void Copter::update_home_from_EKF()
{ {
// exit immediately if home already set // exit immediately if home already set
if (ap.home_state != HOME_UNSET) { if (ahrs.home_is_set()) {
return; return;
} }
@ -83,11 +76,12 @@ bool Copter::set_home(const Location& loc, bool lock)
ahrs.set_home(loc); ahrs.set_home(loc);
// init inav and compass declination // init inav and compass declination
if (ap.home_state == HOME_UNSET) { if (!ahrs.home_is_set()) {
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles // update navigation scalers. used to offset the shrinking longitude as we go towards the poles
scaleLongDown = longitude_scale(loc); scaleLongDown = longitude_scale(loc);
// record home is set // record home is set
set_home_state(HOME_SET_NOT_LOCKED); ahrs.set_home_status(HOME_SET_NOT_LOCKED);
Log_Write_Event(DATA_SET_HOME);
#if MODE_AUTO_ENABLED == ENABLED #if MODE_AUTO_ENABLED == ENABLED
// log new home position which mission library will pull from ahrs // log new home position which mission library will pull from ahrs
@ -102,7 +96,7 @@ bool Copter::set_home(const Location& loc, bool lock)
// lock home position // lock home position
if (lock) { if (lock) {
set_home_state(HOME_SET_AND_LOCKED); ahrs.set_home_status(HOME_SET_AND_LOCKED);
} }
// log ahrs home and ekf origin dataflash // log ahrs home and ekf origin dataflash

View File

@ -16,7 +16,7 @@ void Copter::read_inertia()
} }
// without home return alt above the EKF origin // without home return alt above the EKF origin
if (ap.home_state == HOME_UNSET) { if (!ahrs.home_is_set()) {
// with inertial nav we can update the altitude and climb rate at 50hz // with inertial nav we can update the altitude and climb rate at 50hz
current_loc.alt = inertial_nav.get_altitude(); current_loc.alt = inertial_nav.get_altitude();
} else { } else {

View File

@ -176,14 +176,14 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
initial_armed_bearing = ahrs.yaw_sensor; initial_armed_bearing = ahrs.yaw_sensor;
if (ap.home_state == HOME_UNSET) { if (!ahrs.home_is_set()) {
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home) // Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
ahrs.resetHeightDatum(); ahrs.resetHeightDatum();
Log_Write_Event(DATA_EKF_ALT_RESET); Log_Write_Event(DATA_EKF_ALT_RESET);
// we have reset height, so arming height is zero // we have reset height, so arming height is zero
arming_altitude_m = 0; arming_altitude_m = 0;
} else if (ap.home_state == HOME_SET_NOT_LOCKED) { } else if (ahrs.home_status() == HOME_SET_NOT_LOCKED) {
// Reset home position if it has already been set before (but not locked) // Reset home position if it has already been set before (but not locked)
set_home_to_current_location(false); set_home_to_current_location(false);