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

This commit is contained in:
Peter Barker 2019-04-26 17:13:16 +10:00 committed by Andrew Tridgell
parent 3e4366906b
commit 973222c786
2 changed files with 10 additions and 8 deletions

View File

@ -219,14 +219,6 @@ bool GCS_Sub::vehicle_initialised() const {
// try to send a message, return false if it won't fit in the serial tx buffer // try to send a message, return false if it won't fit in the serial tx buffer
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id) bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
{ {
// 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
if (sub.scheduler.time_available_usec() < 250 && sub.motors.armed()) {
gcs().set_out_of_time(true);
return false;
}
switch (id) { switch (id) {
case MSG_NAMED_FLOAT: case MSG_NAMED_FLOAT:

View File

@ -27,6 +27,16 @@ public:
bool vehicle_initialised() const override; bool vehicle_initialised() 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: private:
GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS]; GCS_MAVLINK_Sub _chan[MAVLINK_COMM_NUM_BUFFERS];