mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_AVR: prevent build of AVR code on non-AVR platforms
This commit is contained in:
parent
9b15d0e714
commit
551ff0c8b8
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
@ -88,3 +90,4 @@ void ADCSource::new_sample(uint16_t sample) {
|
||||||
_sum_count++;
|
_sum_count++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
@ -123,3 +125,4 @@ AP_HAL::AnalogSource* AVRAnalogIn::channel(int16_t ch, float scale) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
@ -158,3 +160,4 @@ void AVRDigitalSource::write(uint8_t value) {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -31,6 +31,9 @@
|
||||||
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
@ -314,3 +317,4 @@ SIGNAL(TWI_vect)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
@ -146,3 +148,5 @@ void APM1RCInput::clear_overrides() {
|
||||||
_override[i] = 0;
|
_override[i] = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
@ -146,3 +148,5 @@ void APM2RCInput::clear_overrides() {
|
||||||
_override[i] = 0;
|
_override[i] = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
|
||||||
|
@ -225,3 +227,4 @@ void APM1RCOutput::read(uint16_t* period_us, uint8_t len) {
|
||||||
uint16_t APM1RCOutput::_timer_period(uint16_t speed_hz) {
|
uint16_t APM1RCOutput::_timer_period(uint16_t speed_hz) {
|
||||||
return 2000000UL / speed_hz;
|
return 2000000UL / speed_hz;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
|
||||||
|
@ -217,3 +219,5 @@ void APM2RCOutput::read(uint16_t* period_us, uint8_t len) {
|
||||||
uint16_t APM2RCOutput::_timer_period(uint16_t speed_hz) {
|
uint16_t APM2RCOutput::_timer_period(uint16_t speed_hz) {
|
||||||
return 2000000UL / speed_hz;
|
return 2000000UL / speed_hz;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
@ -47,3 +49,4 @@ AP_HAL::SPIDeviceDriver* APM1SPIDeviceManager::device(enum AP_HAL::SPIDevice d)
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
@ -62,3 +64,4 @@ AP_HAL::SPIDeviceDriver* APM2SPIDeviceManager::device(enum AP_HAL::SPIDevice d)
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
|
||||||
|
@ -67,3 +69,4 @@ uint8_t AVRSPI0DeviceDriver::transfer(uint8_t data) {
|
||||||
return read_spdr;
|
return read_spdr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,4 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
|
||||||
|
@ -67,3 +68,4 @@ uint8_t AVRSPI2DeviceDriver::transfer(uint8_t data) {
|
||||||
return UDR2;
|
return UDR2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
@ -71,3 +73,4 @@ uint8_t AVRSPI3DeviceDriver::transfer(uint8_t data) {
|
||||||
return UDR3;
|
return UDR3;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
|
@ -159,3 +161,5 @@ void AVRTimer::delay_microseconds(uint16_t us)
|
||||||
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
|
"brne 1b" : "=w" (us) : "0" (us) // 2 cycles
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,5 @@
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
#include <avr/eeprom.h>
|
#include <avr/eeprom.h>
|
||||||
|
@ -36,3 +38,4 @@ void AVREEPROMStorage::write_block(uint16_t dst, void *src, size_t n) {
|
||||||
eeprom_write_block(src,(void*)dst,n);
|
eeprom_write_block(src,(void*)dst,n);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
|
@ -7,6 +7,8 @@
|
||||||
// Free Software Foundation; either version 2.1 of the License, or (at
|
// Free Software Foundation; either version 2.1 of the License, or (at
|
||||||
// your option) any later version.
|
// your option) any later version.
|
||||||
//
|
//
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <limits.h>
|
#include <limits.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
@ -279,3 +281,4 @@ void AVRUARTDriver::_printf_P(const prog_char *fmt, ...) {
|
||||||
vprintf((AP_HAL::Print*)this, 1, fmt, ap);
|
vprintf((AP_HAL::Print*)this, 1, fmt, ap);
|
||||||
va_end(ap);
|
va_end(ap);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,6 +1,7 @@
|
||||||
|
|
||||||
#ifndef __AP_HAL_AVR_UART_DRIVER_H__
|
#ifndef __AP_HAL_AVR_UART_DRIVER_H__
|
||||||
#define __AP_HAL_AVR_UART_DRIVER_H__
|
#define __AP_HAL_AVR_UART_DRIVER_H__
|
||||||
|
#if (CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2)
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdarg.h>
|
#include <stdarg.h>
|
||||||
|
@ -212,6 +213,6 @@ struct hack
|
||||||
UCSR##_num##B, \
|
UCSR##_num##B, \
|
||||||
_BV(UDRIE##_num))
|
_BV(UDRIE##_num))
|
||||||
|
|
||||||
|
#endif
|
||||||
#endif // __AP_HAL_AVR_UART_DRIVER_H__
|
#endif // __AP_HAL_AVR_UART_DRIVER_H__
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue