Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/AP_Periph/AP_Periph.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15AP_Periph main firmware1617To flash this firmware on Linux use:1819st-flash write build/f103-periph/bin/AP_Periph.bin 0x80060002021*/22#include <AP_HAL/AP_HAL.h>23#include <AP_HAL/AP_HAL_Boards.h>24#include "AP_Periph.h"25#include <stdio.h>2627#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS28#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>29#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>30#include <AP_HAL_ChibiOS/I2CDevice.h>31#endif3233#ifndef HAL_PERIPH_HWESC_SERIAL_PORT34#define HAL_PERIPH_HWESC_SERIAL_PORT 335#endif3637// not only will the code not compile without features this enables,38// but it forms part of a series of measures to give a robust recovery39// mechanism on AP_Periph if a bad flash occurs.40#ifndef AP_CHECK_FIRMWARE_ENABLED41#error AP_CHECK_FIRMWARE_ENABLED must be enabled42#endif4344extern const AP_HAL::HAL &hal;4546AP_Periph_FW periph;4748void setup();49void loop();5051const AP_HAL::HAL& hal = AP_HAL::get_HAL();5253#if CONFIG_HAL_BOARD == HAL_BOARD_SITL54void stm32_watchdog_init() {}55void stm32_watchdog_pat() {}56#endif5758void setup(void)59{60periph.init();61}6263void loop(void)64{65periph.update();66}6768static uint32_t start_ms;6970AP_Periph_FW::AP_Periph_FW()71{72if (_singleton != nullptr) {73AP_HAL::panic("AP_Periph_FW must be singleton");74}75_singleton = this;76}7778#if HAL_LOGGING_ENABLED79const struct LogStructure AP_Periph_FW::log_structure[] = {80LOG_COMMON_STRUCTURES,81};82#endif8384void AP_Periph_FW::init()85{8687// always run with watchdog enabled. This should have already been88// setup by the bootloader, but if not then enable now89#ifndef DISABLE_WATCHDOG90stm32_watchdog_init();91#endif9293stm32_watchdog_pat();9495#if !HAL_GCS_ENABLED96hal.serial(0)->begin(AP_SERIALMANAGER_CONSOLE_BAUD, 32, 32);97#endif98hal.serial(3)->begin(115200, 128, 256);99100load_parameters();101102stm32_watchdog_pat();103104can_start();105106#if HAL_GCS_ENABLED107stm32_watchdog_pat();108gcs().init();109#endif110serial_manager.init();111112#ifdef HAL_PERIPH_ENABLE_NETWORKING113networking_periph.init();114#endif115116#if HAL_GCS_ENABLED117gcs().setup_console();118gcs().setup_uarts();119gcs().send_text(MAV_SEVERITY_INFO, "AP_Periph GCS Initialised!");120#endif121122stm32_watchdog_pat();123124#ifdef HAL_BOARD_AP_PERIPH_ZUBAXGNSS125// setup remapping register for ZubaxGNSS126uint32_t mapr = AFIO->MAPR;127mapr &= ~AFIO_MAPR_SWJ_CFG;128mapr |= AFIO_MAPR_SWJ_CFG_JTAGDISABLE;129AFIO->MAPR = mapr | AFIO_MAPR_CAN_REMAP_REMAP2 | AFIO_MAPR_SPI3_REMAP;130#endif131132#if HAL_LOGGING_ENABLED133logger.init(g.log_bitmask, log_structure, ARRAY_SIZE(log_structure));134#endif135136check_firmware_print();137138if (hal.util->was_watchdog_reset()) {139printf("Reboot after watchdog reset\n");140}141142#if AP_STATS_ENABLED143node_stats.init();144#endif145146#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS147serial_options.init();148#endif149150#ifdef HAL_PERIPH_ENABLE_GPS151gps.set_default_type_for_gps1(HAL_GPS1_TYPE_DEFAULT);152if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) {153serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD);154#if HAL_LOGGING_ENABLED155#define MASK_LOG_GPS (1<<2)156gps.set_log_gps_bit(MASK_LOG_GPS);157#endif158gps.init();159}160#endif161162#ifdef HAL_PERIPH_ENABLE_MAG163compass.init();164#endif165166#ifdef HAL_PERIPH_ENABLE_BARO167baro.init();168#endif169170#ifdef HAL_PERIPH_ENABLE_IMU171if (g.imu_sample_rate) {172imu.init(g.imu_sample_rate);173if (imu.get_accel_count() > 0 || imu.get_gyro_count() > 0) {174hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Periph_FW::can_imu_update, void), "IMU_UPDATE", 16384, AP_HAL::Scheduler::PRIORITY_CAN, 0);175}176}177#endif178179#ifdef HAL_PERIPH_ENABLE_BATTERY180battery_lib.init();181#endif182183#ifdef HAL_PERIPH_ENABLE_RCIN184rcin_init();185#endif186187#if defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) || defined(HAL_PERIPH_ENABLE_RC_OUT)188hal.rcout->init();189#endif190191#ifdef HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY192hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);193#endif194195#ifdef HAL_PERIPH_ENABLE_RC_OUT196rcout_init();197#endif198199#ifdef HAL_PERIPH_ENABLE_ADSB200adsb_init();201#endif202203#ifdef HAL_PERIPH_ENABLE_EFI204if (efi.enabled() && g.efi_port >= 0) {205auto *uart = hal.serial(g.efi_port);206if (uart != nullptr) {207uart->begin(g.efi_baudrate);208serial_manager.set_protocol_and_baud(g.efi_port, AP_SerialManager::SerialProtocol_EFI, g.efi_baudrate);209efi.init();210}211}212#endif213214#if AP_KDECAN_ENABLED215kdecan.init();216#endif217218#ifdef HAL_PERIPH_ENABLE_AIRSPEED219#if (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) && (HAL_USE_I2C == TRUE)220const bool pins_enabled = ChibiOS::I2CBus::check_select_pins(0x01);221if (pins_enabled) {222ChibiOS::I2CBus::set_bus_to_floating(0);223#ifdef HAL_GPIO_PIN_LED_CAN_I2C224palWriteLine(HAL_GPIO_PIN_LED_CAN_I2C, 1);225#endif226} else {227// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here228airspeed.init();229}230#else231// Note: logging of ARSPD is not enabled currently. To enable, call airspeed.set_log_bit(); here232airspeed.init();233#endif234235#endif236237#ifdef HAL_PERIPH_ENABLE_RANGEFINDER238bool have_rangefinder = false;239for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {240if ((rangefinder.get_type(i) != RangeFinder::Type::NONE) && (g.rangefinder_port[i] >= 0)) {241// init uart for serial rangefinders242auto *uart = hal.serial(g.rangefinder_port[i]);243if (uart != nullptr) {244uart->begin(g.rangefinder_baud[i]);245serial_manager.set_protocol_and_baud(g.rangefinder_port[i], AP_SerialManager::SerialProtocol_Rangefinder, g.rangefinder_baud[i]);246have_rangefinder = true;247}248}249}250if (have_rangefinder) {251// Can only call rangefinder init once, subsequent inits are blocked252rangefinder.init(ROTATION_NONE);253}254#endif255256#ifdef HAL_PERIPH_ENABLE_PROXIMITY257if (proximity.get_type(0) != AP_Proximity::Type::None && g.proximity_port >= 0) {258auto *uart = hal.serial(g.proximity_port);259if (uart != nullptr) {260uart->begin(g.proximity_baud);261serial_manager.set_protocol_and_baud(g.proximity_port, AP_SerialManager::SerialProtocol_Lidar360, g.proximity_baud);262proximity.init();263}264}265#endif266267#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT268pwm_hardpoint_init();269#endif270271#ifdef HAL_PERIPH_ENABLE_HWESC272hwesc_telem.init(hal.serial(HAL_PERIPH_HWESC_SERIAL_PORT));273#endif274275#ifdef HAL_PERIPH_ENABLE_ESC_APD276for (uint8_t i = 0; i < ESC_NUMBERS; i++) {277const uint8_t port = g.esc_serial_port[i];278if (port < SERIALMANAGER_NUM_PORTS) { // skip bad ports279apd_esc_telem[i] = NEW_NOTHROW ESC_APD_Telem (hal.serial(port), g.pole_count[i]);280}281}282#endif283284#ifdef HAL_PERIPH_ENABLE_MSP285if (g.msp_port >= 0) {286msp_init(hal.serial(g.msp_port));287}288#endif289290#if AP_TEMPERATURE_SENSOR_ENABLED291temperature_sensor.init();292#endif293294#if HAL_NMEA_OUTPUT_ENABLED295nmea.init();296#endif297298#ifdef HAL_PERIPH_ENABLE_RPM299rpm_sensor.init();300#endif301302#ifdef HAL_PERIPH_ENABLE_NOTIFY303notify.init();304#endif305306#ifdef HAL_PERIPH_ENABLE_RELAY307relay.init();308#endif309310#if AP_SCRIPTING_ENABLED311scripting.init();312#endif313start_ms = AP_HAL::millis();314}315316#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)317/*318rotating rainbow pattern on startup319*/320void AP_Periph_FW::update_rainbow()321{322#ifdef HAL_PERIPH_ENABLE_NOTIFY323if (notify.get_led_len() != 8) {324return;325}326#endif327static bool rainbow_done;328if (rainbow_done) {329return;330}331uint32_t now = AP_HAL::millis();332if (now - start_ms > 1500) {333rainbow_done = true;334#if defined (HAL_PERIPH_ENABLE_NOTIFY)335periph.notify.handle_rgb(0, 0, 0);336#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)337hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, -1, 0, 0, 0);338hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);339#endif340return;341}342static uint32_t last_update_ms;343const uint8_t step_ms = 30;344if (now - last_update_ms < step_ms) {345return;346}347const struct {348uint8_t red;349uint8_t green;350uint8_t blue;351} rgb_rainbow[] = {352{ 255, 0, 0 },353{ 255, 127, 0 },354{ 255, 255, 0 },355{ 0, 255, 0 },356{ 0, 0, 255 },357{ 75, 0, 130 },358{ 143, 0, 255 },359{ 0, 0, 0 },360};361last_update_ms = now;362static uint8_t step;363const uint8_t nsteps = ARRAY_SIZE(rgb_rainbow);364float brightness = 0.3;365for (uint8_t n=0; n<8; n++) {366uint8_t i = (step + n) % nsteps;367#if defined (HAL_PERIPH_ENABLE_NOTIFY)368periph.notify.handle_rgb(369#elif defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)370hal.rcout->set_serial_led_rgb_data(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, n,371#endif372rgb_rainbow[i].red*brightness,373rgb_rainbow[i].green*brightness,374rgb_rainbow[i].blue*brightness);375}376step++;377378#if defined(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY)379hal.rcout->serial_led_send(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY);380#endif381}382#endif // HAL_PERIPH_ENABLE_NOTIFY383384385#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE386void AP_Periph_FW::show_stack_free()387{388const uint32_t isr_stack_size = uint32_t((const uint8_t *)&__main_stack_end__ - (const uint8_t *)&__main_stack_base__);389can_printf("ISR %u/%u", unsigned(stack_free(&__main_stack_base__)), unsigned(isr_stack_size));390391for (thread_t *tp = chRegFirstThread(); tp; tp = chRegNextThread(tp)) {392uint32_t total_stack;393if (tp->wabase == (void*)&__main_thread_stack_base__) {394// main thread has its stack separated from the thread context395total_stack = uint32_t((const uint8_t *)&__main_thread_stack_end__ - (const uint8_t *)&__main_thread_stack_base__);396} else {397// all other threads have their thread context pointer398// above the stack top399total_stack = uint32_t(tp) - uint32_t(tp->wabase);400}401can_printf("%s STACK=%u/%u\n", tp->name, unsigned(stack_free(tp->wabase)), unsigned(total_stack));402}403}404#endif405406407408void AP_Periph_FW::update()409{410#if AP_STATS_ENABLED411node_stats.update();412#endif413414static uint32_t last_led_ms;415uint32_t now = AP_HAL::millis();416if (now - last_led_ms > 1000) {417last_led_ms = now;418#ifdef HAL_GPIO_PIN_LED419if (!no_iface_finished_dna) {420palToggleLine(HAL_GPIO_PIN_LED);421}422#endif423#if 0424#ifdef HAL_PERIPH_ENABLE_GPS425hal.serial(0)->printf("GPS status: %u\n", (unsigned)gps.status());426#endif427#ifdef HAL_PERIPH_ENABLE_MAG428const Vector3f &field = compass.get_field();429hal.serial(0)->printf("MAG (%d,%d,%d)\n", int(field.x), int(field.y), int(field.z));430#endif431#ifdef HAL_PERIPH_ENABLE_BARO432hal.serial(0)->printf("BARO H=%u P=%.2f T=%.2f\n", baro.healthy(), baro.get_pressure(), baro.get_temperature());433#endif434#ifdef HAL_PERIPH_ENABLE_RANGEFINDER435hal.serial(0)->printf("Num RNG sens %u\n", rangefinder.num_sensors());436for (uint8_t i=0; i<RANGEFINDER_MAX_INSTANCES; i++) {437AP_RangeFinder_Backend *backend = rangefinder.get_backend(i);438if (backend == nullptr) {439continue;440}441hal.serial(0)->printf("RNG %u %ucm\n", i, uint16_t(backend->distance()*100));442}443#endif444hal.scheduler->delay(1);445#endif446#ifdef HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY447hal.rcout->set_serial_led_num_LEDs(HAL_PERIPH_NEOPIXEL_CHAN_WITHOUT_NOTIFY, HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY, AP_HAL::RCOutput::MODE_NEOPIXEL);448#endif449450#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT451check_for_serial_reboot_cmd(HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT);452#endif453454#ifdef HAL_PERIPH_ENABLE_RC_OUT455rcout_init_1Hz();456#endif457458GCS_SEND_MESSAGE(MSG_HEARTBEAT);459GCS_SEND_MESSAGE(MSG_SYS_STATUS);460}461462static uint32_t last_error_ms;463const auto &ierr = AP::internalerror();464if (now - last_error_ms > 5000 && ierr.errors()) {465// display internal errors as DEBUG every 5s466last_error_ms = now;467can_printf("IERR 0x%x %u", unsigned(ierr.errors()), unsigned(ierr.last_error_line()));468}469470#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && CH_DBG_ENABLE_STACK_CHECK == TRUE471static uint32_t last_debug_ms;472if (debug_option_is_set(DebugOptions::SHOW_STACK) && now - last_debug_ms > 5000) {473last_debug_ms = now;474show_stack_free();475}476#endif477478if (debug_option_is_set(DebugOptions::AUTOREBOOT) && AP_HAL::millis() > 15000) {479// attempt reboot with HOLD after 15s480periph.prepare_reboot();481#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS482set_fast_reboot((rtc_boot_magic)(RTC_BOOT_HOLD));483NVIC_SystemReset();484#endif485}486487#ifdef HAL_PERIPH_ENABLE_BATTERY488if (now - battery.last_read_ms >= 100) {489// update battery at 10Hz490battery.last_read_ms = now;491battery_lib.read();492}493#endif494495#ifdef HAL_PERIPH_ENABLE_RCIN496rcin_update();497#endif498499#ifdef HAL_PERIPH_ENABLE_BATTERY_BALANCE500batt_balance_update();501#endif502503static uint32_t fiftyhz_last_update_ms;504if (now - fiftyhz_last_update_ms >= 20) {505// update at 50Hz506fiftyhz_last_update_ms = now;507#ifdef HAL_PERIPH_ENABLE_NOTIFY508notify.update();509#endif510#if HAL_GCS_ENABLED511gcs().update_receive();512gcs().update_send();513#endif514}515516#if HAL_NMEA_OUTPUT_ENABLED517nmea.update();518#endif519520#if AP_TEMPERATURE_SENSOR_ENABLED521temperature_sensor.update();522#endif523524#ifdef HAL_PERIPH_ENABLE_RPM525if (now - rpm_last_update_ms >= 100) {526rpm_last_update_ms = now;527rpm_sensor.update();528}529#endif530531#if HAL_LOGGING_ENABLED532logger.periodic_tasks();533#endif534535can_update();536537#ifdef HAL_PERIPH_ENABLE_NETWORKING538networking_periph.update();539#endif540541#if (defined(HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY) && HAL_PERIPH_NEOPIXEL_COUNT_WITHOUT_NOTIFY == 8) || defined(HAL_PERIPH_ENABLE_NOTIFY)542update_rainbow();543#endif544#ifdef HAL_PERIPH_ENABLE_ADSB545adsb_update();546#endif547}548549#ifdef HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT550// check for uploader.py reboot command551void AP_Periph_FW::check_for_serial_reboot_cmd(const int8_t serial_index)552{553// These are the string definitions in uploader.py554// NSH_INIT = bytearray(b'\x0d\x0d\x0d')555// NSH_REBOOT_BL = b"reboot -b\n"556// NSH_REBOOT = b"reboot\n"557558// This is the command sequence that is sent from uploader.py559// self.__send(uploader.NSH_INIT)560// self.__send(uploader.NSH_REBOOT_BL)561// self.__send(uploader.NSH_INIT)562// self.__send(uploader.NSH_REBOOT)563564for (uint8_t i=0; i<hal.num_serial; i++) {565if (serial_index >= 0 && serial_index != i) {566// a specific serial port was selected but this is not it567continue;568}569570auto *uart = hal.serial(i);571if (uart == nullptr || !uart->is_initialized()) {572continue;573}574575uint32_t available = MIN(uart->available(), 1000U);576while (available-- > 0) {577const char reboot_string[] = "\r\r\rreboot -b\n\r\r\rreboot\n";578const char reboot_string_len = sizeof(reboot_string)-1; // -1 is to remove the null termination579static uint16_t index[hal.num_serial];580581uint8_t data;582if (!uart->read(data)) {583// read error584continue;585}586if (index[i] >= reboot_string_len || (uint8_t)data != reboot_string[index[i]]) {587// don't have a perfect match, start over588index[i] = 0;589continue;590}591index[i]++;592if (index[i] == reboot_string_len) {593// received reboot msg. Trigger a reboot and stay in the bootloader594prepare_reboot();595hal.scheduler->reboot(true);596}597}598}599}600#endif // HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT601602// prepare for a safe reboot where PWMs and params are gracefully disabled603// This is copied from AP_Vehicle::reboot(bool hold_in_bootloader) minus the actual reboot604void AP_Periph_FW::prepare_reboot()605{606#ifdef HAL_PERIPH_ENABLE_RC_OUT607// force safety on608hal.rcout->force_safety_on();609#endif610611// flush pending parameter writes612AP_Param::flush();613614// do not process incoming mavlink messages while we delay:615hal.scheduler->register_delay_callback(nullptr, 5);616617// delay to give the ACK a chance to get out, the LEDs to flash,618// the IO board safety to be forced on, the parameters to flush,619hal.scheduler->expect_delay_ms(100);620hal.scheduler->delay(40);621hal.scheduler->expect_delay_ms(0);622}623624/*625reboot, optionally holding in bootloader. For scripting626*/627void AP_Periph_FW::reboot(bool hold_in_bootloader)628{629prepare_reboot();630hal.scheduler->reboot(hold_in_bootloader);631}632633AP_Periph_FW *AP_Periph_FW::_singleton;634635AP_Periph_FW& AP::periph()636{637return *AP_Periph_FW::get_singleton();638}639640AP_HAL_MAIN();641642643