mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
HAL_AVR: fixes for HAL_GPIO_ define change
This commit is contained in:
parent
18a64d17d3
commit
3015356671
@ -99,7 +99,7 @@ void ADCSource::set_pin(uint8_t pin) {
|
||||
if (dpin != -1) {
|
||||
// enable as input without a pull-up. This gives the
|
||||
// best results for our analog sensors
|
||||
hal.gpio->pinMode(dpin, GPIO_INPUT);
|
||||
hal.gpio->pinMode(dpin, HAL_GPIO_INPUT);
|
||||
hal.gpio->write(dpin, 0);
|
||||
}
|
||||
}
|
||||
@ -153,7 +153,7 @@ float ADCSource::_read_average() {
|
||||
void ADCSource::setup_read() {
|
||||
if (_stop_pin != ANALOG_INPUT_NONE) {
|
||||
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
|
||||
hal.gpio->pinMode(digital_pin, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(digital_pin, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(digital_pin, 1);
|
||||
}
|
||||
if (_settle_time_ms != 0) {
|
||||
@ -173,7 +173,7 @@ void ADCSource::setup_read() {
|
||||
void ADCSource::stop_read() {
|
||||
if (_stop_pin != ANALOG_INPUT_NONE) {
|
||||
uint8_t digital_pin = hal.gpio->analogPinToDigitalPin(_stop_pin);
|
||||
hal.gpio->pinMode(digital_pin, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(digital_pin, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(digital_pin, 0);
|
||||
}
|
||||
}
|
||||
|
@ -48,7 +48,7 @@ void AVRGPIO::pinMode(uint8_t pin, uint8_t mode) {
|
||||
// JWS: can I let the optimizer do this?
|
||||
reg = portModeRegister(port);
|
||||
|
||||
if (mode == GPIO_INPUT) {
|
||||
if (mode == HAL_GPIO_INPUT) {
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
*reg &= ~bit;
|
||||
@ -119,7 +119,10 @@ bool AVRGPIO::attach_interrupt(
|
||||
uint8_t interrupt_num, AP_HAL::Proc proc, uint8_t mode) {
|
||||
/* Mode is to set the ISCn0 and ISCn1 bits.
|
||||
* These correspond to the GPIO_INTERRUPT_ defs in AP_HAL.h */
|
||||
if (!((mode == 0)||(mode == 1)||(mode == 2)||(mode==3))) return false;
|
||||
if (!((mode == HAL_GPIO_INTERRUPT_LOW)||
|
||||
(mode == HAL_GPIO_INTERRUPT_HIGH)||
|
||||
(mode == HAL_GPIO_INTERRUPT_FALLING)||
|
||||
(mode == HAL_GPIO_INTERRUPT_RISING))) return false;
|
||||
if (interrupt_num == 6) {
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
@ -150,7 +153,7 @@ void AVRDigitalSource::mode(uint8_t output) {
|
||||
volatile uint8_t* reg;
|
||||
reg = portModeRegister(port);
|
||||
|
||||
if (output == GPIO_INPUT) {
|
||||
if (output == HAL_GPIO_INPUT) {
|
||||
uint8_t oldSREG = SREG;
|
||||
cli();
|
||||
*reg &= ~bit;
|
||||
@ -208,7 +211,7 @@ void AVRDigitalSource::toggle() {
|
||||
bool AVRGPIO::usb_connected(void)
|
||||
{
|
||||
#if HAL_GPIO_USB_MUX_PIN != -1
|
||||
pinMode(HAL_GPIO_USB_MUX_PIN, GPIO_INPUT);
|
||||
pinMode(HAL_GPIO_USB_MUX_PIN, HAL_GPIO_INPUT);
|
||||
return !read(HAL_GPIO_USB_MUX_PIN);
|
||||
#else
|
||||
return false;
|
||||
|
@ -59,7 +59,7 @@ void APM1RCInput::init(void* _isrregistry) {
|
||||
/* initialize overrides */
|
||||
clear_overrides();
|
||||
/* Arduino pin 49 is ICP4 / PL0, timer 4 input capture */
|
||||
hal.gpio->pinMode(49, GPIO_INPUT);
|
||||
hal.gpio->pinMode(49, HAL_GPIO_INPUT);
|
||||
/**
|
||||
* WGM: 1 1 1 1. Fast WPM, TOP is in OCR4A
|
||||
* COM all disabled
|
||||
|
@ -59,7 +59,7 @@ void APM2RCInput::init(void* _isrregistry) {
|
||||
/* initialize overrides */
|
||||
clear_overrides();
|
||||
/* Arduino pin 48 is ICP5 / PL1, timer 5 input capture */
|
||||
hal.gpio->pinMode(48, GPIO_INPUT);
|
||||
hal.gpio->pinMode(48, HAL_GPIO_INPUT);
|
||||
/**
|
||||
* WGM: 1 1 1 1. Fast WPM, TOP is in OCR5A
|
||||
* COM all disabled
|
||||
|
@ -13,9 +13,9 @@ extern const AP_HAL::HAL& hal;
|
||||
/* No init argument required */
|
||||
void APM1RCOutput::init(void* machtnichts) {
|
||||
// --------------------- TIMER1: CH_3, CH_4, and CH_10 ---------------
|
||||
hal.gpio->pinMode(11,GPIO_OUTPUT); // CH_10 (PB5/OC1A)
|
||||
hal.gpio->pinMode(12,GPIO_OUTPUT); // CH_3 (PB6/OC1B)
|
||||
hal.gpio->pinMode(13,GPIO_OUTPUT); // CH_4 (PB7/OC1C)
|
||||
hal.gpio->pinMode(11,HAL_GPIO_OUTPUT); // CH_10 (PB5/OC1A)
|
||||
hal.gpio->pinMode(12,HAL_GPIO_OUTPUT); // CH_3 (PB6/OC1B)
|
||||
hal.gpio->pinMode(13,HAL_GPIO_OUTPUT); // CH_4 (PB7/OC1C)
|
||||
|
||||
// WGM: 1 1 1 0. Clear Timer on Compare, TOP is ICR1.
|
||||
// CS11: prescale by 8 => 0.5us tick
|
||||
@ -27,9 +27,9 @@ void APM1RCOutput::init(void* machtnichts) {
|
||||
OCR1C = 0xFFFF;
|
||||
|
||||
//--------------- TIMER3: CH_7, CH_8, and CH_11 ---------------------
|
||||
hal.gpio->pinMode(5,GPIO_OUTPUT); // CH_11 (PE3/OC3A)
|
||||
hal.gpio->pinMode(2,GPIO_OUTPUT); // CH_8 (PE4/OC3B)
|
||||
hal.gpio->pinMode(3,GPIO_OUTPUT); // CH_7 (PE5/OC3C)
|
||||
hal.gpio->pinMode(5,HAL_GPIO_OUTPUT); // CH_11 (PE3/OC3A)
|
||||
hal.gpio->pinMode(2,HAL_GPIO_OUTPUT); // CH_8 (PE4/OC3B)
|
||||
hal.gpio->pinMode(3,HAL_GPIO_OUTPUT); // CH_7 (PE5/OC3C)
|
||||
|
||||
// WGM: 1 1 1 0. Clear timer on Compare, TOP is ICR3
|
||||
// CS31: prescale by 8 => 0.5us tick
|
||||
@ -43,14 +43,14 @@ void APM1RCOutput::init(void* machtnichts) {
|
||||
//--------------- TIMER4: CH_6 and CH_5 ----------------------------
|
||||
// NB TIMER4 is shared with PPM input from RCInput_APM1.cpp
|
||||
// The TIMER4 registers are assumed to be setup already.
|
||||
hal.gpio->pinMode(7,GPIO_OUTPUT); // CH_5 (PH4/OC4B)
|
||||
hal.gpio->pinMode(8,GPIO_OUTPUT); // CH_6 (PH5/OC4C)
|
||||
hal.gpio->pinMode(7,HAL_GPIO_OUTPUT); // CH_5 (PH4/OC4B)
|
||||
hal.gpio->pinMode(8,HAL_GPIO_OUTPUT); // CH_6 (PH5/OC4C)
|
||||
|
||||
|
||||
//--------------- TIMER5: CH_1, CH_2 and CH_9 -----------------------
|
||||
hal.gpio->pinMode(46, GPIO_OUTPUT); // CH_9 (PL3/OC5A)
|
||||
hal.gpio->pinMode(45, GPIO_OUTPUT); // CH_1 (PL4/OC5B)
|
||||
hal.gpio->pinMode(44, GPIO_OUTPUT); // CH_2 (PL5/OC5C)
|
||||
hal.gpio->pinMode(46, HAL_GPIO_OUTPUT); // CH_9 (PL3/OC5A)
|
||||
hal.gpio->pinMode(45, HAL_GPIO_OUTPUT); // CH_1 (PL4/OC5B)
|
||||
hal.gpio->pinMode(44, HAL_GPIO_OUTPUT); // CH_2 (PL5/OC5C)
|
||||
|
||||
// WGM: 1 1 1 0. Clear timer on Compare, TOP is ICR5
|
||||
// CS51: prescale by 8 => 0.5us tick
|
||||
|
@ -13,8 +13,8 @@ extern const AP_HAL::HAL& hal;
|
||||
/* No init argument required */
|
||||
void APM2RCOutput::init(void* machtnichts) {
|
||||
// --------------------- TIMER1: CH_1 and CH_2 -----------------------
|
||||
hal.gpio->pinMode(12,GPIO_OUTPUT); // CH_1 (PB6/OC1B)
|
||||
hal.gpio->pinMode(11,GPIO_OUTPUT); // CH_2 (PB5/OC1A)
|
||||
hal.gpio->pinMode(12,HAL_GPIO_OUTPUT); // CH_1 (PB6/OC1B)
|
||||
hal.gpio->pinMode(11,HAL_GPIO_OUTPUT); // CH_2 (PB5/OC1A)
|
||||
|
||||
// WGM: 1 1 1 0. Clear Timer on Compare, TOP is ICR1.
|
||||
// CS11: prescale by 8 => 0.5us tick
|
||||
@ -25,9 +25,9 @@ void APM2RCOutput::init(void* machtnichts) {
|
||||
OCR1B = 0xFFFF;
|
||||
|
||||
// --------------- TIMER4: CH_3, CH_4, and CH_5 ---------------------
|
||||
hal.gpio->pinMode(8,GPIO_OUTPUT); // CH_3 (PH5/OC4C)
|
||||
hal.gpio->pinMode(7,GPIO_OUTPUT); // CH_4 (PH4/OC4B)
|
||||
hal.gpio->pinMode(6,GPIO_OUTPUT); // CH_5 (PH3/OC4A)
|
||||
hal.gpio->pinMode(8,HAL_GPIO_OUTPUT); // CH_3 (PH5/OC4C)
|
||||
hal.gpio->pinMode(7,HAL_GPIO_OUTPUT); // CH_4 (PH4/OC4B)
|
||||
hal.gpio->pinMode(6,HAL_GPIO_OUTPUT); // CH_5 (PH3/OC4A)
|
||||
|
||||
// WGM: 1 1 1 0. Clear Timer on Compare, TOP is ICR4.
|
||||
// CS41: prescale by 8 => 0.5us tick
|
||||
@ -39,9 +39,9 @@ void APM2RCOutput::init(void* machtnichts) {
|
||||
ICR4 = 40000; // 0.5us tick => 50hz freq
|
||||
|
||||
//--------------- TIMER3: CH_6, CH_7, and CH_8 ----------------------
|
||||
hal.gpio->pinMode(3,GPIO_OUTPUT); // CH_6 (PE5/OC3C)
|
||||
hal.gpio->pinMode(2,GPIO_OUTPUT); // CH_7 (PE4/OC3B)
|
||||
hal.gpio->pinMode(5,GPIO_OUTPUT); // CH_8 (PE3/OC3A)
|
||||
hal.gpio->pinMode(3,HAL_GPIO_OUTPUT); // CH_6 (PE5/OC3C)
|
||||
hal.gpio->pinMode(2,HAL_GPIO_OUTPUT); // CH_7 (PE4/OC3B)
|
||||
hal.gpio->pinMode(5,HAL_GPIO_OUTPUT); // CH_8 (PE3/OC3A)
|
||||
|
||||
// WGM: 1 1 1 0. Clear timer on Compare, TOP is ICR3
|
||||
// CS31: prescale by 8 => 0.5us tick
|
||||
@ -55,8 +55,8 @@ void APM2RCOutput::init(void* machtnichts) {
|
||||
//--------------- TIMER5: CH_10, and CH_11 ---------------
|
||||
// NB TIMER5 is shared with PPM input from RCInput_APM2.cpp
|
||||
// The TIMER5 registers are assumed to be setup already.
|
||||
hal.gpio->pinMode(45, GPIO_OUTPUT); // CH_10 (PL4/OC5B)
|
||||
hal.gpio->pinMode(44, GPIO_OUTPUT); // CH_11 (PL5/OC5C)
|
||||
hal.gpio->pinMode(45, HAL_GPIO_OUTPUT); // CH_10 (PL4/OC5B)
|
||||
hal.gpio->pinMode(44, HAL_GPIO_OUTPUT); // CH_11 (PL5/OC5C)
|
||||
}
|
||||
|
||||
/* Output freq (1/period) control */
|
||||
|
@ -22,11 +22,11 @@ bool AVRSPI0DeviceDriver::_force_low_speed;
|
||||
static volatile bool spi0_transferflag = false;
|
||||
|
||||
void AVRSPI0DeviceDriver::init() {
|
||||
hal.gpio->pinMode(SPI0_MISO_PIN, GPIO_INPUT);
|
||||
hal.gpio->pinMode(SPI0_MOSI_PIN, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI0_SCK_PIN, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI0_MISO_PIN, HAL_GPIO_INPUT);
|
||||
hal.gpio->pinMode(SPI0_MOSI_PIN, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI0_SCK_PIN, HAL_GPIO_OUTPUT);
|
||||
|
||||
_cs_pin->mode(GPIO_OUTPUT);
|
||||
_cs_pin->mode(HAL_GPIO_OUTPUT);
|
||||
_cs_pin->write(1);
|
||||
|
||||
/* Enable the SPI0 peripheral as a master */
|
||||
|
@ -17,13 +17,13 @@ AVRSemaphore AVRSPI2DeviceDriver::_semaphore;
|
||||
|
||||
void AVRSPI2DeviceDriver::init() {
|
||||
AVRDigitalSource spi2_miso(_BV(0), PH);
|
||||
spi2_miso.mode(GPIO_INPUT);
|
||||
spi2_miso.mode(HAL_GPIO_INPUT);
|
||||
|
||||
AVRDigitalSource spi2_mosi(_BV(1), PH);
|
||||
spi2_mosi.mode(GPIO_OUTPUT);
|
||||
spi2_mosi.mode(HAL_GPIO_OUTPUT);
|
||||
|
||||
AVRDigitalSource spi2_sck(_BV(2), PH);
|
||||
spi2_sck.mode(GPIO_OUTPUT);
|
||||
spi2_sck.mode(HAL_GPIO_OUTPUT);
|
||||
|
||||
/* UMSELn1 and UMSELn2: USART in SPI Master mode */
|
||||
UCSR2C = _BV(UMSEL21) | _BV(UMSEL20);
|
||||
@ -31,7 +31,7 @@ void AVRSPI2DeviceDriver::init() {
|
||||
UCSR2B = _BV(RXEN2) | _BV(TXEN2);
|
||||
|
||||
/* Setup chip select pin */
|
||||
_cs_pin->mode(GPIO_OUTPUT);
|
||||
_cs_pin->mode(HAL_GPIO_OUTPUT);
|
||||
_cs_pin->write(1);
|
||||
}
|
||||
|
||||
|
@ -26,9 +26,9 @@ void AVRSPI3DeviceDriver::init() {
|
||||
* by the arduino pin numbers, so we access it directly
|
||||
* with AVRDigitalSource. */
|
||||
AVRDigitalSource spi3_sck(_BV(2), PJ);
|
||||
spi3_sck.mode(GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI3_MOSI, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI3_MISO, GPIO_INPUT);
|
||||
spi3_sck.mode(HAL_GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI3_MOSI, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(SPI3_MISO, HAL_GPIO_INPUT);
|
||||
|
||||
/* UMSELn1 and UMSELn2: USART in SPI Master mode */
|
||||
UCSR3C = _BV(UMSEL31) | _BV(UMSEL30);
|
||||
@ -36,7 +36,7 @@ void AVRSPI3DeviceDriver::init() {
|
||||
UCSR3B = _BV(RXEN3) | _BV(TXEN3);
|
||||
|
||||
/* Setup chip select pin */
|
||||
_cs_pin->mode(GPIO_OUTPUT);
|
||||
_cs_pin->mode(HAL_GPIO_OUTPUT);
|
||||
_cs_pin->write(1);
|
||||
}
|
||||
|
||||
|
@ -34,16 +34,16 @@ void loop (void) {
|
||||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.gpio->pinMode(13, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(13, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(13, 0);
|
||||
|
||||
a_led = hal.gpio->channel(27);
|
||||
b_led = hal.gpio->channel(26);
|
||||
c_led = hal.gpio->channel(25);
|
||||
|
||||
a_led->mode(GPIO_OUTPUT);
|
||||
b_led->mode(GPIO_OUTPUT);
|
||||
c_led->mode(GPIO_OUTPUT);
|
||||
a_led->mode(HAL_GPIO_OUTPUT);
|
||||
b_led->mode(HAL_GPIO_OUTPUT);
|
||||
c_led->mode(HAL_GPIO_OUTPUT);
|
||||
|
||||
a_led->write(0);
|
||||
b_led->write(0);
|
||||
|
@ -58,7 +58,7 @@ LiquidCrystal lcd(8, 9, 4, 5, 6, 7);
|
||||
|
||||
void setup() {
|
||||
/* pin 54 is A0 on the mega */
|
||||
hal.gpio->pinMode(54, GPIO_INPUT);
|
||||
hal.gpio->pinMode(54, HAL_GPIO_INPUT);
|
||||
// set up the LCD's number of columns and rows:
|
||||
lcd.begin(16, 2);
|
||||
// Print a message to the LCD.
|
||||
|
@ -70,12 +70,12 @@ void LiquidCrystal::init(uint8_t fourbitmode, uint8_t rs, uint8_t rw, uint8_t en
|
||||
_data_pins[6] = d6;
|
||||
_data_pins[7] = d7;
|
||||
|
||||
hal.gpio->pinMode(_rs_pin, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(_rs_pin, HAL_GPIO_OUTPUT);
|
||||
// we can save 1 pin by not using RW. Indicate by passing 255 instead of pin#
|
||||
if (_rw_pin != 255) {
|
||||
hal.gpio->pinMode(_rw_pin, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(_rw_pin, HAL_GPIO_OUTPUT);
|
||||
}
|
||||
hal.gpio->pinMode(_enable_pin, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(_enable_pin, HAL_GPIO_OUTPUT);
|
||||
|
||||
if (fourbitmode)
|
||||
_displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS;
|
||||
@ -296,7 +296,7 @@ void LiquidCrystal::pulseEnable(void) {
|
||||
|
||||
void LiquidCrystal::write4bits(uint8_t value) {
|
||||
for (int i = 0; i < 4; i++) {
|
||||
hal.gpio->pinMode(_data_pins[i], GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(_data_pins[i], HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(_data_pins[i], (value >> i) & 0x01);
|
||||
}
|
||||
|
||||
@ -305,7 +305,7 @@ void LiquidCrystal::write4bits(uint8_t value) {
|
||||
|
||||
void LiquidCrystal::write8bits(uint8_t value) {
|
||||
for (int i = 0; i < 8; i++) {
|
||||
hal.gpio->pinMode(_data_pins[i], GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(_data_pins[i], HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(_data_pins[i], (value >> i) & 0x01);
|
||||
}
|
||||
|
||||
|
@ -61,7 +61,7 @@ void loop (void) {
|
||||
|
||||
void setup (void) {
|
||||
hal.console->printf_P(PSTR("reading rc in:"));
|
||||
hal.gpio->pinMode(27, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(27, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(27, 0);
|
||||
}
|
||||
|
||||
|
@ -81,7 +81,7 @@ void loop (void) {
|
||||
}
|
||||
|
||||
void setup (void) {
|
||||
hal.gpio->pinMode(27, GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(27, HAL_GPIO_OUTPUT);
|
||||
hal.gpio->write(27, 0);
|
||||
for (uint8_t i=0; i<16; i++) {
|
||||
hal.rcout->enable_ch(i);
|
||||
|
@ -59,7 +59,7 @@ void schedule_toggle_hang(void *) {
|
||||
|
||||
void setup_pin(int pin_num) {
|
||||
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
||||
hal.gpio->pinMode(pin_num,GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(pin_num,HAL_GPIO_OUTPUT);
|
||||
/* Blink so we can see setup on the logic analyzer.*/
|
||||
hal.gpio->write(pin_num,1);
|
||||
hal.gpio->write(pin_num,0);
|
||||
|
@ -54,7 +54,7 @@ void blink_a3() {
|
||||
|
||||
void setup_pin(int pin_num) {
|
||||
hal.console->printf_P(PSTR("Setup pin %d\r\n"), pin_num);
|
||||
hal.gpio->pinMode(pin_num,GPIO_OUTPUT);
|
||||
hal.gpio->pinMode(pin_num,HAL_GPIO_OUTPUT);
|
||||
/* Blink so we can see setup on the logic analyzer.*/
|
||||
hal.gpio->write(pin_num,1);
|
||||
hal.gpio->write(pin_num,0);
|
||||
|
Loading…
Reference in New Issue
Block a user