HAL_Linux: fixed scheduling priorities

need to be between 1 and 99
This commit is contained in:
Andrew Tridgell 2013-10-01 13:05:04 +10:00
parent 134bf5a5c9
commit c9fea2c706
2 changed files with 6 additions and 4 deletions

View File

@ -16,10 +16,10 @@ using namespace Linux;
extern const AP_HAL::HAL& hal;
#define APM_LINUX_MAIN_PRIORITY 180
#define APM_LINUX_TIMER_PRIORITY 182
#define APM_LINUX_UART_PRIORITY 181
#define APM_LINUX_IO_PRIORITY 59
#define APM_LINUX_TIMER_PRIORITY 13
#define APM_LINUX_UART_PRIORITY 12
#define APM_LINUX_MAIN_PRIORITY 11
#define APM_LINUX_IO_PRIORITY 10
LinuxScheduler::LinuxScheduler()
{}

View File

@ -55,6 +55,8 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_wr_fd = 1;
rxS = 512;
txS = 512;
fcntl(_rd_fd, F_SETFL, fcntl(_rd_fd, F_GETFL, 0) | O_NONBLOCK);
fcntl(_wr_fd, F_SETFL, fcntl(_wr_fd, F_GETFL, 0) | O_NONBLOCK);
} else if (!_initialised) {
if (device_path == NULL) {
return;