|
|
|
@ -24,27 +24,11 @@
@@ -24,27 +24,11 @@
|
|
|
|
|
#define AP_COMPASS_MOT_COMP_THROTTLE 0x01 |
|
|
|
|
#define AP_COMPASS_MOT_COMP_CURRENT 0x02 |
|
|
|
|
|
|
|
|
|
// setup default mag orientation for each board type
|
|
|
|
|
// setup default mag orientation for some board types
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_ROLL_180 |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_PX4 |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX |
|
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#else |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#endif |
|
|
|
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#else |
|
|
|
|
# error "You must define a default compass orientation for this board" |
|
|
|
|
# define MAG_BOARD_ORIENTATION ROTATION_NONE |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|