mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: use AP_RTC
Sub: AP_GPS now sets the system time directly Sub: use AP_RTC for delays in missions
This commit is contained in:
parent
078d90132c
commit
4cc236b8a7
@ -309,9 +309,6 @@ void Sub::update_GPS(void)
|
||||
}
|
||||
|
||||
if (gps_updated) {
|
||||
// set system time if necessary
|
||||
set_system_time_from_GPS();
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
camera.update();
|
||||
#endif
|
||||
|
@ -234,7 +234,6 @@ private:
|
||||
uint8_t compass_mot : 1; // true if we are currently performing compassmot calibration
|
||||
uint8_t motor_test : 1; // true if we are currently performing the motors test
|
||||
uint8_t initialised : 1; // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
|
||||
uint8_t system_time_set : 1; // true if the system time has been set from the GPS
|
||||
uint8_t gps_base_pos_set : 1; // true when the gps base position has been set (used for RTK gps only)
|
||||
uint8_t at_bottom : 1; // true if we are at the bottom
|
||||
uint8_t at_surface : 1; // true if we are at the surface
|
||||
@ -519,7 +518,6 @@ private:
|
||||
bool set_home_to_current_location(bool lock);
|
||||
bool set_home(const Location& loc, bool lock);
|
||||
bool far_from_EKF_origin(const Location& loc);
|
||||
void set_system_time_from_GPS();
|
||||
void exit_mission();
|
||||
bool verify_loiter_unlimited();
|
||||
bool verify_loiter_time();
|
||||
|
@ -112,26 +112,3 @@ bool Sub::far_from_EKF_origin(const Location& loc)
|
||||
// close enough to origin
|
||||
return false;
|
||||
}
|
||||
|
||||
// checks if we should update ahrs/RTL home position from GPS
|
||||
void Sub::set_system_time_from_GPS()
|
||||
{
|
||||
// exit immediately if system time already set
|
||||
if (ap.system_time_set) {
|
||||
return;
|
||||
}
|
||||
|
||||
// if we have a 3d lock and valid location
|
||||
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
uint64_t gps_timestamp = gps.time_epoch_usec();
|
||||
|
||||
// set system clock for log timestamps
|
||||
hal.util->set_system_clock(gps_timestamp);
|
||||
|
||||
// update signing timestamp
|
||||
GCS_MAVLINK::update_signing_timestamp(gps_timestamp);
|
||||
|
||||
ap.system_time_set = true;
|
||||
Log_Write_Event(DATA_SYSTEM_TIME_SET);
|
||||
}
|
||||
}
|
||||
|
@ -1,5 +1,7 @@
|
||||
#include "Sub.h"
|
||||
|
||||
#include <AP_RTC/AP_RTC.h>
|
||||
|
||||
static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
|
||||
|
||||
// start_command - this function will be called when the ap_mission lib wishes to start a new command
|
||||
@ -526,7 +528,7 @@ void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)
|
||||
nav_delay_time_max = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
|
||||
} else {
|
||||
// absolute delay to utc time
|
||||
nav_delay_time_max = hal.util->get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
|
||||
nav_delay_time_max = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
|
||||
}
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec",(unsigned int)(nav_delay_time_max/1000));
|
||||
}
|
||||
|
@ -140,7 +140,7 @@ enum LoggingParameters {
|
||||
|
||||
// DATA - event logging
|
||||
#define DATA_AP_STATE 7
|
||||
#define DATA_SYSTEM_TIME_SET 8
|
||||
// 8 was DATA_SYSTEM_TIME_SET
|
||||
#define DATA_ARMED 10
|
||||
#define DATA_DISARMED 11
|
||||
#define DATA_LOST_GPS 19
|
||||
|
Loading…
Reference in New Issue
Block a user