mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed build with -Werror-sign-compare
This commit is contained in:
parent
d12cf0ab59
commit
5bf078cc86
|
@ -183,7 +183,7 @@ bool SPIDevice::clock_pulse(uint32_t n)
|
|||
uint16_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
|
||||
{
|
||||
uint32_t spi_clock_freq = SPI1_CLOCK;
|
||||
if (busid > 0 && busid-1 < ARRAY_SIZE_SIMPLE(bus_clocks)) {
|
||||
if (busid > 0 && uint8_t(busid-1) < ARRAY_SIZE_SIMPLE(bus_clocks)) {
|
||||
spi_clock_freq = bus_clocks[busid-1] / 2;
|
||||
}
|
||||
|
||||
|
|
|
@ -22,8 +22,8 @@
|
|||
#include "shared_dma.h"
|
||||
#include "Semaphores.h"
|
||||
|
||||
#define RX_BOUNCE_BUFSIZE 128
|
||||
#define TX_BOUNCE_BUFSIZE 64
|
||||
#define RX_BOUNCE_BUFSIZE 128U
|
||||
#define TX_BOUNCE_BUFSIZE 64U
|
||||
|
||||
#define UART_MAX_DRIVERS 7
|
||||
|
||||
|
|
Loading…
Reference in New Issue