Merge pull request #11319 from SteveCEvans/relax_determinism

Add scheduler_relax_rx and scheduler_relax_osd variables
This commit is contained in:
Jan Post 2022-01-21 10:44:08 +01:00 committed by GitHub
commit f2559fbfd8
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
7 changed files with 144 additions and 57 deletions

View File

@ -101,6 +101,7 @@
#include "pg/vcd.h"
#include "pg/vtx_io.h"
#include "pg/usb.h"
#include "pg/scheduler.h"
#include "pg/sdio.h"
#include "pg/rcdevice.h"
#include "pg/stats.h"
@ -1682,6 +1683,9 @@ const clivalue_t valueTable[] = {
{ "expresslrs_model_id", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, UINT8_MAX }, PG_RX_EXPRESSLRS_SPI_CONFIG, offsetof(rxExpressLrsSpiConfig_t, modelId) },
#endif
{ "scheduler_relax_rx", VAR_UINT16 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, 500 }, PG_SCHEDULER_CONFIG, PG_ARRAY_ELEMENT_OFFSET(schedulerConfig_t, 0, rxRelaxDeterminism) },
{ "scheduler_relax_osd", VAR_UINT16 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, 500 }, PG_SCHEDULER_CONFIG, PG_ARRAY_ELEMENT_OFFSET(schedulerConfig_t, 0, osdRelaxDeterminism) },
// PG_TIMECONFIG
#ifdef USE_RTC_TIME
{ "timezone_offset_minutes", VAR_INT16 | MASTER_VALUE, .config.minmax = { TIMEZONE_OFFSET_MINUTES_MIN, TIMEZONE_OFFSET_MINUTES_MAX }, PG_TIME_CONFIG, offsetof(timeConfig_t, tz_offsetMinutes) },

View File

@ -95,64 +95,65 @@
// betaflight specific parameter group ids start at 500
#define PG_BETAFLIGHT_START 500
#define PG_BETAFLIGHT_START 500
//#define PG_MODE_ACTIVATION_OPERATOR_CONFIG 500 removed
#define PG_OSD_CONFIG 501
#define PG_BEEPER_CONFIG 502
#define PG_BEEPER_DEV_CONFIG 503
#define PG_PID_CONFIG 504
#define PG_STATUS_LED_CONFIG 505
#define PG_FLASH_CONFIG 506
#define PG_PPM_CONFIG 507
#define PG_PWM_CONFIG 508
#define PG_SERIAL_PIN_CONFIG 509
#define PG_ADC_CONFIG 510
#define PG_SDCARD_CONFIG 511
#define PG_DISPLAY_PORT_MSP_CONFIG 512
#define PG_OSD_CONFIG 501
#define PG_BEEPER_CONFIG 502
#define PG_BEEPER_DEV_CONFIG 503
#define PG_PID_CONFIG 504
#define PG_STATUS_LED_CONFIG 505
#define PG_FLASH_CONFIG 506
#define PG_PPM_CONFIG 507
#define PG_PWM_CONFIG 508
#define PG_SERIAL_PIN_CONFIG 509
#define PG_ADC_CONFIG 510
#define PG_SDCARD_CONFIG 511
#define PG_DISPLAY_PORT_MSP_CONFIG 512
#define PG_DISPLAY_PORT_MAX7456_CONFIG 513
#define PG_VCD_CONFIG 514
#define PG_VTX_CONFIG 515
#define PG_SONAR_CONFIG 516
#define PG_ESC_SENSOR_CONFIG 517
#define PG_I2C_CONFIG 518
#define PG_DASHBOARD_CONFIG 519
#define PG_SPI_PIN_CONFIG 520
#define PG_ESCSERIAL_CONFIG 521
#define PG_CAMERA_CONTROL_CONFIG 522
#define PG_RX_CC2500_SPI_CONFIG 523
#define PG_MAX7456_CONFIG 524
#define PG_FLYSKY_CONFIG 525
#define PG_TIME_CONFIG 526
#define PG_RANGEFINDER_CONFIG 527 // iNav
#define PG_TRICOPTER_CONFIG 528
#define PG_PINIO_CONFIG 529
#define PG_PINIOBOX_CONFIG 530
#define PG_USB_CONFIG 531
#define PG_SDIO_CONFIG 532
#define PG_VCD_CONFIG 514
#define PG_VTX_CONFIG 515
#define PG_SONAR_CONFIG 516
#define PG_ESC_SENSOR_CONFIG 517
#define PG_I2C_CONFIG 518
#define PG_DASHBOARD_CONFIG 519
#define PG_SPI_PIN_CONFIG 520
#define PG_ESCSERIAL_CONFIG 521
#define PG_CAMERA_CONTROL_CONFIG 522
#define PG_RX_CC2500_SPI_CONFIG 523
#define PG_MAX7456_CONFIG 524
#define PG_FLYSKY_CONFIG 525
#define PG_TIME_CONFIG 526
#define PG_RANGEFINDER_CONFIG 527 // iNav
#define PG_TRICOPTER_CONFIG 528
#define PG_PINIO_CONFIG 529
#define PG_PINIOBOX_CONFIG 530
#define PG_USB_CONFIG 531
#define PG_SDIO_CONFIG 532
#define PG_DISPLAY_PORT_CRSF_CONFIG 533 // no longer required -- never released
#define PG_TIMER_IO_CONFIG 534 // used to store the index for timer use in timerHardware array in target.c
#define PG_SPI_PREINIT_IPU_CONFIG 535
#define PG_SPI_PREINIT_OPU_CONFIG 536
#define PG_RX_SPI_CONFIG 537
#define PG_BOARD_CONFIG 538
#define PG_RCDEVICE_CONFIG 539
#define PG_GYRO_DEVICE_CONFIG 540
#define PG_MCO_CONFIG 541
#define PG_RX_SPEKTRUM_SPI_CONFIG 542
#define PG_SERIAL_UART_CONFIG 543
#define PG_RPM_FILTER_CONFIG 544
#define PG_TIMER_IO_CONFIG 534 // used to store the index for timer use in timerHardware array in target.c
#define PG_SPI_PREINIT_IPU_CONFIG 535
#define PG_SPI_PREINIT_OPU_CONFIG 536
#define PG_RX_SPI_CONFIG 537
#define PG_BOARD_CONFIG 538
#define PG_RCDEVICE_CONFIG 539
#define PG_GYRO_DEVICE_CONFIG 540
#define PG_MCO_CONFIG 541
#define PG_RX_SPEKTRUM_SPI_CONFIG 542
#define PG_SERIAL_UART_CONFIG 543
#define PG_RPM_FILTER_CONFIG 544
#define PG_LED_STRIP_STATUS_MODE_CONFIG 545 // Used to hold the configuration for the LED_STRIP status mode (not built on targets with limited flash)
#define PG_VTX_TABLE_CONFIG 546
#define PG_STATS_CONFIG 547
#define PG_QUADSPI_CONFIG 548
#define PG_TIMER_UP_CONFIG 549 // used to store dmaopt for TIMx_UP channel
#define PG_SDIO_PIN_CONFIG 550
#define PG_PULLUP_CONFIG 551
#define PG_PULLDOWN_CONFIG 552
#define PG_MODE_ACTIVATION_CONFIG 553
#define PG_DYN_NOTCH_CONFIG 554
#define PG_VTX_TABLE_CONFIG 546
#define PG_STATS_CONFIG 547
#define PG_QUADSPI_CONFIG 548
#define PG_TIMER_UP_CONFIG 549 // used to store dmaopt for TIMx_UP channel
#define PG_SDIO_PIN_CONFIG 550
#define PG_PULLUP_CONFIG 551
#define PG_PULLDOWN_CONFIG 552
#define PG_MODE_ACTIVATION_CONFIG 553
#define PG_DYN_NOTCH_CONFIG 554
#define PG_RX_EXPRESSLRS_SPI_CONFIG 555
#define PG_BETAFLIGHT_END 555
#define PG_SCHEDULER_CONFIG 556
#define PG_BETAFLIGHT_END 556
// OSD configuration (subject to change)

31
src/main/pg/scheduler.c Normal file
View File

@ -0,0 +1,31 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "platform.h"
#include "pg/pg_ids.h"
#include "pg/scheduler.h"
PG_REGISTER_WITH_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig, PG_SCHEDULER_CONFIG, 0);
PG_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig,
.rxRelaxDeterminism = SCHEDULER_RELAX_RX,
.osdRelaxDeterminism = SCHEDULER_RELAX_OSD,
);

40
src/main/pg/scheduler.h Normal file
View File

@ -0,0 +1,40 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include "pg/pg.h"
#ifdef STM32F411xE
// Allow RX and OSD tasks to be scheduled at the second attempt on F411 processors
#define SCHEDULER_RELAX_RX 1
#define SCHEDULER_RELAX_OSD 1
#else
#define SCHEDULER_RELAX_RX 25
#define SCHEDULER_RELAX_OSD 25
#endif
typedef struct schedulerConfig_s {
uint16_t rxRelaxDeterminism;
uint16_t osdRelaxDeterminism;
} schedulerConfig_t;
PG_DECLARE(schedulerConfig_t, schedulerConfig);

View File

@ -659,9 +659,9 @@ FAST_CODE void scheduler(void)
#endif // USE_LATE_TASK_STATISTICS
} else if ((selectedTask->taskAgePeriods > TASK_AGE_EXPEDITE_COUNT) ||
#ifdef USE_OSD
(((selectedTask - tasks) == TASK_OSD) && (++skippedOSDAttempts > TASK_AGE_EXPEDITE_OSD)) ||
(((selectedTask - tasks) == TASK_OSD) && (TASK_AGE_EXPEDITE_OSD != 0) && (++skippedOSDAttempts > TASK_AGE_EXPEDITE_OSD)) ||
#endif
(((selectedTask - tasks) == TASK_RX) && (++skippedRxAttempts > TASK_AGE_EXPEDITE_RX))) {
(((selectedTask - tasks) == TASK_RX) && (TASK_AGE_EXPEDITE_RX != 0) && (++skippedRxAttempts > TASK_AGE_EXPEDITE_RX))) {
// If a task has been unable to run, then reduce it's recorded estimated run time to ensure
// it's ultimate scheduling
selectedTask->anticipatedExecutionTime *= TASK_AGE_EXPEDITE_SCALE;

View File

@ -22,6 +22,7 @@
#include "common/time.h"
#include "config/config.h"
#include "pg/scheduler.h"
#define TASK_PERIOD_HZ(hz) (1000000 / (hz))
#define TASK_PERIOD_MS(ms) ((ms) * 1000)
@ -47,8 +48,8 @@
// Decay the estimated max task duration by 1/(1 << TASK_EXEC_TIME_SHIFT) on every invocation
#define TASK_EXEC_TIME_SHIFT 7
#define TASK_AGE_EXPEDITE_RX 25 // Make RX tasks more schedulable if it's failed to be scheduled this many times
#define TASK_AGE_EXPEDITE_OSD 25 // Make OSD tasks more schedulable if it's failed to be scheduled this many times
#define TASK_AGE_EXPEDITE_RX schedulerConfig()->rxRelaxDeterminism // Make RX tasks more schedulable if it's failed to be scheduled this many times
#define TASK_AGE_EXPEDITE_OSD schedulerConfig()->osdRelaxDeterminism // Make OSD tasks more schedulable if it's failed to be scheduled this many times
#define TASK_AGE_EXPEDITE_COUNT 1 // Make aged tasks more schedulable
#define TASK_AGE_EXPEDITE_SCALE 0.9 // By scaling their expected execution time

View File

@ -19,7 +19,17 @@
extern "C" {
#include "platform.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/scheduler.h"
#include "scheduler/scheduler.h"
PG_REGISTER_WITH_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig, PG_SCHEDULER_CONFIG, 0);
PG_RESET_TEMPLATE(schedulerConfig_t, schedulerConfig,
.rxRelaxDeterminism = 25,
.osdRelaxDeterminism = 25,
);
}
#include "unittest_macros.h"