mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: remove unused method
This commit is contained in:
parent
0e1957328e
commit
979e5261d5
|
@ -240,9 +240,6 @@ public:
|
|||
// return true if channel is private
|
||||
bool is_private(void) const { return is_private(chan); }
|
||||
|
||||
// send queued parameters if needed
|
||||
void send_queued_parameters(void);
|
||||
|
||||
/*
|
||||
send a MAVLink message to all components with this vehicle's system id
|
||||
This is a no-op if no routes to components have been learned
|
||||
|
|
|
@ -314,17 +314,6 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
send queued parameters if needed
|
||||
*/
|
||||
void GCS_MAVLINK::send_queued_parameters(void)
|
||||
{
|
||||
if (!param_timer_registered) {
|
||||
param_timer_registered = true;
|
||||
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::param_io_timer, void));
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
timer callback for async parameter requests
|
||||
|
|
Loading…
Reference in New Issue