2015-10-19 15:01:24 -03:00
|
|
|
#ifndef __AP_HAL_MAIN_H__
|
|
|
|
#define __AP_HAL_MAIN_H__
|
|
|
|
|
|
|
|
#include "HAL.h"
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
|
|
|
|
#define CONFIG_MAIN_WITHOUT_ARGC_ARGV 1
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
|
|
|
|
#define AP_MAIN __EXPORT ArduPilot_main
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifndef AP_MAIN
|
|
|
|
#define AP_MAIN main
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if CONFIG_MAIN_WITHOUT_ARGC_ARGV
|
|
|
|
|
|
|
|
#define AP_HAL_MAIN() extern "C" { \
|
|
|
|
int AP_MAIN(void) { \
|
|
|
|
AP_HAL::HAL::FunCallbacks callbacks(setup, loop); \
|
|
|
|
hal.run(0, NULL, &callbacks); \
|
|
|
|
return 0; \
|
|
|
|
} \
|
|
|
|
}
|
|
|
|
|
2015-10-19 15:05:54 -03:00
|
|
|
#define AP_HAL_MAIN_CALLBACKS(CALLBACKS) extern "C" { \
|
|
|
|
int AP_MAIN(void) { \
|
|
|
|
hal.run(0, NULL, CALLBACKS); \
|
|
|
|
return 0; \
|
|
|
|
} \
|
|
|
|
}
|
|
|
|
|
2015-10-19 15:01:24 -03:00
|
|
|
#else
|
|
|
|
|
|
|
|
#define AP_HAL_MAIN() extern "C" { \
|
|
|
|
int AP_MAIN(int argc, char* const argv[]) { \
|
|
|
|
AP_HAL::HAL::FunCallbacks callbacks(setup, loop); \
|
|
|
|
hal.run(argc, argv, &callbacks); \
|
|
|
|
return 0; \
|
|
|
|
} \
|
|
|
|
}
|
|
|
|
|
2015-10-19 15:05:54 -03:00
|
|
|
#define AP_HAL_MAIN_CALLBACKS(CALLBACKS) extern "C" { \
|
|
|
|
int AP_MAIN(int argc, char* const argv[]) { \
|
|
|
|
hal.run(argc, argv, CALLBACKS); \
|
|
|
|
return 0; \
|
|
|
|
} \
|
|
|
|
}
|
|
|
|
|
2015-10-19 15:01:24 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#endif // __AP_HAL_MAIN_H__
|