GCS_MAVLink: fixed build with MAVLink1

This commit is contained in:
Andrew Tridgell 2016-01-21 17:55:50 +11:00
parent 24eb6afbe9
commit 970dbf3c8d
3 changed files with 38 additions and 10 deletions

View File

@ -204,6 +204,9 @@ public:
dataflash_p = dataflash;
}
// update signing timestamp on GPS lock
static void update_signing_timestamp(uint64_t timestamp_usec);
private:
float adjust_rate_for_stream_trigger(enum streams stream_num);
@ -356,8 +359,14 @@ private:
// return true if this channel has hardware flow control
bool have_flow_control(void);
#if MAVLINK_PROTOCOL_VERSION >= 2
mavlink_signing_t signing;
static mavlink_signing_streams_t signing_streams;
static StorageAccess _signing_storage;
void handle_setup_signing(const mavlink_message_t *msg);
bool signing_key_save(const struct SigningKey &key);
bool signing_key_load(struct SigningKey &key);
void load_signing_key(void);
#endif // MAVLINK_PROTOCOL_VERSION
};

View File

@ -49,15 +49,6 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan)
initialised = true;
_queued_parameter = NULL;
reset_cli_timeout();
// setup for signing
mavlink_status_t *status = mavlink_get_channel_status(chan);
signing.flags = MAVLINK_SIGNING_FLAG_SIGN_OUTGOING;
signing.link_id = chan;
signing.timestamp = 0;
memset(signing.secret_key, 42, sizeof(signing.secret_key));
status->signing = &signing;
}
@ -110,8 +101,10 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager
// and init the gcs instance
init(uart, mav_chan);
#if MAVLINK_PROTOCOL_VERSION >= 2
// load signing key
load_signing_key();
#endif
}
/**

View File

@ -21,6 +21,8 @@
extern const AP_HAL::HAL& hal;
#if MAVLINK_PROTOCOL_VERSION >= 2
// storage object
StorageAccess GCS_MAVLINK::_signing_storage(StorageManager::StorageKeys);
@ -124,10 +126,34 @@ void GCS_MAVLINK::load_signing_key(void)
}
memcpy(signing.secret_key, key.secret_key, 32);
signing.link_id = (uint8_t)chan;
signing.timestamp = 1;
signing.timestamp = key.timestamp;
signing.flags = MAVLINK_SIGNING_FLAG_SIGN_OUTGOING;
signing.accept_unsigned_callback = accept_unsigned_callback;
status->signing = &signing;
status->signing_streams = &signing_streams;
}
/*
update signing timestamp. This is called when we get GPS lock
timestamp_usec is since 1/1/1970 (the epoch)
*/
void GCS_MAVLINK::update_signing_timestamp(uint64_t timestamp_usec)
{
uint64_t signing_timestamp = (timestamp_usec / 1000*1000UL);
const uint64_t epoch_offset = 1420070400;
if (signing_timestamp > epoch_offset) {
signing_timestamp -= epoch_offset;
}
for (uint8_t i=0; i<MAVLINK_COMM_NUM_BUFFERS; i++) {
mavlink_channel_t chan = (mavlink_channel_t)(MAVLINK_COMM_0 + i);
mavlink_status_t *status = mavlink_get_channel_status(chan);
if (status && status->signing && status->signing->timestamp < signing_timestamp) {
status->signing->timestamp = signing_timestamp;
}
}
}
#else
void GCS_MAVLINK::update_signing_timestamp(uint64_t timestamp_usec) {}
#endif // MAVLINK_PROTOCOL_VERSION