mirror of https://github.com/ArduPilot/ardupilot
Copter: added MAVLink SYSTEM_TIME message
This commit is contained in:
parent
3289041428
commit
92bf4b9c89
|
@ -1263,12 +1263,12 @@ static void update_GPS(void)
|
|||
|
||||
g_gps->update();
|
||||
|
||||
if (g_gps->new_data && last_gps_time != g_gps->time && g_gps->status() >= GPS::GPS_OK_FIX_2D) {
|
||||
if (g_gps->new_data && last_gps_time != g_gps->last_fix_time && g_gps->status() >= GPS::GPS_OK_FIX_2D) {
|
||||
// clear new data flag
|
||||
g_gps->new_data = false;
|
||||
|
||||
// save GPS time so we don't get duplicate reads
|
||||
last_gps_time = g_gps->time;
|
||||
last_gps_time = g_gps->last_fix_time;
|
||||
|
||||
// log location if we have at least a 2D fix
|
||||
if (g.log_bitmask & MASK_LOG_GPS && motors.armed()) {
|
||||
|
|
|
@ -307,6 +307,14 @@ static void NOINLINE send_gps_raw(mavlink_channel_t chan)
|
|||
|
||||
}
|
||||
|
||||
static void NOINLINE send_system_time(mavlink_channel_t chan)
|
||||
{
|
||||
mavlink_msg_system_time_send(
|
||||
chan,
|
||||
g_gps->time_epoch_usec(),
|
||||
hal.scheduler->millis());
|
||||
}
|
||||
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
||||
{
|
||||
|
@ -561,6 +569,11 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
|||
send_gps_raw(chan);
|
||||
break;
|
||||
|
||||
case MSG_SYSTEM_TIME:
|
||||
CHECK_PAYLOAD_SIZE(SYSTEM_TIME);
|
||||
send_system_time(chan);
|
||||
break;
|
||||
|
||||
case MSG_SERVO_OUT:
|
||||
#if HIL_MODE != HIL_MODE_DISABLED
|
||||
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
|
||||
|
@ -1048,6 +1061,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|||
if (stream_trigger(STREAM_EXTRA3)) {
|
||||
send_message(MSG_AHRS);
|
||||
send_message(MSG_HWSTATUS);
|
||||
send_message(MSG_SYSTEM_TIME);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -715,6 +715,7 @@ static void Log_Write_PID(uint8_t pid_id, int32_t error, int32_t p, int32_t i, i
|
|||
struct PACKED log_Camera {
|
||||
LOG_PACKET_HEADER;
|
||||
uint32_t gps_time;
|
||||
uint16_t gps_week;
|
||||
int32_t latitude;
|
||||
int32_t longitude;
|
||||
int32_t altitude;
|
||||
|
@ -729,7 +730,8 @@ static void Log_Write_Camera()
|
|||
#if CAMERA == ENABLED
|
||||
struct log_Camera pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CAMERA_MSG),
|
||||
gps_time : g_gps->time,
|
||||
gps_time : g_gps->time_week_ms,
|
||||
gps_week : g_gps->time_week,
|
||||
latitude : current_loc.lat,
|
||||
longitude : current_loc.lng,
|
||||
altitude : current_loc.alt,
|
||||
|
@ -818,7 +820,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
|
|||
{ LOG_PID_MSG, sizeof(log_PID),
|
||||
"PID", "Biiiiif", "Id,Error,P,I,D,Out,Gain" },
|
||||
{ LOG_CAMERA_MSG, sizeof(log_Camera),
|
||||
"CAM", "ILLeccC", "GPSTime,Lat,Lng,Alt,Roll,Pitch,Yaw" },
|
||||
"CAM", "IHLLeccC", "GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw" },
|
||||
{ LOG_ERROR_MSG, sizeof(log_Error),
|
||||
"ERR", "BB", "Subsys,ECode" },
|
||||
};
|
||||
|
|
|
@ -259,6 +259,7 @@ enum ap_message {
|
|||
MSG_RAW_IMU2,
|
||||
MSG_RAW_IMU3,
|
||||
MSG_GPS_RAW,
|
||||
MSG_SYSTEM_TIME,
|
||||
MSG_SERVO_OUT,
|
||||
MSG_NEXT_WAYPOINT,
|
||||
MSG_NEXT_PARAM,
|
||||
|
|
Loading…
Reference in New Issue