mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: move adjust_rate_for_stream up
This commit is contained in:
parent
f4f0ae8c8b
commit
43fed65f37
|
@ -254,7 +254,8 @@ protected:
|
|||
void handle_setup_signing(const mavlink_message_t *msg);
|
||||
|
||||
private:
|
||||
virtual float adjust_rate_for_stream_trigger(enum streams stream_num) = 0;
|
||||
// Tracker is the only vehicle to override this, and it probably shouldn't
|
||||
virtual float adjust_rate_for_stream_trigger(enum streams stream_num);
|
||||
|
||||
virtual void handleMessage(mavlink_message_t * msg) = 0;
|
||||
|
||||
|
|
|
@ -1616,3 +1616,15 @@ void GCS_MAVLINK::send_heartbeat(uint8_t type, uint8_t base_mode, uint32_t custo
|
|||
custom_mode,
|
||||
system_status);
|
||||
}
|
||||
|
||||
float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
{
|
||||
// send at a much lower rate while handling waypoints and
|
||||
// parameter sends
|
||||
if ((stream_num != STREAM_PARAMS) &&
|
||||
(waypoint_receiving || _queued_parameter != NULL)) {
|
||||
return 0.25f;
|
||||
}
|
||||
|
||||
return 1.0f;
|
||||
}
|
||||
|
|
|
@ -21,7 +21,6 @@ protected:
|
|||
|
||||
private:
|
||||
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num) override { return 0.0f; }
|
||||
void handleMessage(mavlink_message_t * msg) { }
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override { return false ; }
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override { }
|
||||
|
|
Loading…
Reference in New Issue