add boards.c , remove msc_uf2.h lots of clean up and refactor
This commit is contained in:
parent
e4716816c2
commit
85ad6e6b65
1
Makefile
1
Makefile
@ -120,6 +120,7 @@ endif
|
||||
|
||||
# src
|
||||
C_SOURCE_FILES += $(SRC_PATH)/main.c
|
||||
C_SOURCE_FILES += $(SRC_PATH)/boards.c
|
||||
C_SOURCE_FILES += $(SRC_PATH)/flash.c
|
||||
C_SOURCE_FILES += $(SRC_PATH)/dfu_ble_svc.c
|
||||
C_SOURCE_FILES += $(SRC_PATH)/dfu_init.c
|
||||
|
@ -10,6 +10,7 @@
|
||||
*
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include "dfu_transport.h"
|
||||
#include "dfu.h"
|
||||
#include <dfu_types.h>
|
||||
@ -45,9 +46,8 @@ enum { BLE_CONN_CFG_HIGH_BANDWIDTH = 1 };
|
||||
#define DFU_SERVICE_HANDLE 0x000C /**< Handle of DFU service when DFU service is first service initialized. */
|
||||
#define BLE_HANDLE_MAX 0xFFFF /**< Max handle value is BLE. */
|
||||
|
||||
#define DEVICE_NAME "AdaDFU" // limit of 8 chars /**< Name of device. Will be included in the advertising data. */
|
||||
#define DIS_MANUFACTURER "Adafruit Industries"
|
||||
// DIS_MODEL is defined in boards.h, DIS_FIRMWARE is defined by makefile
|
||||
// limit of 8 chars
|
||||
#define DEVICE_NAME "AdaDFU" /**< Name of device. Will be included in the advertising data. */
|
||||
|
||||
#define MIN_CONN_INTERVAL (uint16_t)(MSEC_TO_UNITS(10, UNIT_1_25_MS)) /**< Minimum acceptable connection interval (11.25 milliseconds). */
|
||||
#define MAX_CONN_INTERVAL (uint16_t)(MSEC_TO_UNITS(30, UNIT_1_25_MS)) /**< Maximum acceptable connection interval (15 milliseconds). */
|
||||
@ -983,7 +983,18 @@ static void services_init(void)
|
||||
|
||||
ascii_to_utf8(&dis_init.manufact_name_str, DIS_MANUFACTURER);
|
||||
ascii_to_utf8(&dis_init.model_num_str, DIS_MODEL);
|
||||
ascii_to_utf8(&dis_init.fw_rev_str, MK_DIS_FIRMWARE);
|
||||
|
||||
uint32_t const sd_id = SD_ID_GET(MBR_SIZE);
|
||||
uint32_t const sd_version = SD_VERSION_GET(MBR_SIZE);
|
||||
|
||||
uint32_t const ver1 = sd_version / 1000000;
|
||||
uint32_t const ver2 = (sd_version % 1000000)/1000;
|
||||
uint32_t const ver3 = sd_version % 1000;
|
||||
|
||||
char fw_str[30+1];
|
||||
sprintf(fw_str, "s%ld %ld.%ld.%ld r%ld", sd_id, ver1, ver2, ver3, MK_BOOTLOADER_VERSION & 0xFFUL);
|
||||
|
||||
ascii_to_utf8(&dis_init.fw_rev_str, fw_str);
|
||||
|
||||
BLE_GAP_CONN_SEC_MODE_SET_OPEN(&dis_init.dis_attr_md.read_perm);
|
||||
BLE_GAP_CONN_SEC_MODE_SET_NO_ACCESS(&dis_init.dis_attr_md.write_perm);
|
||||
|
166
src/boards.c
Normal file
166
src/boards.c
Normal file
@ -0,0 +1,166 @@
|
||||
/**************************************************************************/
|
||||
/*!
|
||||
@file boards.c
|
||||
@author hathach (tinyusb.org)
|
||||
|
||||
@section LICENSE
|
||||
|
||||
Software License Agreement (BSD License)
|
||||
|
||||
Copyright (c) 2018, Adafruit Industries (adafruit.com)
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
1. Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
2. Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
3. Neither the name of the copyright holders nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
|
||||
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
/**************************************************************************/
|
||||
|
||||
#include "boards.h"
|
||||
#include "app_scheduler.h"
|
||||
#include "app_timer.h"
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// MACRO TYPEDEF CONSTANT ENUM DECLARATION
|
||||
//--------------------------------------------------------------------+
|
||||
#define SCHED_MAX_EVENT_DATA_SIZE sizeof(app_timer_event_t) /**< Maximum size of scheduler events. */
|
||||
#define SCHED_QUEUE_SIZE 30 /**< Maximum number of events in the scheduler queue. */
|
||||
|
||||
/* use PWM for blinky to prevent inconsistency due to MCU blocking in flash operation
|
||||
* clock = 125khz --> resolution = 8us
|
||||
* top value = 25000 -> period = 200 ms
|
||||
* Mode up -> toggle every 100 ms = fast blink
|
||||
* Mode up and down = 400 ms = slow blink
|
||||
*/
|
||||
#define PWM_MAXCOUNT 25000
|
||||
#define PWM_CHANNEL_NUM 4
|
||||
|
||||
|
||||
uint16_t _pwm_red_seq [PWM_CHANNEL_NUM] = { PWM_MAXCOUNT/2, 0, 0 , 0 };
|
||||
uint16_t _pwm_blue_seq[PWM_CHANNEL_NUM] = { PWM_MAXCOUNT/2, 0, 0 , 0 };
|
||||
|
||||
//------------- IMPLEMENTATION -------------//
|
||||
|
||||
void board_init(void)
|
||||
{
|
||||
// stop WDT if started by application, when jumping from application using BLE DFU
|
||||
if ( NRF_WDT->RUNSTATUS )
|
||||
{
|
||||
NRF_WDT->TASKS_START = 0;
|
||||
}
|
||||
|
||||
button_init(BUTTON_DFU);
|
||||
button_init(BUTTON_FRESET);
|
||||
NRFX_DELAY_US(100); // wait for the pin state is stable
|
||||
|
||||
// LED init
|
||||
nrf_gpio_cfg_output(LED_RED);
|
||||
nrf_gpio_cfg_output(LED_BLUE);
|
||||
led_off(LED_RED);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
// use PMW0 for LED RED
|
||||
led_pwm_init(NRF_PWM0, LED_RED);
|
||||
|
||||
// Init scheduler
|
||||
APP_SCHED_INIT(SCHED_MAX_EVENT_DATA_SIZE, SCHED_QUEUE_SIZE);
|
||||
|
||||
// Init app timer (use RTC1)
|
||||
app_timer_init();
|
||||
}
|
||||
|
||||
void board_teardown(void)
|
||||
{
|
||||
// Disable and reset PWM for LED
|
||||
led_pwm_teardown(NRF_PWM0);
|
||||
|
||||
led_off(LED_BLUE);
|
||||
led_off(LED_RED);
|
||||
|
||||
// Button
|
||||
|
||||
// Stop RTC1 used by app_timer
|
||||
NVIC_DisableIRQ(RTC1_IRQn);
|
||||
NRF_RTC1->EVTENCLR = RTC_EVTEN_COMPARE0_Msk;
|
||||
NRF_RTC1->INTENCLR = RTC_INTENSET_COMPARE0_Msk;
|
||||
NRF_RTC1->TASKS_STOP = 1;
|
||||
NRF_RTC1->TASKS_CLEAR = 1;
|
||||
}
|
||||
|
||||
uint32_t tusb_hal_millis(void)
|
||||
{
|
||||
return ( ( ((uint64_t)app_timer_cnt_get())*1000*(APP_TIMER_CONFIG_RTC_FREQUENCY+1)) / APP_TIMER_CLOCK_FREQ );
|
||||
}
|
||||
|
||||
|
||||
|
||||
void led_pwm_init(NRF_PWM_Type* pwm, uint32_t led_pin)
|
||||
{
|
||||
pwm->MODE = PWM_MODE_UPDOWN_UpAndDown;
|
||||
pwm->COUNTERTOP = PWM_MAXCOUNT;
|
||||
pwm->PRESCALER = PWM_PRESCALER_PRESCALER_DIV_128;
|
||||
pwm->DECODER = PWM_DECODER_LOAD_Individual;
|
||||
pwm->LOOP = 0;
|
||||
|
||||
pwm->SEQ[0].PTR = (uint32_t) (led_pin == LED_RED ? _pwm_red_seq : _pwm_blue_seq);
|
||||
pwm->SEQ[0].CNT = PWM_CHANNEL_NUM; // default mode is Individual --> count must be 4
|
||||
pwm->SEQ[0].REFRESH = 0;
|
||||
pwm->SEQ[0].ENDDELAY = 0;
|
||||
|
||||
pwm->PSEL.OUT[0] = led_pin;
|
||||
|
||||
pwm->ENABLE = 1;
|
||||
pwm->TASKS_SEQSTART[0] = 1;
|
||||
}
|
||||
|
||||
void led_pwm_teardown(NRF_PWM_Type* pwm)
|
||||
{
|
||||
pwm->TASKS_SEQSTART[0] = 0;
|
||||
pwm->ENABLE = 0;
|
||||
|
||||
pwm->PSEL.OUT[0] = 0xFFFFFFFF;
|
||||
|
||||
pwm->MODE = 0;
|
||||
pwm->COUNTERTOP = 0x3FF;
|
||||
pwm->PRESCALER = 0;
|
||||
pwm->DECODER = 0;
|
||||
pwm->LOOP = 0;
|
||||
pwm->SEQ[0].PTR = 0;
|
||||
pwm->SEQ[0].CNT = 0;
|
||||
}
|
||||
|
||||
void led_pwm_solid(uint32_t led_pin, bool solid)
|
||||
{
|
||||
uint16_t* seq = ((led_pin == LED_RED) ? _pwm_red_seq : _pwm_blue_seq);
|
||||
seq[0] = (solid ? PWM_MAXCOUNT : PWM_MAXCOUNT/2);
|
||||
}
|
||||
|
||||
void led_blink_fast(bool enable)
|
||||
{
|
||||
if ( enable )
|
||||
{
|
||||
NRF_PWM0->MODE = PWM_MODE_UPDOWN_Up;
|
||||
}else
|
||||
{
|
||||
NRF_PWM0->MODE = PWM_MODE_UPDOWN_UpAndDown;
|
||||
}
|
||||
}
|
||||
|
16
src/boards.h
16
src/boards.h
@ -26,11 +26,19 @@
|
||||
#error No boards defined
|
||||
#endif
|
||||
|
||||
#define BUTTON_DFU BUTTON_1
|
||||
#define BUTTON_FRESET BUTTON_2
|
||||
|
||||
#define LED_RED LED_1
|
||||
#define LED_BLUE LED_2
|
||||
|
||||
|
||||
void board_init(void);
|
||||
void board_teardown(void);
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// LED
|
||||
//--------------------------------------------------------------------+
|
||||
#define LED_RED LED_1
|
||||
#define LED_BLUE LED_2
|
||||
|
||||
#define bit(b) (1UL << (b))
|
||||
|
||||
@ -49,6 +57,10 @@ static inline void led_off(uint32_t pin)
|
||||
led_control(pin, false);
|
||||
}
|
||||
|
||||
void led_pwm_init(NRF_PWM_Type* pwm, uint32_t led_pin);
|
||||
void led_pwm_teardown(NRF_PWM_Type* pwm);
|
||||
void led_pwm_solid(uint32_t led_pin, bool solid);
|
||||
|
||||
void led_blink_fast(bool enable);
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
|
@ -63,6 +63,7 @@
|
||||
#define HWFC false
|
||||
|
||||
// Used as model string in OTA mode
|
||||
#define DIS_MANUFACTURER "Adafruit Industries"
|
||||
#define DIS_MODEL "Bluefruit Feather nRF52832"
|
||||
|
||||
#endif // _FEATHER52832_H
|
||||
|
@ -65,6 +65,7 @@
|
||||
#define HWFC false
|
||||
|
||||
// Used as model string in OTA mode
|
||||
#define DIS_MODEL "Bluefruit Feather nRF52840"
|
||||
#define DIS_MANUFACTURER "Adafruit Industries"
|
||||
#define DIS_MODEL "Bluefruit Feather nRF52840 Express"
|
||||
|
||||
#endif // _FEATHER52840_H
|
||||
|
@ -63,6 +63,7 @@
|
||||
#define HWFC false
|
||||
|
||||
// Used as model string in OTA mode
|
||||
#define DIS_MODEL "Nordic PCA10056"
|
||||
#define DIS_MANUFACTURER "Nordic"
|
||||
#define DIS_MODEL "PCA10056"
|
||||
|
||||
#endif // PCA10056_H
|
||||
|
163
src/main.c
163
src/main.c
@ -51,14 +51,12 @@
|
||||
#include "nrf.h"
|
||||
#include "ble_hci.h"
|
||||
#include "app_scheduler.h"
|
||||
#include "app_timer.h"
|
||||
#include "nrf_error.h"
|
||||
|
||||
#include "boards.h"
|
||||
|
||||
#include "pstorage_platform.h"
|
||||
#include "nrf_mbr.h"
|
||||
#include "nrf_wdt.h"
|
||||
#include "pstorage.h"
|
||||
|
||||
#include "nrf_nvmc.h"
|
||||
@ -66,7 +64,6 @@
|
||||
#ifdef NRF52840_XXAA
|
||||
#include "nrf_usbd.h"
|
||||
#include "tusb.h"
|
||||
#include "usb/msc_uf2.h"
|
||||
|
||||
void usb_init(void);
|
||||
void usb_teardown(void);
|
||||
@ -78,10 +75,16 @@ void usb_teardown(void);
|
||||
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Blinking patterns:
|
||||
* - DFU Serial : LED Status blink
|
||||
* - DFU OTA : LED Status & Conn blink at the same time
|
||||
* - DFU Flashing : LED Status blink 2x fast
|
||||
* - Factory Reset : LED Status blink 2x fast
|
||||
* - Fatal Error : LED Status & Conn blink one after another
|
||||
*/
|
||||
|
||||
#define BOOTLOADER_VERSION_REGISTER NRF_TIMER2->CC[0]
|
||||
|
||||
#define LED_BLINK_INTERVAL 100
|
||||
#define BOOTLOADER_STARTUP_DFU_INTERVAL 1000
|
||||
|
||||
/* Magic that written to NRF_POWER->GPREGRET by application when it wish to go into DFU
|
||||
@ -95,12 +98,6 @@ void usb_teardown(void);
|
||||
#define BOOTLOADER_DFU_OTA_FULLRESET_MAGIC 0xA8
|
||||
#define BOOTLOADER_DFU_SERIAL_MAGIC 0x4e
|
||||
|
||||
#define BUTTON_DFU BUTTON_1 // Button used to enter SW update mode.
|
||||
#define BUTTON_FRESET BUTTON_2 // Button used in addition to DFU button, to force OTA DFU
|
||||
|
||||
#define SCHED_MAX_EVENT_DATA_SIZE sizeof(app_timer_event_t) /**< Maximum size of scheduler events. */
|
||||
#define SCHED_QUEUE_SIZE 30 /**< Maximum number of events in the scheduler queue. */
|
||||
|
||||
// Helper function
|
||||
#define memclr(buffer, size) memset(buffer, 0, size)
|
||||
#define varclr(_var) memclr(_var, sizeof(*(_var)))
|
||||
@ -125,122 +122,13 @@ STATIC_ASSERT( APPDATA_ADDR_START == 0x6D000);
|
||||
|
||||
void adafruit_factory_reset(void);
|
||||
|
||||
/*
|
||||
* Blinking patterns:
|
||||
* - DFU Serial : LED Status blink
|
||||
* - DFU OTA : LED Status & Conn blink at the same time
|
||||
* - DFU Flashing : LED Status blink 2x fast
|
||||
* - Factory Reset : LED Status blink 2x fast
|
||||
* - Fatal Error : LED Status & Conn blink one after another
|
||||
*/
|
||||
bool _ota_connected = false;
|
||||
|
||||
// true if ble, false if serial
|
||||
bool _ota_update = false;
|
||||
bool _ota_connected = false;
|
||||
|
||||
bool is_ota(void) { return _ota_update; }
|
||||
|
||||
#define PWM_MAXCOUNT 25000
|
||||
uint16_t _pwm_red_seq0 [NRF_PWM_CHANNEL_COUNT] = { PWM_MAXCOUNT/2, 0, 0 , 0 };
|
||||
uint16_t _pwm_blue_seq0[NRF_PWM_CHANNEL_COUNT] = { PWM_MAXCOUNT/2, 0, 0 , 0 };
|
||||
|
||||
void led_blink_fast(bool enable)
|
||||
bool is_ota(void)
|
||||
{
|
||||
if ( enable )
|
||||
{
|
||||
NRF_PWM0->MODE = PWM_MODE_UPDOWN_Up;
|
||||
}else
|
||||
{
|
||||
NRF_PWM0->MODE = PWM_MODE_UPDOWN_UpAndDown;
|
||||
}
|
||||
}
|
||||
|
||||
/* use PWM for blinky to prevent inconsistency due to MCU blocking in flash operation
|
||||
* clock = 125khz --> resolution = 8us
|
||||
* top value = 25000 -> period = 200 ms (fast blink) --> up and down mode = 400 ms ( slow blink )
|
||||
*/
|
||||
void led_pwm_init(NRF_PWM_Type* pwm, uint32_t led_pin)
|
||||
{
|
||||
pwm->MODE = PWM_MODE_UPDOWN_UpAndDown;
|
||||
pwm->COUNTERTOP = PWM_MAXCOUNT;
|
||||
pwm->PRESCALER = PWM_PRESCALER_PRESCALER_DIV_128;
|
||||
pwm->DECODER = PWM_DECODER_LOAD_Individual;
|
||||
pwm->LOOP = 0;
|
||||
|
||||
pwm->SEQ[0].PTR = (uint32_t) (led_pin == LED_RED ? _pwm_red_seq0 : _pwm_blue_seq0);
|
||||
pwm->SEQ[0].CNT = NRF_PWM_CHANNEL_COUNT; // default mode is Individual --> count must be 4
|
||||
pwm->SEQ[0].REFRESH = 0;
|
||||
pwm->SEQ[0].ENDDELAY = 0;
|
||||
|
||||
pwm->PSEL.OUT[0] = led_pin;
|
||||
|
||||
pwm->ENABLE = 1;
|
||||
pwm->TASKS_SEQSTART[0] = 1;
|
||||
}
|
||||
|
||||
void led_pwm_teardown(NRF_PWM_Type* pwm)
|
||||
{
|
||||
pwm->TASKS_SEQSTART[0] = 0;
|
||||
pwm->ENABLE = 0;
|
||||
|
||||
pwm->PSEL.OUT[0] = 0xFFFFFFFF;
|
||||
|
||||
pwm->MODE = 0;
|
||||
pwm->COUNTERTOP = 0x3FF;
|
||||
pwm->PRESCALER = 0;
|
||||
pwm->DECODER = 0;
|
||||
pwm->LOOP = 0;
|
||||
pwm->SEQ[0].PTR = 0;
|
||||
pwm->SEQ[0].CNT = 0;
|
||||
}
|
||||
|
||||
void board_init(void)
|
||||
{
|
||||
// stop WDT if started by application, when jumping from application using BLE DFU
|
||||
if ( NRF_WDT->RUNSTATUS )
|
||||
{
|
||||
NRF_WDT->TASKS_START = 0;
|
||||
}
|
||||
|
||||
button_init(BUTTON_DFU);
|
||||
button_init(BUTTON_FRESET);
|
||||
NRFX_DELAY_US(100); // wait for the pin state is stable
|
||||
|
||||
// LED init
|
||||
nrf_gpio_cfg_output(LED_RED);
|
||||
nrf_gpio_cfg_output(LED_BLUE);
|
||||
led_off(LED_RED);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
// use PMW0 for LED RED
|
||||
led_pwm_init(NRF_PWM0, LED_RED);
|
||||
|
||||
// Init scheduler
|
||||
APP_SCHED_INIT(SCHED_MAX_EVENT_DATA_SIZE, SCHED_QUEUE_SIZE);
|
||||
|
||||
// Init app timer (use RTC1)
|
||||
app_timer_init();
|
||||
}
|
||||
|
||||
void board_teardown(void)
|
||||
{
|
||||
// Disable and reset PWM for LED
|
||||
led_pwm_teardown(NRF_PWM0);
|
||||
|
||||
if ( is_ota() ) led_pwm_teardown(NRF_PWM1);
|
||||
|
||||
led_off(LED_BLUE);
|
||||
led_off(LED_RED);
|
||||
|
||||
// Stop RTC1 used by app_timer
|
||||
NVIC_DisableIRQ(RTC1_IRQn);
|
||||
NRF_RTC1->EVTENCLR = RTC_EVTEN_COMPARE0_Msk;
|
||||
NRF_RTC1->INTENCLR = RTC_INTENSET_COMPARE0_Msk;
|
||||
NRF_RTC1->TASKS_STOP = 1;
|
||||
NRF_RTC1->TASKS_CLEAR = 1;
|
||||
|
||||
// disable usb
|
||||
usb_teardown();
|
||||
return _ota_update;
|
||||
}
|
||||
|
||||
void softdev_mbr_init(void)
|
||||
@ -376,7 +264,16 @@ int main(void)
|
||||
// Initiate an update of the firmware.
|
||||
APP_ERROR_CHECK( bootloader_dfu_start(_ota_update, 0) );
|
||||
|
||||
if ( _ota_update ) sd_softdevice_disable();
|
||||
if ( _ota_update )
|
||||
{
|
||||
led_pwm_teardown(NRF_PWM1);
|
||||
led_off(LED_BLUE);
|
||||
|
||||
sd_softdevice_disable();
|
||||
}else
|
||||
{
|
||||
usb_teardown();
|
||||
}
|
||||
}
|
||||
#ifdef NRF52832_XXAA
|
||||
else
|
||||
@ -388,15 +285,16 @@ int main(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
/*------------- Adafruit Factory reset -------------*/
|
||||
// Adafruit Factory reset
|
||||
if ( !button_pressed(BUTTON_DFU) && button_pressed(BUTTON_FRESET) )
|
||||
{
|
||||
adafruit_factory_reset();
|
||||
}
|
||||
|
||||
/*------------- Reset used prph and jump to application -------------*/
|
||||
// Reset Board
|
||||
board_teardown();
|
||||
|
||||
// Jump to application if valid
|
||||
if (bootloader_app_is_valid(DFU_BANK_0_REGION_START) && !bootloader_dfu_sd_in_progress())
|
||||
{
|
||||
// MBR must be init before start application
|
||||
@ -411,10 +309,6 @@ int main(void)
|
||||
}
|
||||
|
||||
|
||||
//--------------------------------------------------------------------+
|
||||
// FACTORY RESET
|
||||
//--------------------------------------------------------------------+
|
||||
|
||||
// Perform factory reset to erase Application + Data
|
||||
void adafruit_factory_reset(void)
|
||||
{
|
||||
@ -451,11 +345,6 @@ void assert_nrf_callback(uint16_t line_num, const uint8_t * p_file_name)
|
||||
app_error_handler(0xDEADBEEF, line_num, p_file_name);
|
||||
}
|
||||
|
||||
uint32_t tusb_hal_millis(void)
|
||||
{
|
||||
return ( ( ((uint64_t)app_timer_cnt_get())*1000*(APP_TIMER_CONFIG_RTC_FREQUENCY+1)) / APP_TIMER_CLOCK_FREQ );
|
||||
}
|
||||
|
||||
/*------------------------------------------------------------------*/
|
||||
/* SoftDevice Event handler
|
||||
*------------------------------------------------------------------*/
|
||||
@ -478,12 +367,12 @@ uint32_t proc_ble(void)
|
||||
{
|
||||
case BLE_GAP_EVT_CONNECTED:
|
||||
_ota_connected = true;
|
||||
_pwm_blue_seq0[0] = PWM_MAXCOUNT;
|
||||
led_pwm_solid(LED_BLUE, true); // LED on
|
||||
break;
|
||||
|
||||
case BLE_GAP_EVT_DISCONNECTED:
|
||||
_ota_connected = false;
|
||||
_pwm_blue_seq0[0] = PWM_MAXCOUNT/2;
|
||||
led_pwm_solid(LED_BLUE, false); // LED Blink
|
||||
break;
|
||||
|
||||
default: break;
|
||||
|
@ -65,7 +65,6 @@
|
||||
<file file_name="../usb/uf2/ghostfat.c" />
|
||||
</folder>
|
||||
<file file_name="../usb/msc_uf2.c" />
|
||||
<file file_name="../usb/msc_uf2.h" />
|
||||
<file file_name="../usb/usb.c" />
|
||||
</folder>
|
||||
<folder Name="cmsis">
|
||||
|
@ -34,7 +34,8 @@
|
||||
*/
|
||||
/**************************************************************************/
|
||||
|
||||
#include "msc_uf2.h"
|
||||
#include "tusb.h"
|
||||
#include "uf2/uf2.h"
|
||||
|
||||
#if CFG_TUD_MSC
|
||||
|
||||
|
@ -1,65 +0,0 @@
|
||||
/**************************************************************************/
|
||||
/*!
|
||||
@file msc_uf2.h
|
||||
@author hathach (tinyusb.org)
|
||||
|
||||
@section LICENSE
|
||||
|
||||
Software License Agreement (BSD License)
|
||||
|
||||
Copyright (c) 2018, Adafruit Industries (adafruit.com)
|
||||
All rights reserved.
|
||||
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions are met:
|
||||
1. Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
2. Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in the
|
||||
documentation and/or other materials provided with the distribution.
|
||||
3. Neither the name of the copyright holders nor the
|
||||
names of its contributors may be used to endorse or promote products
|
||||
derived from this software without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY
|
||||
EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
|
||||
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
|
||||
DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
|
||||
(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
|
||||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
|
||||
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
|
||||
SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
/**************************************************************************/
|
||||
#ifndef MSC_FLASH_H_
|
||||
#define MSC_FLASH_H_
|
||||
|
||||
#include "tusb.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
// for checking flash size
|
||||
#include "dfu_types.h"
|
||||
#include "uf2/uf2.h"
|
||||
|
||||
/*------------------------------------------------------------------*/
|
||||
/* FLASH Configuration
|
||||
*------------------------------------------------------------------*/
|
||||
#define MSC_UF2_FLASH_ADDR_START 0xAD000
|
||||
#define MSC_UF2_FLASH_SIZE (256*1024)
|
||||
|
||||
#define MSC_UF2_BLOCK_SIZE 512
|
||||
#define MSC_UF2_BLOCK_NUM UF2_NUM_BLOCKS
|
||||
|
||||
TU_VERIFY_STATIC( MSC_UF2_FLASH_ADDR_START+MSC_UF2_FLASH_SIZE == BOOTLOADER_REGION_START-DFU_APP_DATA_RESERVED, );
|
||||
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* MSC_FLASH_H_ */
|
@ -114,7 +114,7 @@
|
||||
#define CFG_TUD_MSC_VENDOR "Adafruit"
|
||||
|
||||
// Product name included in Inquiry response, max 16 bytes
|
||||
#define CFG_TUD_MSC_PRODUCT "Feather52840"
|
||||
#define CFG_TUD_MSC_PRODUCT "Feather nRF52840"
|
||||
|
||||
// Product revision string included in Inquiry response, max 4 bytes
|
||||
#define CFG_TUD_MSC_PRODUCT_REV "1.0"
|
||||
|
@ -1,5 +1,5 @@
|
||||
#define UF2_VERSION "1.00"
|
||||
#define PRODUCT_NAME "Adafruit Bluefruit nRF52840"
|
||||
#define PRODUCT_NAME "Adafruit " DIS_MODEL
|
||||
#define BOARD_ID "NRF52-Bluefruit-v0"
|
||||
#define INDEX_URL "https://www.adafruit.com/product/0000"
|
||||
#define BOOTLOADER_ID MK_DIS_FIRMWARE
|
||||
@ -8,7 +8,7 @@
|
||||
#define VOLUME_LABEL "NRF52BOOT "
|
||||
#define FLASH_SIZE (USER_FLASH_END-USER_FLASH_START) // Max flash size
|
||||
|
||||
// Only allow to write application
|
||||
// Only allow to write application TODO dynamic depending on SD size
|
||||
#define USER_FLASH_START 0x26000
|
||||
#define USER_FLASH_END 0xAD000 // Fat Fs start here
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user