Copter: allow GCS MAVLink base class to handle out-of-time for sending messages

This commit is contained in:
Peter Barker 2019-04-26 17:12:54 +10:00 committed by Andrew Tridgell
parent feddaabc42
commit b0beca7b01
2 changed files with 10 additions and 14 deletions

View File

@ -32,6 +32,16 @@ public:
bool simple_input_active() const override;
bool supersimple_input_active() const override;
protected:
// minimum amount of time (in microseconds) that must remain in
// the main scheduler loop before we are allowed to send any
// mavlink messages. We want to prioritise the main flight
// control loop over communications
uint16_t min_loop_time_remaining_for_message_send_us() const override {
return 250;
}
private:
GCS_MAVLINK_Copter _chan[MAVLINK_COMM_NUM_BUFFERS];

View File

@ -251,20 +251,6 @@ bool GCS_Copter::vehicle_initialised() const {
// try to send a message, return false if it wasn't sent
bool GCS_MAVLINK_Copter::try_send_message(enum ap_message id)
{
#if HIL_MODE != HIL_MODE_SENSORS
// if we don't have at least 250 micros remaining before the main loop
// wants to fire then don't send a mavlink message. We want to
// prioritise the main flight control loop over communications
// the check for nullptr here doesn't just save a nullptr
// dereference; it means that we send messages out even if we're
// failing to detect a PX4 board type (see delay(3000) in px_drivers).
if (copter.motors != nullptr && copter.scheduler.time_available_usec() < 250 && copter.motors->armed()) {
gcs().set_out_of_time(true);
return false;
}
#endif
switch(id) {
case MSG_TERRAIN: