123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372 |
- #include <AP_HAL/AP_HAL.h>
- #include <AP_Common/AP_Common.h>
- #include <GCS_MAVLink/GCS.h>
- #include "AP_BoardConfig.h"
- #include <stdio.h>
- #include <AP_RTC/AP_RTC.h>
- #if HAL_WITH_UAVCAN
- #include <AP_UAVCAN/AP_UAVCAN.h>
- #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
- #include <AP_HAL_Linux/CAN.h>
- #endif
- #endif
- #ifndef BOARD_TYPE_DEFAULT
- #define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
- #endif
- #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
- # define BOARD_SAFETY_ENABLE_DEFAULT 1
- #ifndef BOARD_PWM_COUNT_DEFAULT
- # define BOARD_PWM_COUNT_DEFAULT 6
- #endif
- #ifndef BOARD_SER1_RTSCTS_DEFAULT
- # define BOARD_SER1_RTSCTS_DEFAULT 2
- #endif
- #ifndef BOARD_TYPE_DEFAULT
- # define BOARD_TYPE_DEFAULT PX4_BOARD_AUTO
- #endif
- #endif
- #ifndef HAL_IMU_TEMP_DEFAULT
- #define HAL_IMU_TEMP_DEFAULT -1
- #endif
- #ifndef BOARD_SAFETY_OPTION_DEFAULT
- # define BOARD_SAFETY_OPTION_DEFAULT (BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF|BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)
- #endif
- #ifndef BOARD_SAFETY_ENABLE
- # define BOARD_SAFETY_ENABLE 1
- #endif
- #ifndef BOARD_PWM_COUNT_DEFAULT
- #define BOARD_PWM_COUNT_DEFAULT 8
- #endif
- #ifndef BOARD_CONFIG_BOARD_VOLTAGE_MIN
- #define BOARD_CONFIG_BOARD_VOLTAGE_MIN 4.3f
- #endif
- #ifndef HAL_BRD_OPTIONS_DEFAULT
- #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
- #define HAL_BRD_OPTIONS_DEFAULT BOARD_OPTION_WATCHDOG
- #else
- #define HAL_BRD_OPTIONS_DEFAULT 0
- #endif
- #endif
- #ifndef HAL_DEFAULT_BOOT_DELAY
- #define HAL_DEFAULT_BOOT_DELAY 0
- #endif
- extern const AP_HAL::HAL& hal;
- AP_BoardConfig *AP_BoardConfig::_singleton;
- const AP_Param::GroupInfo AP_BoardConfig::var_info[] = {
-
-
-
-
-
-
- AP_GROUPINFO("PWM_COUNT", 0, AP_BoardConfig, pwm_count, BOARD_PWM_COUNT_DEFAULT),
- #if AP_FEATURE_RTSCTS
-
-
-
-
-
-
- AP_GROUPINFO("SER1_RTSCTS", 1, AP_BoardConfig, state.ser1_rtscts, BOARD_SER1_RTSCTS_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("SER2_RTSCTS", 2, AP_BoardConfig, state.ser2_rtscts, 2),
- #endif
- #if HAL_HAVE_SAFETY_SWITCH
-
-
-
-
-
-
- AP_GROUPINFO("SAFETYENABLE", 3, AP_BoardConfig, state.safety_enable, BOARD_SAFETY_ENABLE_DEFAULT),
- #endif
- #if AP_FEATURE_SBUS_OUT
-
-
-
-
-
-
- AP_GROUPINFO("SBUS_OUT", 4, AP_BoardConfig, state.sbus_out_rate, 0),
- #endif
-
-
-
-
-
- AP_GROUPINFO("SERIAL_NUM", 5, AP_BoardConfig, vehicleSerialNumber, 0),
- #if HAL_HAVE_SAFETY_SWITCH
-
-
-
-
-
-
-
- AP_GROUPINFO("SAFETY_MASK", 7, AP_BoardConfig, state.ignore_safety_channels, 0),
- #endif
- #if HAL_HAVE_IMU_HEATER
-
-
-
-
-
-
- AP_GROUPINFO("IMU_TARGTEMP", 8, AP_BoardConfig, _imu_target_temperature, HAL_IMU_TEMP_DEFAULT),
- #endif
- #if AP_FEATURE_BOARD_DETECT
-
-
-
-
-
-
- AP_GROUPINFO("TYPE", 9, AP_BoardConfig, state.board_type, BOARD_TYPE_DEFAULT),
- #endif
- #if AP_FEATURE_BOARD_DETECT
- #if HAL_PX4_HAVE_PX4IO || HAL_WITH_IO_MCU
-
-
-
-
-
-
- AP_GROUPINFO("IO_ENABLE", 10, AP_BoardConfig, state.io_enable, 1),
- #endif
- #endif
- #if HAL_RCINPUT_WITH_AP_RADIO
-
-
- AP_SUBGROUPINFO(_radio, "RADIO", 11, AP_BoardConfig, AP_Radio),
- #endif
-
-
-
-
-
- AP_GROUPINFO("SAFETYOPTION", 13, AP_BoardConfig, state.safety_option, BOARD_SAFETY_OPTION_DEFAULT),
-
-
- AP_SUBGROUPINFO(rtc, "RTC", 14, AP_BoardConfig, AP_RTC),
- #if HAL_HAVE_BOARD_VOLTAGE
-
-
-
-
-
-
-
- AP_GROUPINFO("VBUS_MIN", 15, AP_BoardConfig, _vbus_min, BOARD_CONFIG_BOARD_VOLTAGE_MIN),
- #endif
- #if HAL_HAVE_SERVO_VOLTAGE
-
-
-
-
-
-
-
- AP_GROUPINFO("VSERVO_MIN", 16, AP_BoardConfig, _vservo_min, 0),
- #endif
- #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
-
-
-
-
-
-
- AP_GROUPINFO("SD_SLOWDOWN", 17, AP_BoardConfig, _sdcard_slowdown, 0),
- #endif
- #ifdef HAL_GPIO_PWM_VOLT_PIN
-
-
-
-
-
- AP_GROUPINFO("PWM_VOLT_SEL", 18, AP_BoardConfig, _pwm_volt_sel, 0),
- #endif
-
-
-
-
-
- AP_GROUPINFO("OPTIONS", 19, AP_BoardConfig, _options, HAL_BRD_OPTIONS_DEFAULT),
-
-
-
-
-
-
- AP_GROUPINFO("BOOT_DELAY", 20, AP_BoardConfig, _boot_delay_ms, HAL_DEFAULT_BOOT_DELAY),
-
- AP_GROUPEND
- };
- void AP_BoardConfig::init()
- {
- board_setup();
- #if HAL_HAVE_IMU_HEATER
-
-
-
- hal.util->set_imu_target_temp((int8_t *)&_imu_target_temperature);
- #endif
- AP::rtc().set_utc_usec(hal.util->get_hw_rtc(), AP_RTC::SOURCE_HW);
- if (_boot_delay_ms > 0) {
- uint16_t delay_ms = uint16_t(_boot_delay_ms.get());
- if (hal.util->was_watchdog_armed() && delay_ms > 200) {
-
-
- delay_ms = 200;
- }
- hal.scheduler->delay(delay_ms);
- }
-
- #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && defined(USE_POSIX)
- uint8_t slowdown = constrain_int16(_sdcard_slowdown.get(), 0, 32);
- const uint8_t max_slowdown = 8;
- do {
- if (hal.util->fs_init()) {
- break;
- }
- slowdown++;
- hal.scheduler->delay(5);
- } while (slowdown < max_slowdown);
- if (slowdown < max_slowdown) {
- _sdcard_slowdown.set(slowdown);
- } else {
- printf("SDCard failed to start\n");
- }
- #endif
- }
- void AP_BoardConfig::set_default_safety_ignore_mask(uint16_t mask)
- {
- #if HAL_HAVE_SAFETY_SWITCH
- state.ignore_safety_channels.set_default(mask);
- #endif
- }
- void AP_BoardConfig::init_safety()
- {
- board_init_safety();
- }
- bool AP_BoardConfig::_in_sensor_config_error;
- void AP_BoardConfig::sensor_config_error(const char *reason)
- {
- _in_sensor_config_error = true;
-
- uint32_t last_print_ms = 0;
- while (true) {
- uint32_t now = AP_HAL::millis();
- if (now - last_print_ms >= 3000) {
- last_print_ms = now;
- printf("Sensor failure: %s\n", reason);
- #if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH)
- gcs().send_text(MAV_SEVERITY_ERROR, "Check BRD_TYPE: %s", reason);
- #endif
- }
- #if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH)
- gcs().update_receive();
- gcs().update_send();
- #endif
- hal.scheduler->delay(5);
- }
- }
- bool AP_BoardConfig::safety_button_handle_pressed(uint8_t press_count)
- {
- if (press_count != 10) {
- return false;
- }
-
- uint16_t safety_options = get_safety_button_options();
- if (!(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED) &&
- hal.util->get_soft_armed()) {
- return false;
- }
- AP_HAL::Util::safety_state safety_state = hal.util->safety_switch_state();
- if (safety_state == AP_HAL::Util::SAFETY_DISARMED &&
- !(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_OFF)) {
- return false;
- }
- if (safety_state == AP_HAL::Util::SAFETY_ARMED &&
- !(safety_options & BOARD_SAFETY_OPTION_BUTTON_ACTIVE_SAFETY_ON)) {
- return false;
- }
- return true;
- }
|