2019-05-26 22:46:41 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
AP_Periph main firmware
|
|
|
|
|
|
|
|
To flash this firmware on Linux use:
|
|
|
|
|
|
|
|
st-flash write build/f103-periph/bin/AP_Periph.bin 0x8006000
|
|
|
|
|
|
|
|
*/
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2022-02-21 00:40:40 -04:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
2019-05-26 22:46:41 -03:00
|
|
|
#include "AP_Periph.h"
|
|
|
|
#include <stdio.h>
|
2020-09-12 16:00:22 -03:00
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
2019-05-26 22:46:41 -03:00
|
|
|
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
|
2019-10-25 22:46:22 -03:00
|
|
|
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
|
2022-02-01 16:39:43 -04:00
|
|
|
#include <AP_HAL_ChibiOS/I2CDevice.h>
|
2020-09-12 16:00:22 -03:00
|
|
|
#endif
|
2019-05-26 22:46:41 -03:00
|
|
|
|
2023-01-22 14:21:54 -04:00
|
|
|
#ifndef HAL_PERIPH_HWESC_SERIAL_PORT
|
|
|
|
#define HAL_PERIPH_HWESC_SERIAL_PORT 3
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
extern const AP_HAL::HAL &hal;
|
|
|
|
|
|
|
|
AP_Periph_FW periph;
|
|
|
|
|
|
|
|
void setup();
|
|
|
|
void loop();
|
|
|
|
|
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|
|
|
|
2020-09-12 16:00:22 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
void stm32_watchdog_init() {}
|
|
|
|
void stm32_watchdog_pat() {}
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
void setup(void)
|
|
|
|
{
|
|
|
|
periph.init();
|
|
|
|
}
|
|
|
|
|
|
|
|
void loop(void)
|
|
|
|
{
|
|
|
|
periph.update();
|
|
|
|
}
|
|
|
|
|
2019-09-10 01:07:24 -03:00
|
|
|
static uint32_t start_ms;
|
|
|
|
|
2021-05-19 23:34:15 -03:00
|
|
|
AP_Periph_FW::AP_Periph_FW()
|
|
|
|
#if HAL_LOGGING_ENABLED
|
|
|
|
: logger(g.log_bitmask)
|
|
|
|
#endif
|
2021-04-30 22:36:42 -03:00
|
|
|
{
|
|
|
|
if (_singleton != nullptr) {
|
|
|
|
AP_HAL::panic("AP_Periph_FW must be singleton");
|
|
|
|
}
|
|
|
|
_singleton = this;
|
|
|
|
}
|
2021-05-19 23:34:15 -03:00
|
|
|
|
|
|
|
#if HAL_LOGGING_ENABLED
|
|
|
|
const struct LogStructure AP_Periph_FW::log_structure[] = {
|
|
|
|
LOG_COMMON_STRUCTURES,
|
|
|
|
};
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
void AP_Periph_FW::init()
|
|
|
|
{
|
2020-09-12 16:00:22 -03:00
|
|
|
|
2019-10-25 22:46:22 -03:00
|
|
|
// always run with watchdog enabled. This should have already been
|
|
|
|
// setup by the bootloader, but if not then enable now
|
2021-06-19 13:19:07 -03:00
|
|
|
#ifndef DISABLE_WATCHDOG
|
2019-10-25 22:46:22 -03:00
|
|
|
stm32_watchdog_init();
|
2021-06-19 13:19:07 -03:00
|
|
|
#endif
|
2019-10-25 22:46:22 -03:00
|
|
|
|
|
|
|
stm32_watchdog_pat();
|
|
|
|
|
2021-08-18 08:42:18 -03:00
|
|
|
#if !HAL_GCS_ENABLED
|
2020-12-10 20:18:38 -04:00
|
|
|
hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD, 32, 32);
|
2021-07-11 03:38:42 -03:00
|
|
|
#endif
|
2020-12-10 20:18:38 -04:00
|
|
|
hal.serial(3)->begin(115200, 128, 256);
|
2019-05-26 22:46:41 -03:00
|
|
|
|
|
|
|
load_parameters();
|
2019-10-25 22:46:22 -03:00
|
|
|
|
|
|
|
stm32_watchdog_pat();
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
can_start();
|
|
|
|
|
2023-08-02 21:50:27 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_NETWORKING
|
2023-11-22 20:10:55 -04:00
|
|
|
networking_periph.init();
|
2023-07-06 14:46:05 -03:00
|
|
|
#endif
|
|
|
|
|
2021-08-18 08:42:18 -03:00
|
|
|
#if HAL_GCS_ENABLED
|
2021-07-11 03:38:42 -03:00
|
|
|
stm32_watchdog_pat();
|
|
|
|
gcs().init();
|
|
|
|
#endif
|
2019-05-26 22:46:41 -03:00
|
|
|
serial_manager.init();
|
|
|
|
|
2021-08-18 08:42:18 -03:00
|
|
|
#if HAL_GCS_ENABLED
|
2021-07-11 03:38:42 -03:00
|
|
|
gcs().setup_console();
|
2021-09-29 05:02:19 -03:00
|
|
|
gcs().setup_uarts();
|
2021-07-11 03:38:42 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "AP_Periph GCS Initialised!");
|
|
|
|
#endif
|
|
|
|
|
2019-10-25 22:46:22 -03:00
|
|
|
stm32_watchdog_pat();
|
|
|
|
|
2019-10-19 06:41:55 -03:00
|
|
|
#ifdef HAL_BOARD_AP_PERIPH_ZUBAXGNSS
|
|
|
|
// setup remapping register for ZubaxGNSS
|
|
|
|
uint32_t mapr = AFIO->MAPR;
|
|
|
|
mapr &= ~AFIO_MAPR_SWJ_CFG;
|
|
|
|
mapr |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;
|
|
|
|
AFIO->MAPR = mapr | AFIO_MAPR_CAN_REMAP_REMAP2 | AFIO_MAPR_SPI3_REMAP;
|
|
|
|
#endif
|
|
|
|
|
2021-05-19 23:34:15 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
|
|
|
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
|
|
|
#endif
|
|
|
|
|
2022-08-11 05:03:47 -03:00
|
|
|
check_firmware_print();
|
2019-10-20 23:35:01 -03:00
|
|
|
|
|
|
|
if (hal.util->was_watchdog_reset()) {
|
|
|
|
printf("Reboot after watchdog reset\n");
|
|
|
|
}
|
|
|
|
|
2022-06-01 01:46:16 -03:00
|
|
|
#if AP_STATS_ENABLED
|
|
|
|
node_stats.init();
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS
|
2020-12-26 19:35:15 -04:00
|
|
|
if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {
|
2020-12-22 19:29:59 -04:00
|
|
|
serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);
|
2021-05-19 23:34:15 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
|
|
|
#define MASK_LOG_GPS (1<<2)
|
|
|
|
gps.set_log_gps_bit(MASK_LOG_GPS);
|
|
|
|
#endif
|
2020-01-24 19:59:01 -04:00
|
|
|
gps.init(serial_manager);
|
|
|
|
}
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_MAG
|
2021-08-10 07:18:26 -03:00
|
|
|
compass.init();
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_BARO
|
|
|
|
baro.init();
|
|
|
|
#endif
|
2019-09-09 18:37:42 -03:00
|
|
|
|
2020-11-21 01:29:10 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_BATTERY
|
2023-08-22 20:00:26 -03:00
|
|
|
battery_lib.init();
|
2020-11-21 01:29:10 -04:00
|
|
|
#endif
|
|
|
|
|
2023-05-18 05:20:22 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RCIN
|
|
|
|
rcin_init();
|
|
|
|
#endif
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_RC_OUT)
|
2019-09-09 18:37:42 -03:00
|
|
|
hal.rcout->init();
|
2020-12-12 05:08:45 -04:00
|
|
|
#endif
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY
|
2022-01-25 05:57:39 -04:00
|
|
|
hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);
|
2019-09-09 18:37:42 -03:00
|
|
|
#endif
|
2019-10-02 06:04:44 -03:00
|
|
|
|
2020-12-12 05:08:45 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
|
|
|
rcout_init();
|
|
|
|
#endif
|
|
|
|
|
2019-10-02 06:04:44 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_ADSB
|
|
|
|
adsb_init();
|
|
|
|
#endif
|
|
|
|
|
2022-06-03 08:00:14 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_EFI
|
|
|
|
if (efi.enabled() && g.efi_port >= 0) {
|
|
|
|
auto *uart = hal.serial(g.efi_port);
|
|
|
|
if (uart != nullptr) {
|
|
|
|
uart->begin(g.efi_baudrate);
|
|
|
|
serial_manager.set_protocol_and_baud(g.efi_port, AP_SerialManager::SerialProtocol_EFI, g.efi_baudrate);
|
|
|
|
efi.init();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
2023-03-16 21:25:56 -03:00
|
|
|
|
|
|
|
#if AP_KDECAN_ENABLED
|
|
|
|
kdecan.init();
|
|
|
|
#endif
|
|
|
|
|
2019-10-03 08:02:56 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_AIRSPEED
|
2022-02-01 16:39:43 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
2022-12-30 15:40:03 -04:00
|
|
|
const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);
|
|
|
|
if (pins_enabled) {
|
|
|
|
ChibiOS::I2CBus::set_bus_to_floating(0);
|
2022-02-01 16:39:43 -04:00
|
|
|
#ifdef HAL_GPIO_PIN_LED_CAN_I2C
|
2022-12-30 15:40:03 -04:00
|
|
|
palWriteLine(HAL_GPIO_PIN_LED_CAN_I2C, 1);
|
2022-02-01 16:39:43 -04:00
|
|
|
#endif
|
2022-12-30 15:40:03 -04:00
|
|
|
} else {
|
2022-02-01 16:39:43 -04:00
|
|
|
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
|
2020-01-24 19:59:01 -04:00
|
|
|
airspeed.init();
|
|
|
|
}
|
2022-12-30 15:40:03 -04:00
|
|
|
#else
|
|
|
|
// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here
|
|
|
|
airspeed.init();
|
|
|
|
#endif
|
2022-02-01 16:39:43 -04:00
|
|
|
|
2019-10-03 08:02:56 -03:00
|
|
|
#endif
|
2019-10-19 01:36:14 -03:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
2023-03-05 18:02:07 -04:00
|
|
|
if (rangefinder.get_type(0) != RangeFinder::Type::NONE) {
|
|
|
|
if (g.rangefinder_port >= 0) {
|
|
|
|
// init uart for serial rangefinders
|
|
|
|
auto *uart = hal.serial(g.rangefinder_port);
|
|
|
|
if (uart != nullptr) {
|
|
|
|
uart->begin(g.rangefinder_baud);
|
|
|
|
serial_manager.set_protocol_and_baud(g.rangefinder_port, AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud);
|
|
|
|
}
|
2020-12-22 19:29:59 -04:00
|
|
|
}
|
2023-03-05 18:02:07 -04:00
|
|
|
rangefinder.init(ROTATION_NONE);
|
2020-01-24 19:59:01 -04:00
|
|
|
}
|
2019-10-19 01:36:14 -03:00
|
|
|
#endif
|
2019-12-19 02:21:25 -04:00
|
|
|
|
2023-08-26 06:53:59 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_PROXIMITY
|
2022-09-27 16:45:07 -03:00
|
|
|
if (proximity.get_type(0) != AP_Proximity::Type::None && g.proximity_port >= 0) {
|
|
|
|
auto *uart = hal.serial(g.proximity_port);
|
|
|
|
if (uart != nullptr) {
|
|
|
|
uart->begin(g.proximity_baud);
|
|
|
|
serial_manager.set_protocol_and_baud(g.proximity_port, AP_SerialManager::SerialProtocol_Lidar360, g.proximity_baud);
|
|
|
|
proximity.init();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2019-12-19 02:21:25 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT
|
|
|
|
pwm_hardpoint_init();
|
|
|
|
#endif
|
2020-02-14 01:18:20 -04:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_HWESC
|
2023-01-22 14:21:54 -04:00
|
|
|
hwesc_telem.init(hal.serial(HAL_PERIPH_HWESC_SERIAL_PORT));
|
2020-02-14 01:18:20 -04:00
|
|
|
#endif
|
2020-09-03 08:47:34 -03:00
|
|
|
|
2021-03-02 14:49:09 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_ESC_APD
|
|
|
|
for (uint8_t i = 0; i < ESC_NUMBERS; i++) {
|
|
|
|
const uint8_t port = g.esc_serial_port[i];
|
|
|
|
if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports
|
|
|
|
apd_esc_telem[i] = new ESC_APD_Telem (hal.serial(port), g.pole_count[i]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2020-09-03 08:47:34 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_MSP
|
2020-12-26 19:35:15 -04:00
|
|
|
if (g.msp_port >= 0) {
|
|
|
|
msp_init(hal.serial(g.msp_port));
|
|
|
|
}
|
2020-09-03 08:47:34 -03:00
|
|
|
#endif
|
2019-10-03 08:02:56 -03:00
|
|
|
|
2022-09-02 18:41:38 -03:00
|
|
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
|
|
|
temperature_sensor.init();
|
|
|
|
#endif
|
|
|
|
|
2023-01-31 19:16:14 -04:00
|
|
|
#if HAL_NMEA_OUTPUT_ENABLED
|
|
|
|
nmea.init();
|
|
|
|
#endif
|
|
|
|
|
2023-08-02 18:34:40 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RPM
|
|
|
|
rpm_sensor.init();
|
|
|
|
#endif
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
|
|
|
notify.init();
|
|
|
|
#endif
|
|
|
|
|
2021-11-15 01:08:36 -04:00
|
|
|
#if AP_SCRIPTING_ENABLED
|
2021-09-17 11:33:17 -03:00
|
|
|
scripting.init();
|
|
|
|
#endif
|
2023-08-21 22:41:18 -03:00
|
|
|
start_ms = AP_HAL::millis();
|
2019-05-26 22:46:41 -03:00
|
|
|
}
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
2019-09-10 01:07:24 -03:00
|
|
|
/*
|
|
|
|
rotating rainbow pattern on startup
|
|
|
|
*/
|
2020-12-29 01:06:44 -04:00
|
|
|
void AP_Periph_FW::update_rainbow()
|
2019-09-10 01:07:24 -03:00
|
|
|
{
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
|
|
|
if (notify.get_led_len() != 8) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
#endif
|
2019-09-10 01:07:24 -03:00
|
|
|
static bool rainbow_done;
|
|
|
|
if (rainbow_done) {
|
|
|
|
return;
|
|
|
|
}
|
2023-08-21 22:41:18 -03:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2020-12-29 01:06:44 -04:00
|
|
|
if (now - start_ms > 1500) {
|
2019-09-10 01:07:24 -03:00
|
|
|
rainbow_done = true;
|
2020-12-29 01:06:44 -04:00
|
|
|
#if defined (HAL_PERIPH_ENABLE_NOTIFY)
|
|
|
|
periph.notify.handle_rgb(0, 0, 0);
|
|
|
|
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
|
|
|
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, 0, 0, 0);
|
|
|
|
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
|
|
|
|
#endif
|
2019-09-10 01:07:24 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
static uint32_t last_update_ms;
|
|
|
|
const uint8_t step_ms = 30;
|
|
|
|
if (now - last_update_ms < step_ms) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
const struct {
|
|
|
|
uint8_t red;
|
|
|
|
uint8_t green;
|
|
|
|
uint8_t blue;
|
|
|
|
} rgb_rainbow[] = {
|
|
|
|
{ 255, 0, 0 },
|
|
|
|
{ 255, 127, 0 },
|
|
|
|
{ 255, 255, 0 },
|
|
|
|
{ 0, 255, 0 },
|
|
|
|
{ 0, 0, 255 },
|
|
|
|
{ 75, 0, 130 },
|
|
|
|
{ 143, 0, 255 },
|
|
|
|
{ 0, 0, 0 },
|
|
|
|
};
|
|
|
|
last_update_ms = now;
|
|
|
|
static uint8_t step;
|
|
|
|
const uint8_t nsteps = ARRAY_SIZE(rgb_rainbow);
|
|
|
|
float brightness = 0.3;
|
|
|
|
for (uint8_t n=0; n<8; n++) {
|
|
|
|
uint8_t i = (step + n) % nsteps;
|
2020-12-29 01:06:44 -04:00
|
|
|
#if defined (HAL_PERIPH_ENABLE_NOTIFY)
|
|
|
|
periph.notify.handle_rgb(
|
|
|
|
#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
|
|
|
hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, n,
|
|
|
|
#endif
|
|
|
|
rgb_rainbow[i].red*brightness,
|
|
|
|
rgb_rainbow[i].green*brightness,
|
|
|
|
rgb_rainbow[i].blue*brightness);
|
2019-09-10 01:07:24 -03:00
|
|
|
}
|
|
|
|
step++;
|
2020-12-29 01:06:44 -04:00
|
|
|
|
|
|
|
#if defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)
|
|
|
|
hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);
|
2019-09-10 01:07:24 -03:00
|
|
|
#endif
|
2020-12-29 01:06:44 -04:00
|
|
|
}
|
|
|
|
#endif // HAL_PERIPH_ENABLE_NOTIFY
|
2019-09-10 01:07:24 -03:00
|
|
|
|
|
|
|
|
2020-11-29 19:14:56 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
|
|
|
|
void AP_Periph_FW::show_stack_free()
|
|
|
|
{
|
|
|
|
const uint32_t isr_stack_size = uint32_t((const uint8_t *)&__main_stack_end__ - (const uint8_t *)&__main_stack_base__);
|
2021-08-03 23:55:26 -03:00
|
|
|
can_printf("ISR %u/%u", unsigned(stack_free(&__main_stack_base__)), unsigned(isr_stack_size));
|
2020-11-29 19:14:56 -04:00
|
|
|
|
|
|
|
for (thread_t *tp = chRegFirstThread(); tp; tp = chRegNextThread(tp)) {
|
|
|
|
uint32_t total_stack;
|
|
|
|
if (tp->wabase == (void*)&__main_thread_stack_base__) {
|
|
|
|
// main thread has its stack separated from the thread context
|
|
|
|
total_stack = uint32_t((const uint8_t *)&__main_thread_stack_end__ - (const uint8_t *)&__main_thread_stack_base__);
|
|
|
|
} else {
|
|
|
|
// all other threads have their thread context pointer
|
|
|
|
// above the stack top
|
|
|
|
total_stack = uint32_t(tp) - uint32_t(tp->wabase);
|
|
|
|
}
|
2021-08-03 23:55:26 -03:00
|
|
|
can_printf("%s STACK=%u/%u\n", tp->name, unsigned(stack_free(tp->wabase)), unsigned(total_stack));
|
2020-11-29 19:14:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
|
2019-09-10 01:07:24 -03:00
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
void AP_Periph_FW::update()
|
|
|
|
{
|
2022-06-01 01:46:16 -03:00
|
|
|
#if AP_STATS_ENABLED
|
|
|
|
node_stats.update();
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
static uint32_t last_led_ms;
|
2023-08-21 22:41:18 -03:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2019-05-26 22:46:41 -03:00
|
|
|
if (now - last_led_ms > 1000) {
|
|
|
|
last_led_ms = now;
|
2020-09-12 16:00:22 -03:00
|
|
|
#ifdef HAL_GPIO_PIN_LED
|
2021-07-12 12:59:31 -03:00
|
|
|
if (!no_iface_finished_dna) {
|
|
|
|
palToggleLine(HAL_GPIO_PIN_LED);
|
|
|
|
}
|
2020-09-12 16:00:22 -03:00
|
|
|
#endif
|
2019-05-26 22:46:41 -03:00
|
|
|
#if 0
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_GPS
|
2020-12-10 20:18:38 -04:00
|
|
|
hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_MAG
|
|
|
|
const Vector3f &field = compass.get_field();
|
2020-12-10 20:18:38 -04:00
|
|
|
hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_BARO
|
2020-12-10 20:18:38 -04:00
|
|
|
hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());
|
2019-10-27 21:31:29 -03:00
|
|
|
#endif
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_RANGEFINDER
|
2020-12-10 20:18:38 -04:00
|
|
|
hal.serial(0)->printf("RNG %u %ucm\n", rangefinder.num_sensors(), rangefinder.distance_cm_orient(ROTATION_NONE));
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
|
|
|
hal.scheduler->delay(1);
|
2019-09-10 03:20:41 -03:00
|
|
|
#endif
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY
|
|
|
|
hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);
|
2019-05-26 22:46:41 -03:00
|
|
|
#endif
|
2020-12-15 21:27:28 -04:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
|
|
|
|
check_for_serial_reboot_cmd(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT);
|
|
|
|
#endif
|
2020-12-12 05:08:45 -04:00
|
|
|
|
|
|
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
2020-12-21 20:27:53 -04:00
|
|
|
rcout_init_1Hz();
|
2020-12-12 05:08:45 -04:00
|
|
|
#endif
|
2021-07-11 03:38:42 -03:00
|
|
|
|
2023-09-02 02:21:36 -03:00
|
|
|
GCS_SEND_MESSAGE(MSG_HEARTBEAT);
|
|
|
|
GCS_SEND_MESSAGE(MSG_SYS_STATUS);
|
2019-05-26 22:46:41 -03:00
|
|
|
}
|
2020-11-21 01:29:10 -04:00
|
|
|
|
2020-11-29 19:14:56 -04:00
|
|
|
static uint32_t last_error_ms;
|
|
|
|
const auto &ierr = AP::internalerror();
|
|
|
|
if (now - last_error_ms > 5000 && ierr.errors()) {
|
|
|
|
// display internal errors as DEBUG every 5s
|
|
|
|
last_error_ms = now;
|
2021-08-03 23:55:26 -03:00
|
|
|
can_printf("IERR 0x%x %u", unsigned(ierr.errors()), unsigned(ierr.last_error_line()));
|
2020-11-29 19:14:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE
|
|
|
|
static uint32_t last_debug_ms;
|
2023-07-07 04:36:52 -03:00
|
|
|
if (debug_option_is_set(DebugOptions::SHOW_STACK) && now - last_debug_ms > 5000) {
|
2020-11-29 19:14:56 -04:00
|
|
|
last_debug_ms = now;
|
|
|
|
show_stack_free();
|
|
|
|
}
|
|
|
|
#endif
|
2022-03-08 04:51:27 -04:00
|
|
|
|
2023-07-07 04:36:52 -03:00
|
|
|
if (debug_option_is_set(DebugOptions::AUTOREBOOT) && AP_HAL::millis() > 15000) {
|
2022-03-08 04:51:27 -04:00
|
|
|
// attempt reboot with HOLD after 15s
|
|
|
|
periph.prepare_reboot();
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
set_fast_reboot((rtc_boot_magic)(RTC_BOOT_HOLD));
|
|
|
|
NVIC_SystemReset();
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2020-11-21 01:29:10 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_BATTERY
|
|
|
|
if (now - battery.last_read_ms >= 100) {
|
|
|
|
// update battery at 10Hz
|
|
|
|
battery.last_read_ms = now;
|
2023-08-22 20:00:26 -03:00
|
|
|
battery_lib.read();
|
2020-11-21 01:29:10 -04:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2023-05-18 05:20:22 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RCIN
|
|
|
|
rcin_update();
|
|
|
|
#endif
|
|
|
|
|
2023-08-25 06:50:15 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE
|
|
|
|
batt_balance_update();
|
|
|
|
#endif
|
|
|
|
|
2021-07-11 03:38:42 -03:00
|
|
|
static uint32_t fiftyhz_last_update_ms;
|
|
|
|
if (now - fiftyhz_last_update_ms >= 20) {
|
|
|
|
// update at 50Hz
|
|
|
|
fiftyhz_last_update_ms = now;
|
2020-12-29 01:06:44 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_NOTIFY
|
|
|
|
notify.update();
|
|
|
|
#endif
|
2021-08-18 08:42:18 -03:00
|
|
|
#if HAL_GCS_ENABLED
|
2021-07-11 03:38:42 -03:00
|
|
|
gcs().update_receive();
|
|
|
|
gcs().update_send();
|
|
|
|
#endif
|
|
|
|
}
|
2020-12-29 01:06:44 -04:00
|
|
|
|
2023-01-31 19:16:14 -04:00
|
|
|
#if HAL_NMEA_OUTPUT_ENABLED
|
|
|
|
nmea.update();
|
|
|
|
#endif
|
|
|
|
|
2022-09-02 18:41:38 -03:00
|
|
|
#if AP_TEMPERATURE_SENSOR_ENABLED
|
|
|
|
temperature_sensor.update();
|
|
|
|
#endif
|
|
|
|
|
2023-08-02 18:34:40 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RPM
|
|
|
|
if (now - rpm_last_update_ms >= 100) {
|
|
|
|
rpm_last_update_ms = now;
|
|
|
|
rpm_sensor.update();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2021-05-19 23:34:15 -03:00
|
|
|
#if HAL_LOGGING_ENABLED
|
|
|
|
logger.periodic_tasks();
|
|
|
|
#endif
|
|
|
|
|
2019-05-26 22:46:41 -03:00
|
|
|
can_update();
|
2021-07-23 15:48:56 -03:00
|
|
|
|
2023-08-02 21:50:27 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_NETWORKING
|
2023-11-22 20:10:55 -04:00
|
|
|
networking_periph.update();
|
2023-07-06 14:46:05 -03:00
|
|
|
#endif
|
|
|
|
|
2020-12-29 01:06:44 -04:00
|
|
|
#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)
|
2019-09-10 01:07:24 -03:00
|
|
|
update_rainbow();
|
|
|
|
#endif
|
2019-10-02 06:04:44 -03:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_ADSB
|
|
|
|
adsb_update();
|
|
|
|
#endif
|
2019-05-26 22:46:41 -03:00
|
|
|
}
|
|
|
|
|
2020-12-21 20:27:53 -04:00
|
|
|
#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
|
2020-12-15 21:27:28 -04:00
|
|
|
// check for uploader.py reboot command
|
|
|
|
void AP_Periph_FW::check_for_serial_reboot_cmd(const int8_t serial_index)
|
|
|
|
{
|
|
|
|
// These are the string definitions in uploader.py
|
|
|
|
// NSH_INIT = bytearray(b'\x0d\x0d\x0d')
|
|
|
|
// NSH_REBOOT_BL = b"reboot -b\n"
|
|
|
|
// NSH_REBOOT = b"reboot\n"
|
|
|
|
|
|
|
|
// This is the command sequence that is sent from uploader.py
|
|
|
|
// self.__send(uploader.NSH_INIT)
|
|
|
|
// self.__send(uploader.NSH_REBOOT_BL)
|
|
|
|
// self.__send(uploader.NSH_INIT)
|
|
|
|
// self.__send(uploader.NSH_REBOOT)
|
|
|
|
|
|
|
|
for (uint8_t i=0; i<hal.num_serial; i++) {
|
|
|
|
if (serial_index >= 0 && serial_index != i) {
|
|
|
|
// a specific serial port was selected but this is not it
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
auto *uart = hal.serial(i);
|
|
|
|
if (uart == nullptr || !uart->is_initialized()) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t available = MIN(uart->available(), 1000U);
|
|
|
|
while (available-- > 0) {
|
|
|
|
const char reboot_string[] = "\r\r\rreboot -b\n\r\r\rreboot\n";
|
|
|
|
const char reboot_string_len = sizeof(reboot_string)-1; // -1 is to remove the null termination
|
|
|
|
static uint16_t index[hal.num_serial];
|
|
|
|
|
2023-02-21 05:35:58 -04:00
|
|
|
uint8_t data;
|
|
|
|
if (!uart->read(data)) {
|
2020-12-15 21:27:28 -04:00
|
|
|
// read error
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (index[i] >= reboot_string_len || (uint8_t)data != reboot_string[index[i]]) {
|
|
|
|
// don't have a perfect match, start over
|
|
|
|
index[i] = 0;
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
index[i]++;
|
|
|
|
if (index[i] == reboot_string_len) {
|
2020-12-21 20:27:53 -04:00
|
|
|
// received reboot msg. Trigger a reboot and stay in the bootloader
|
|
|
|
prepare_reboot();
|
|
|
|
hal.scheduler->reboot(true);
|
2020-12-15 21:27:28 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
2020-12-21 20:27:53 -04:00
|
|
|
#endif // HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT
|
2020-12-15 21:27:28 -04:00
|
|
|
|
2020-12-21 20:27:53 -04:00
|
|
|
// prepare for a safe reboot where PWMs and params are gracefully disabled
|
|
|
|
// This is copied from AP_Vehicle::reboot(bool hold_in_bootloader) minus the actual reboot
|
|
|
|
void AP_Periph_FW::prepare_reboot()
|
2020-12-15 21:27:28 -04:00
|
|
|
{
|
2020-12-21 20:27:53 -04:00
|
|
|
#ifdef HAL_PERIPH_ENABLE_RC_OUT
|
2020-12-15 21:27:28 -04:00
|
|
|
// force safety on
|
|
|
|
hal.rcout->force_safety_on();
|
2020-12-21 20:27:53 -04:00
|
|
|
#endif
|
2020-12-15 21:27:28 -04:00
|
|
|
|
|
|
|
// flush pending parameter writes
|
|
|
|
AP_Param::flush();
|
|
|
|
|
|
|
|
// do not process incoming mavlink messages while we delay:
|
|
|
|
hal.scheduler->register_delay_callback(nullptr, 5);
|
|
|
|
|
|
|
|
// delay to give the ACK a chance to get out, the LEDs to flash,
|
2020-12-21 20:27:53 -04:00
|
|
|
// the IO board safety to be forced on, the parameters to flush,
|
|
|
|
hal.scheduler->delay(40);
|
2020-12-15 21:27:28 -04:00
|
|
|
}
|
2020-12-21 20:27:53 -04:00
|
|
|
|
2021-04-30 22:36:42 -03:00
|
|
|
AP_Periph_FW *AP_Periph_FW::_singleton;
|
|
|
|
|
|
|
|
AP_Periph_FW& AP::periph()
|
|
|
|
{
|
|
|
|
return *AP_Periph_FW::get_singleton();
|
|
|
|
}
|
|
|
|
|
2023-06-05 18:43:50 -03:00
|
|
|
AP_HAL_MAIN();
|