AP_BoardConfig: make error function public and static

So it can be used by other parts of the code calling px4_start_driver().
This commit is contained in:
Lucas De Marchi 2017-03-21 18:44:16 -07:00 committed by Andrew Tridgell
parent fb24a03faf
commit da68612f4b

View File

@ -35,6 +35,7 @@ public:
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// public method to start a driver // public method to start a driver
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments); static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments);
static void px4_sensor_error(const char *reason);
// valid types for BRD_TYPE // valid types for BRD_TYPE
enum px4_board_type { enum px4_board_type {
@ -103,7 +104,6 @@ private:
void px4_setup_peripherals(void); void px4_setup_peripherals(void);
void px4_setup_px4io(void); void px4_setup_px4io(void);
void px4_tone_alarm(const char *tone_string); void px4_tone_alarm(const char *tone_string);
void px4_sensor_error(const char *reason);
bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80); bool spi_check_register(const char *devname, uint8_t regnum, uint8_t value, uint8_t read_flag = 0x80);
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4