mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 07:13:56 -04:00
HAL_Linux: use board subtypes
This commit is contained in:
parent
7195e38585
commit
fc8068adfe
@ -27,7 +27,7 @@
|
|||||||
* `void setup()` and `void loop()`, ala Arduino.
|
* `void setup()` and `void loop()`, ala Arduino.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "HAL_Linux_Class.h"
|
#include "HAL_Linux_Class.h"
|
||||||
#include "AP_HAL_Linux_Main.h"
|
#include "AP_HAL_Linux_Main.h"
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
#ifndef __AP_HAL_LINUX_MAIN_H__
|
#ifndef __AP_HAL_LINUX_MAIN_H__
|
||||||
#define __AP_HAL_LINUX_MAIN_H__
|
#define __AP_HAL_LINUX_MAIN_H__
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#define AP_HAL_MAIN() extern "C" {\
|
#define AP_HAL_MAIN() extern "C" {\
|
||||||
int main (int argc, char * const argv[]) { \
|
int main (int argc, char * const argv[]) { \
|
||||||
hal.init(argc, argv); \
|
hal.init(argc, argv); \
|
||||||
@ -13,6 +13,6 @@ int main (int argc, char * const argv[]) { \
|
|||||||
return 0;\
|
return 0;\
|
||||||
}\
|
}\
|
||||||
}
|
}
|
||||||
#endif // HAL_BOARD_LINUX || HAL_BOARD_ERLE
|
#endif // HAL_BOARD_LINUX
|
||||||
|
|
||||||
#endif // __AP_HAL_LINUX_MAIN_H__
|
#endif // __AP_HAL_LINUX_MAIN_H__
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include "AnalogIn.h"
|
#include "AnalogIn.h"
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "GPIO.h"
|
#include "GPIO.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "HAL_Linux_Class.h"
|
#include "HAL_Linux_Class.h"
|
||||||
#include "AP_HAL_Linux_Private.h"
|
#include "AP_HAL_Linux_Private.h"
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include "I2CDriver.h"
|
#include "I2CDriver.h"
|
||||||
|
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
@ -13,9 +13,12 @@
|
|||||||
#include <linux/i2c-dev.h>
|
#include <linux/i2c-dev.h>
|
||||||
#ifndef I2C_SMBUS_BLOCK_MAX
|
#ifndef I2C_SMBUS_BLOCK_MAX
|
||||||
#include <linux/i2c.h>
|
#include <linux/i2c.h>
|
||||||
#define I2C_DATA_TYPE __u8
|
#endif
|
||||||
#else
|
|
||||||
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NONE
|
||||||
#define I2C_DATA_TYPE char
|
#define I2C_DATA_TYPE char
|
||||||
|
#else
|
||||||
|
#define I2C_DATA_TYPE __u8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
using namespace Linux;
|
using namespace Linux;
|
||||||
@ -182,7 +185,7 @@ uint8_t LinuxI2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
|
|||||||
msgs[i*2].addr = addr;
|
msgs[i*2].addr = addr;
|
||||||
msgs[i*2].flags = 0;
|
msgs[i*2].flags = 0;
|
||||||
msgs[i*2].len = 1;
|
msgs[i*2].len = 1;
|
||||||
msgs[i*2].buf = ®
|
msgs[i*2].buf = (I2C_DATA_TYPE *)®
|
||||||
msgs[i*2+1].addr = addr;
|
msgs[i*2+1].addr = addr;
|
||||||
msgs[i*2+1].flags = I2C_M_RD;
|
msgs[i*2+1].flags = I2C_M_RD;
|
||||||
msgs[i*2+1].len = len;
|
msgs[i*2+1].len = len;
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "RCInput.h"
|
#include "RCInput.h"
|
||||||
|
|
||||||
|
@ -1,7 +1,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "RCOutput.h"
|
#include "RCOutput.h"
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include "SPIDriver.h"
|
#include "SPIDriver.h"
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
#include <sys/stat.h>
|
#include <sys/stat.h>
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "Scheduler.h"
|
#include "Scheduler.h"
|
||||||
#include "Storage.h"
|
#include "Storage.h"
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL_Linux.h>
|
#include <AP_HAL_Linux.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include <sys/time.h>
|
#include <sys/time.h>
|
||||||
#include <pthread.h>
|
#include <pthread.h>
|
||||||
|
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "Semaphores.h"
|
#include "Semaphores.h"
|
||||||
|
|
||||||
|
@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
#include <AP_HAL_Boards.h>
|
#include <AP_HAL_Boards.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include <AP_HAL_Linux.h>
|
#include <AP_HAL_Linux.h>
|
||||||
#include <pthread.h>
|
#include <pthread.h>
|
||||||
|
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include <assert.h>
|
#include <assert.h>
|
||||||
#include <sys/types.h>
|
#include <sys/types.h>
|
||||||
|
@ -1,6 +1,6 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
|
||||||
#include "UARTDriver.h"
|
#include "UARTDriver.h"
|
||||||
|
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdarg.h>
|
#include <stdarg.h>
|
||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
@ -20,4 +20,4 @@ void LinuxUtil::commandline_arguments(uint8_t &argc, char * const *&argv)
|
|||||||
argv = saved_argv;
|
argv = saved_argv;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE
|
#endif // CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
Loading…
Reference in New Issue
Block a user