APM:Copter
commands.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // checks if we should update ahrs/RTL home position from the EKF
5 {
6  // exit immediately if home already set
7  if (ahrs.home_is_set()) {
8  return;
9  }
10 
11  // special logic if home is set in-flight
12  if (motors->armed()) {
14  } else {
15  // move home to current ekf location (this will set home_state to HOME_SET)
17  }
18 }
19 
20 // set_home_to_current_location_inflight - set home to current GPS location (horizontally) and EKF origin vertically
22  // get current location from EKF
23  Location temp_loc;
24  if (inertial_nav.get_location(temp_loc)) {
25  const struct Location &ekf_origin = inertial_nav.get_origin();
26  temp_loc.alt = ekf_origin.alt;
27  if (!set_home(temp_loc, false)) {
28  return;
29  }
30  // we have successfully set AHRS home, set it for SmartRTL
31 #if MODE_SMARTRTL_ENABLED == ENABLED
32  g2.smart_rtl.set_home(true);
33 #endif
34  }
35 }
36 
37 // set_home_to_current_location - set home to current GPS location
39  // get current location from EKF
40  Location temp_loc;
41  if (inertial_nav.get_location(temp_loc)) {
42  if (!set_home(temp_loc, lock)) {
43  return false;
44  }
45  // we have successfully set AHRS home, set it for SmartRTL
46 #if MODE_SMARTRTL_ENABLED == ENABLED
47  g2.smart_rtl.set_home(true);
48 #endif
49  return true;
50  }
51  return false;
52 }
53 
54 // set_home - sets ahrs home (used for RTL) to specified location
55 // initialises inertial nav and compass on first call
56 // returns true if home location set successfully
57 bool Copter::set_home(const Location& loc, bool lock)
58 {
59  // check location is valid
60  if (loc.lat == 0 && loc.lng == 0) {
61  return false;
62  }
63 
64  // check EKF origin has been set
66  if (!ahrs.get_origin(ekf_origin)) {
67  return false;
68  }
69 
70  // check home is close to EKF origin
71  if (far_from_EKF_origin(loc)) {
72  return false;
73  }
74 
75  const bool home_was_set = ahrs.home_is_set();
76 
77  // set ahrs home (used for RTL)
78  ahrs.set_home(loc);
79 
80  // init inav and compass declination
81  if (!home_was_set) {
82  // update navigation scalers. used to offset the shrinking longitude as we go towards the poles
84  // record home is set
86 
87 #if MODE_AUTO_ENABLED == ENABLED
88  // log new home position which mission library will pull from ahrs
89  if (should_log(MASK_LOG_CMD)) {
91  if (mission.read_cmd_from_storage(0, temp_cmd)) {
93  }
94  }
95 #endif
96  }
97 
98  // lock home position
99  if (lock) {
100  ahrs.lock_home();
101  }
102 
103  // log ahrs home and ekf origin dataflash
105 
106  // send new home and ekf origin to GCS
107  gcs().send_home();
108  gcs().send_ekf_origin();
109 
110  // return success
111  return true;
112 }
113 
114 // far_from_EKF_origin - checks if a location is too far from the EKF origin
115 // returns true if too far
117 {
118  // check distance to EKF origin
119  const struct Location &ekf_origin = inertial_nav.get_origin();
120  if (get_distance(ekf_origin, loc) > EKF_ORIGIN_MAX_DIST_M) {
121  return true;
122  }
123 
124  // close enough to origin
125  return false;
126 }
127 
128 // checks if we should update ahrs/RTL home position from GPS
130 {
131  // exit immediately if system time already set
132  if (ap.system_time_set) {
133  return;
134  }
135 
136  // if we have a 3d lock and valid location
137  if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
138  // set system clock for log timestamps
139  uint64_t gps_timestamp = gps.time_epoch_usec();
140 
141  hal.util->set_system_clock(gps_timestamp);
142 
143  // update signing timestamp
145 
146  ap.system_time_set = true;
148  }
149 }
#define DATA_SYSTEM_TIME_SET
Definition: defines.h:337
bool set_home(const Location &loc, bool lock)
Definition: commands.cpp:57
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
void set_home(const Location &loc) override
struct Location get_origin() const
void set_home_to_current_location_inflight()
Definition: commands.cpp:21
float get_distance(const struct Location &loc1, const struct Location &loc2)
void update_home_from_EKF()
Definition: commands.cpp:4
GCS_Copter & gcs()
Definition: Copter.h:301
#define MASK_LOG_CMD
Definition: defines.h:322
AP_HAL::Util * util
#define DATA_SET_HOME
Definition: defines.h:348
float longitude_scale(const struct Location &loc)
void Log_Write_Home_And_Origin()
bool should_log(uint32_t mask)
Definition: system.cpp:435
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
MOTOR_CLASS * motors
Definition: Copter.h:422
int32_t lat
void lock_home()
bool get_origin(Location &ret) const override
bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const
void send_home() const
int32_t alt
const AP_HAL::HAL & hal
Definition: Copter.cpp:21
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
bool far_from_EKF_origin(const Location &loc)
Definition: commands.cpp:116
float scaleLongDown
Definition: Copter.h:427
GPS_Status status(uint8_t instance) const
virtual void set_system_clock(uint64_t time_utc_usec)
DataFlash_Class DataFlash
Definition: Copter.h:227
void Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
ekf_origin
AP_GPS gps
Definition: Copter.h:229
int32_t lng
void send_ekf_origin() const
bool set_home_to_current_location(bool lock)
Definition: commands.cpp:38
uint64_t time_epoch_usec(uint8_t instance) const
ParametersG2 g2
Definition: Copter.h:209
void set_home(bool position_ok)
bool home_is_set(void) const
#define EKF_ORIGIN_MAX_DIST_M
Definition: config.h:189
AP_Mission mission
Definition: Copter.h:263
AP_SmartRTL smart_rtl
Definition: Parameters.h:570
void set_system_time_from_GPS()
Definition: commands.cpp:129
bool get_location(struct Location &loc) const