AP_Periph: get AP_Periph ready for SITL build

This commit is contained in:
bugobliterator 2020-09-13 00:30:22 +05:30 committed by Andrew Tridgell
parent 2d80dcd937
commit e4c5d7b697
4 changed files with 48 additions and 9 deletions

View File

@ -22,10 +22,12 @@
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_Periph.h"
#include "hal.h"
#include <stdio.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
#endif
extern const AP_HAL::HAL &hal;
@ -36,6 +38,11 @@ void loop();
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
void stm32_watchdog_init() {}
void stm32_watchdog_pat() {}
#endif
void setup(void)
{
periph.init();
@ -51,10 +58,15 @@ static uint32_t start_ms;
/*
declare constant app_descriptor in flash
*/
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
const struct app_descriptor app_descriptor __attribute__((section(".app_descriptor")));
#else
const struct app_descriptor app_descriptor;
#endif
void AP_Periph_FW::init()
{
// always run with watchdog enabled. This should have already been
// setup by the bootloader, but if not then enable now
stm32_watchdog_init();
@ -208,7 +220,9 @@ void AP_Periph_FW::update()
uint32_t now = AP_HAL::millis();
if (now - last_led_ms > 1000) {
last_led_ms = now;
#ifdef HAL_GPIO_PIN_LED
palToggleLine(HAL_GPIO_PIN_LED);
#endif
#if 0
#ifdef HAL_PERIPH_ENABLE_GPS
hal.uartA->printf("GPS status: %u\n", (unsigned)gps.status());

View File

@ -1,3 +1,5 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_Param/AP_Param.h>
#include <AP_GPS/AP_GPS.h>
@ -15,8 +17,11 @@
#endif
#include "Parameters.h"
#include "ch.h"
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
void stm32_watchdog_init();
void stm32_watchdog_pat();
#endif
/*
app descriptor compatible with MissionPlanner
*/

View File

@ -18,7 +18,6 @@
#include <AP_HAL/AP_HAL.h>
#include <AP_Math/AP_Math.h>
#include "AP_Periph.h"
#include "hal.h"
#include <canard.h>
#include <uavcan/protocol/dynamic_node_id/Allocation.h>
#include <uavcan/protocol/NodeStatus.h>
@ -45,14 +44,20 @@
#include <uavcan/equipment/gnss/RTCMStream.h>
#include <uavcan/protocol/debug/LogMessage.h>
#include <stdio.h>
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
#include <drivers/stm32/canard_stm32.h>
#include <AP_HAL/I2CDevice.h>
#include "../AP_Bootloader/app_comms.h"
#include <AP_HAL/utility/RingBuffer.h>
#include <AP_Common/AP_FWVersion.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
#include "../AP_Bootloader/app_comms.h"
#include <AP_HAL_ChibiOS/CANIface.h>
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <AP_HAL_SITL/CANSocketIface.h>
#endif
#include "i2c.h"
#include <utility>
@ -80,8 +85,11 @@ static uint8_t transfer_id;
#define CAN_PROBE_CONTINUOUS 0
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
static ChibiOS::CANIface can_iface(0);
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
static HALSITL::CANIface can_iface(0);
#endif
/*
* Variables used for dynamic node ID allocation.
* RTFM at http://uavcan.org/Specification/6._Application_level_functions/#dynamic-node-id-allocation
@ -366,8 +374,10 @@ static void handle_begin_firmware_update(CanardInstance* ins, CanardRxTransfer*
// instant reboot, with backup register used to give bootloader
// the node_id
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
set_fast_reboot((rtc_boot_magic)(RTC_BOOT_CANBL | canardGetLocalNodeID(ins)));
NVIC_SystemReset();
#endif
}
static void handle_allocation_response(CanardInstance* ins, CanardRxTransfer* transfer)
@ -669,7 +679,11 @@ static void onTransferReceived(CanardInstance* ins,
case UAVCAN_PROTOCOL_RESTARTNODE_ID:
printf("RestartNode\n");
hal.scheduler->delay(10);
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
NVIC_SystemReset();
#elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
HAL_SITL::actually_reboot();
#endif
break;
case UAVCAN_PROTOCOL_PARAM_GETSET_ID:
@ -909,13 +923,14 @@ static void process1HzTasks(uint64_t timestamp_usec)
while (true) ;
}
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
if (AP_HAL::millis() > 30000) {
// use RTC to mark that we have been running fine for
// 30s. This is used along with watchdog resets to ensure the
// user has a chance to load a fixed firmware
set_fast_reboot(RTC_BOOT_FWOK);
}
#endif
}
/*
@ -950,7 +965,12 @@ static void can_wait_node_id(void)
if (now - last_led_change > led_change_period) {
// blink LED in recognisable pattern while waiting for DNA
#ifdef HAL_GPIO_PIN_LED
palWriteLine(HAL_GPIO_PIN_LED, (led_pattern & (1U<<led_idx))?1:0);
#else
(void)led_pattern;
(void)led_idx;
#endif
led_idx = (led_idx+1) % 32;
last_led_change = now;
}

View File

@ -4,7 +4,7 @@
import fnmatch
def build(bld):
targets = ['f103-*', 'f303-*', 'CUAV_GPS', 'ZubaxGNSS*', 'Cube*-periph']
targets = ['f103-*', 'f303-*', 'CUAV_GPS', 'ZubaxGNSS*', 'Cube*-periph', 'sitl*']
valid_target = False
for t in targets:
if fnmatch.fnmatch(bld.env.BOARD, t):