mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-12 01:23:56 -03:00
AP_HAL: enable HAL_QURT
This commit is contained in:
parent
0816937ab1
commit
7c431b40f2
@ -15,6 +15,7 @@
|
|||||||
#define HAL_BOARD_FLYMAPLE 6
|
#define HAL_BOARD_FLYMAPLE 6
|
||||||
#define HAL_BOARD_LINUX 7
|
#define HAL_BOARD_LINUX 7
|
||||||
#define HAL_BOARD_VRBRAIN 8
|
#define HAL_BOARD_VRBRAIN 8
|
||||||
|
#define HAL_BOARD_QURT 9
|
||||||
#define HAL_BOARD_EMPTY 99
|
#define HAL_BOARD_EMPTY 99
|
||||||
|
|
||||||
// default board subtype is -1
|
// default board subtype is -1
|
||||||
@ -66,6 +67,7 @@
|
|||||||
#define HAL_INS_MPU9250_I2C 13
|
#define HAL_INS_MPU9250_I2C 13
|
||||||
#define HAL_INS_BH 14
|
#define HAL_INS_BH 14
|
||||||
#define HAL_INS_QFLIGHT 15
|
#define HAL_INS_QFLIGHT 15
|
||||||
|
#define HAL_INS_QURT 16
|
||||||
|
|
||||||
// barometer driver types
|
// barometer driver types
|
||||||
#define HAL_BARO_BMP085 1
|
#define HAL_BARO_BMP085 1
|
||||||
@ -77,6 +79,7 @@
|
|||||||
#define HAL_BARO_VRBRAIN 7
|
#define HAL_BARO_VRBRAIN 7
|
||||||
#define HAL_BARO_MS5637_I2C 8
|
#define HAL_BARO_MS5637_I2C 8
|
||||||
#define HAL_BARO_QFLIGHT 9
|
#define HAL_BARO_QFLIGHT 9
|
||||||
|
#define HAL_BARO_QURT 10
|
||||||
|
|
||||||
// compass driver types
|
// compass driver types
|
||||||
#define HAL_COMPASS_HMC5843 1
|
#define HAL_COMPASS_HMC5843 1
|
||||||
@ -90,6 +93,7 @@
|
|||||||
#define HAL_COMPASS_AK8963_MPU9250_I2C 9
|
#define HAL_COMPASS_AK8963_MPU9250_I2C 9
|
||||||
#define HAL_COMPASS_BH 10
|
#define HAL_COMPASS_BH 10
|
||||||
#define HAL_COMPASS_QFLIGHT 11
|
#define HAL_COMPASS_QFLIGHT 11
|
||||||
|
#define HAL_COMPASS_QURT 12
|
||||||
|
|
||||||
// Heat Types
|
// Heat Types
|
||||||
#define HAL_LINUX_HEAT_PWM 1
|
#define HAL_LINUX_HEAT_PWM 1
|
||||||
@ -336,6 +340,20 @@
|
|||||||
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HIL
|
#define HAL_COMPASS_DEFAULT HAL_COMPASS_HIL
|
||||||
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
||||||
|
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_QURT
|
||||||
|
#define AP_HAL_BOARD_DRIVER AP_HAL_QURT
|
||||||
|
#define HAL_BOARD_NAME "QURT"
|
||||||
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_1000
|
||||||
|
#define HAL_STORAGE_SIZE 16384
|
||||||
|
#define HAL_STORAGE_SIZE_AVAILABLE HAL_STORAGE_SIZE
|
||||||
|
#define HAL_INS_DEFAULT HAL_INS_QURT
|
||||||
|
#define HAL_BARO_DEFAULT HAL_BARO_QURT
|
||||||
|
#define HAL_COMPASS_DEFAULT HAL_COMPASS_QURT
|
||||||
|
#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_NONE
|
||||||
|
#define HAL_BOARD_LOG_DIRECTORY "/dev/fs/logs"
|
||||||
|
#define HAL_OS_POSIX_IO 1
|
||||||
|
#define HAL_SERIAL0_BAUD_DEFAULT 115200
|
||||||
|
|
||||||
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
||||||
#define HAL_BOARD_NAME "VRBRAIN"
|
#define HAL_BOARD_NAME "VRBRAIN"
|
||||||
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
|
#define HAL_CPU_CLASS HAL_CPU_CLASS_150
|
||||||
@ -383,5 +401,8 @@
|
|||||||
#error "No CONFIG_HAL_BOARD_SUBTYPE set"
|
#error "No CONFIG_HAL_BOARD_SUBTYPE set"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef HAL_OS_POSIX_IO
|
||||||
|
#define HAL_OS_POSIX_IO 0
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // __AP_HAL_BOARDS_H__
|
#endif // __AP_HAL_BOARDS_H__
|
||||||
|
@ -3,7 +3,7 @@
|
|||||||
|
|
||||||
#include "HAL.h"
|
#include "HAL.h"
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
#if CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE || CONFIG_HAL_BOARD == HAL_BOARD_QURT
|
||||||
#define CONFIG_MAIN_WITHOUT_ARGC_ARGV 1
|
#define CONFIG_MAIN_WITHOUT_ARGC_ARGV 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@ -20,7 +20,7 @@
|
|||||||
#define AP_HAL_MAIN() extern "C" { \
|
#define AP_HAL_MAIN() extern "C" { \
|
||||||
int AP_MAIN(void); \
|
int AP_MAIN(void); \
|
||||||
int AP_MAIN(void) { \
|
int AP_MAIN(void) { \
|
||||||
AP_HAL::HAL::FunCallbacks callbacks(setup, loop); \
|
AP_HAL::HAL::FunCallbacks callbacks(setup, loop); \
|
||||||
hal.run(0, NULL, &callbacks); \
|
hal.run(0, NULL, &callbacks); \
|
||||||
return 0; \
|
return 0; \
|
||||||
} \
|
} \
|
||||||
|
@ -18,7 +18,7 @@
|
|||||||
*/
|
*/
|
||||||
#define BUF_AVAILABLE(buf) ((buf##_head > (_tail=buf##_tail))? (buf##_size - buf##_head) + _tail: _tail - buf##_head)
|
#define BUF_AVAILABLE(buf) ((buf##_head > (_tail=buf##_tail))? (buf##_size - buf##_head) + _tail: _tail - buf##_head)
|
||||||
#define BUF_SPACE(buf) (((_head=buf##_head) > buf##_tail)?(_head - buf##_tail) - 1:((buf##_size - buf##_tail) + _head) - 1)
|
#define BUF_SPACE(buf) (((_head=buf##_head) > buf##_tail)?(_head - buf##_tail) - 1:((buf##_size - buf##_tail) + _head) - 1)
|
||||||
#define BUF_EMPTY(buf) (buf##_head == buf##_tail)
|
#define BUF_EMPTY(buf) buf##_head == buf##_tail
|
||||||
#define BUF_ADVANCETAIL(buf, n) buf##_tail = (buf##_tail + n) % buf##_size
|
#define BUF_ADVANCETAIL(buf, n) buf##_tail = (buf##_tail + n) % buf##_size
|
||||||
#define BUF_ADVANCEHEAD(buf, n) buf##_head = (buf##_head + n) % buf##_size
|
#define BUF_ADVANCEHEAD(buf, n) buf##_head = (buf##_head + n) % buf##_size
|
||||||
|
|
||||||
|
@ -35,6 +35,9 @@
|
|||||||
* SUCH DAMAGE.
|
* SUCH DAMAGE.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#if HAL_OS_POSIX_IO && CONFIG_HAL_BOARD != HAL_BOARD_QURT
|
||||||
|
|
||||||
#include "getopt_cpp.h"
|
#include "getopt_cpp.h"
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
@ -201,3 +204,5 @@ int GetOptLong::getoption(void)
|
|||||||
return optopt;
|
return optopt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAL_OS_POSIX_IO
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user