GCS_MAVLink: create persist_streamrates() callback to indicate persistence

Removes the catching of the message in each vehicle separately.
This commit is contained in:
Peter Barker 2018-05-21 22:34:22 +10:00 committed by Andrew Tridgell
parent 879f250fac
commit d8871078ff
3 changed files with 9 additions and 4 deletions

View File

@ -278,7 +278,8 @@ protected:
// saveable rate of each stream
AP_Int16 streamRates[NUM_STREAMS];
void handle_request_data_stream(mavlink_message_t *msg, bool save);
virtual bool persist_streamrates() const { return false; }
void handle_request_data_stream(mavlink_message_t *msg);
virtual void handle_command_ack(const mavlink_message_t* msg);
void handle_set_mode(mavlink_message_t* msg);

View File

@ -2349,6 +2349,10 @@ void GCS_MAVLINK::handle_common_message(mavlink_message_t *msg)
handle_common_rally_message(msg);
break;
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
handle_request_data_stream(msg);
break;
case MAVLINK_MSG_ID_DATA96:
handle_data_packet(msg);
break;

View File

@ -124,7 +124,7 @@ bool GCS_MAVLINK::have_flow_control(void)
save==false so we don't want the save to happen when the user connects the
ground station.
*/
void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save)
void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg)
{
mavlink_request_data_stream_t packet;
mavlink_msg_request_data_stream_decode(msg, &packet);
@ -143,7 +143,7 @@ void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save)
case MAV_DATA_STREAM_ALL:
// note that we don't set STREAM_PARAMS - that is internal only
for (uint8_t i=0; i<STREAM_PARAMS; i++) {
if (save) {
if (persist_streamrates()) {
streamRates[i].set_and_save_ifchanged(freq);
} else {
streamRates[i].set(freq);
@ -177,7 +177,7 @@ void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save)
}
if (rate != nullptr) {
if (save) {
if (persist_streamrates()) {
rate->set_and_save_ifchanged(freq);
} else {
rate->set(freq);