Browse Source

GCS_MAVLink: use AP_RTC

GCS_MAVLINK: Add SYSTEM_TIME handle (Patrick José Pereira)
master
Peter Barker 7 years ago committed by Andrew Tridgell
parent
commit
721feaf40f
  1. 2
      libraries/GCS_MAVLink/GCS.h
  2. 17
      libraries/GCS_MAVLink/GCS_Common.cpp

2
libraries/GCS_MAVLink/GCS.h

@ -296,7 +296,7 @@ protected: @@ -296,7 +296,7 @@ protected:
void handle_param_request_list(mavlink_message_t *msg);
void handle_param_request_read(mavlink_message_t *msg);
virtual bool params_ready() const { return true; }
void handle_system_time_message(const mavlink_message_t *msg);
void handle_common_rally_message(mavlink_message_t *msg);
void handle_rally_fetch_point(mavlink_message_t *msg);
void handle_rally_point(mavlink_message_t *msg);

17
libraries/GCS_MAVLink/GCS_Common.cpp

@ -976,9 +976,12 @@ GCS_MAVLINK::update(uint32_t max_time_us) @@ -976,9 +976,12 @@ GCS_MAVLINK::update(uint32_t max_time_us)
*/
void GCS_MAVLINK::send_system_time()
{
uint64_t time_unix = 0;
AP::rtc().get_utc_usec(time_unix); // may fail, leaving time_unix at 0
mavlink_msg_system_time_send(
chan,
AP::gps().time_epoch_usec(),
time_unix,
AP_HAL::millis());
}
@ -1950,6 +1953,14 @@ void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg) @@ -1950,6 +1953,14 @@ void GCS_MAVLINK::handle_statustext(mavlink_message_t *msg)
}
void GCS_MAVLINK::handle_system_time_message(const mavlink_message_t *msg)
{
mavlink_system_time_t packet;
mavlink_msg_system_time_decode(msg, &packet);
AP::rtc().set_utc_usec(packet.time_unix_usec, AP_RTC::SOURCE_MAVLINK_SYSTEM_TIME);
}
MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_long_t &packet)
{
AP_Camera *camera = get_camera();
@ -2331,6 +2342,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg) @@ -2331,6 +2342,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
case MAVLINK_MSG_ID_ATT_POS_MOCAP:
handle_att_pos_mocap(msg);
break;
case MAVLINK_MSG_ID_SYSTEM_TIME:
handle_system_time_message(msg);
break;
}
}

Loading…
Cancel
Save