mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Tracker: move adjust_rate_for_stream up
This commit is contained in:
parent
de452eb760
commit
ddd956f8e1
@ -377,15 +377,6 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
float GCS_MAVLINK_Tracker::adjust_rate_for_stream_trigger(enum streams stream_num)
|
||||
{
|
||||
if (_queued_parameter != nullptr) {
|
||||
return 0.25f;
|
||||
}
|
||||
|
||||
return 1.0f;
|
||||
}
|
||||
|
||||
void
|
||||
GCS_MAVLINK_Tracker::data_stream_send(void)
|
||||
{
|
||||
|
@ -13,7 +13,6 @@ protected:
|
||||
|
||||
private:
|
||||
|
||||
float adjust_rate_for_stream_trigger(enum streams stream_num) override;
|
||||
void handleMessage(mavlink_message_t * msg) override;
|
||||
bool handle_guided_request(AP_Mission::Mission_Command &cmd) override;
|
||||
void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override;
|
||||
|
Loading…
Reference in New Issue
Block a user