forked from Archive/PX4-Autopilot
canbootloader:Use Micro hal and arch selection
nxp/s32k14x:board_identity: Return length of mfguid nxp/s32k14x:CAN driver nxp/s32k14x:Drver Added ABORT on error canbootloader:Use N words for first word canbootloader:Ensure the up_progmem API always defined
This commit is contained in:
parent
ea255234da
commit
62c0c96749
|
@ -31,9 +31,9 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(arch/${PX4_CHIP_MANUFACTURER})
|
||||
|
||||
px4_add_library(canbootloader
|
||||
arch/stm32/board_identity.c
|
||||
arch/stm32/drivers/can/driver.c
|
||||
common/nuttx_stubs.c
|
||||
fs/flash.c
|
||||
protocol/uavcan.c
|
||||
|
@ -44,9 +44,12 @@ px4_add_library(canbootloader
|
|||
|
||||
include_directories(include)
|
||||
target_include_directories(canbootloader INTERFACE include)
|
||||
|
||||
target_compile_options(canbootloader PRIVATE -Wno-error)
|
||||
target_compile_options(arch_canbootloader PRIVATE -Wno-error)
|
||||
|
||||
target_link_libraries(canbootloader
|
||||
PRIVATE
|
||||
drivers_bootloaders
|
||||
arch_watchdog_iwdg
|
||||
arch_canbootloader
|
||||
)
|
||||
|
|
|
@ -0,0 +1,34 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2021 PX4 Development Team. 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 PX4 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 AND CONTRIBUTORS
|
||||
# "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 OWNER OR CONTRIBUTORS 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(${PX4_CHIP})
|
|
@ -0,0 +1,39 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2021 PX4 Development Team. 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 PX4 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 AND CONTRIBUTORS
|
||||
# "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 OWNER OR CONTRIBUTORS 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_directories(../../../include)
|
||||
px4_add_library(arch_canbootloader
|
||||
board_identity.c
|
||||
drivers/can/driver.c
|
||||
drivers/flash/driver.c
|
||||
)
|
|
@ -1,6 +1,7 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
|
||||
* Copyright (C) 2017 PX4 Development Team. All rights reserved.
|
||||
* Author: @author David Sidrane <david_s5@nscdg.com>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
@ -30,27 +31,31 @@
|
|||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
#pragma once
|
||||
/*
|
||||
* This file is a shim to bridge to nuttx_v3
|
||||
|
||||
/**
|
||||
* @file board_identity.c
|
||||
* Implementation of S32K based Board identity API
|
||||
*/
|
||||
|
||||
__BEGIN_DECLS
|
||||
#include <px4_config.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
# define PX4_CPU_UUID_BYTE_LENGTH 12
|
||||
# define PX4_CPU_UUID_WORD32_LENGTH (PX4_CPU_UUID_BYTE_LENGTH/sizeof(uint32_t))
|
||||
#include "board_common.h"
|
||||
|
||||
/* The mfguid will be an array of bytes with
|
||||
* MSD @ index 0 - LSD @ index PX4_CPU_MFGUID_BYTE_LENGTH-1
|
||||
*
|
||||
* It will be converted to a string with the MSD on left and LSD on the right most position.
|
||||
*/
|
||||
# define PX4_CPU_MFGUID_BYTE_LENGTH PX4_CPU_UUID_BYTE_LENGTH
|
||||
#include <hardware/s32k1xx_memorymap.h>
|
||||
#include <hardware/s32k1xx_sim.h>
|
||||
|
||||
/* Separator nnn:nnn:nnnn 2 char per byte term */
|
||||
# define PX4_CPU_UUID_WORD32_FORMAT_SIZE (PX4_CPU_UUID_WORD32_LENGTH-1+(2*PX4_CPU_UUID_BYTE_LENGTH)+1)
|
||||
# define PX4_CPU_MFGUID_FORMAT_SIZE ((2*PX4_CPU_MFGUID_BYTE_LENGTH)+1)
|
||||
#define SWAP_UINT32(x) (((x) >> 24) | (((x) & 0x00ff0000) >> 8) | (((x) & 0x0000ff00) << 8) | ((x) << 24))
|
||||
|
||||
int board_get_mfguid(mfguid_t mfgid)
|
||||
{
|
||||
uint32_t *chip_uuid = (uint32_t *) S32K1XX_SIM_UIDH;
|
||||
uint32_t *rv = (uint32_t *) &mfgid[0];
|
||||
|
||||
#include <arch/board/board.h>
|
||||
__END_DECLS
|
||||
for (unsigned int i = 0; i < PX4_CPU_UUID_WORD32_LENGTH; i++) {
|
||||
*rv++ = SWAP_UINT32(chip_uuid[(PX4_CPU_UUID_WORD32_LENGTH - 1) - i]);
|
||||
}
|
||||
|
||||
return PX4_CPU_MFGUID_BYTE_LENGTH;
|
||||
}
|
|
@ -0,0 +1,607 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david.sidrane@nscdg.com>
|
||||
*
|
||||
* 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 PX4 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 AND CONTRIBUTORS
|
||||
* "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 OWNER OR CONTRIBUTORS 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 <nuttx/config.h>
|
||||
#include "boot_config.h"
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <limits.h>
|
||||
|
||||
#include <hardware/s32k1xx_flexcan.h>
|
||||
#include "nvic.h"
|
||||
|
||||
#include "board.h"
|
||||
#include "px4_macros.h"
|
||||
#include "can.h"
|
||||
#include "timer.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include "flexcan.h"
|
||||
|
||||
#include <lib/systemlib/crc.h>
|
||||
|
||||
|
||||
#define CAN_TX_TIMEOUT_MS (200 /(1000/(1000000/CONFIG_USEC_PER_TICK)))
|
||||
|
||||
#define MIN(X,Y) ((X) < (Y) ? (X) : (Y))
|
||||
|
||||
/**
|
||||
* CANx register sets
|
||||
*/
|
||||
|
||||
/* Address of the CAN registers */
|
||||
|
||||
CanType *CAN0 = (CanType *) S32K1XX_FLEXCAN0_BASE; // CAN0
|
||||
enum { NumTxMesgBuffers = 6 };
|
||||
enum { NumFilters = 16 };
|
||||
|
||||
#define CLK_FREQ 80000000
|
||||
#define CLOCKSEL 0
|
||||
#define useFIFO 1
|
||||
#define numberFIFOFilters CAN_CTRL2_RFFN_16MB
|
||||
#define FIFO_IFLAG1 (CAN_FIFO_NE | CAN_FIFO_WARN | CAN_FIFO_OV)
|
||||
|
||||
|
||||
typedef struct Timings {
|
||||
uint8_t prescaler;
|
||||
uint8_t rjw;
|
||||
uint8_t pseg1;
|
||||
uint8_t pseg2;
|
||||
uint8_t propseg;
|
||||
} Timings;
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_speed2freq
|
||||
*
|
||||
* Description:
|
||||
* This function maps a can_speed_t to a bit rate in Hz
|
||||
*
|
||||
* Input Parameters:
|
||||
* can_speed - A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
|
||||
*
|
||||
* Returned value:
|
||||
* Bit rate in Hz
|
||||
*
|
||||
****************************************************************************/
|
||||
int can_speed2freq(can_speed_t speed)
|
||||
|
||||
{
|
||||
return 1000000 >> (CAN_1MBAUD - speed);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_speed2freq
|
||||
*
|
||||
* Description:
|
||||
* This function maps a frequency in Hz to a can_speed_t in the range
|
||||
* CAN_125KBAUD to CAN_1MBAUD.
|
||||
*
|
||||
* Input Parameters:
|
||||
* freq - Bit rate in Hz
|
||||
*
|
||||
* Returned value:
|
||||
* A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
|
||||
*
|
||||
****************************************************************************/
|
||||
can_speed_t can_freq2speed(int freq)
|
||||
{
|
||||
return (freq == 1000000u ? CAN_1MBAUD : freq == 500000u ? CAN_500KBAUD : freq == 250000u ? CAN_250KBAUD : CAN_125KBAUD);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_tx
|
||||
*
|
||||
* Description:
|
||||
* This function is called to transmit a CAN frame using the supplied
|
||||
* mailbox. It will busy wait on the mailbox if not available.
|
||||
*
|
||||
* Input Parameters:
|
||||
* message_id - The CAN message's EXID field
|
||||
* length - The number of bytes of data - the DLC field
|
||||
* message - A pointer to 8 bytes of data to be sent (all 8 bytes will be
|
||||
* loaded into the CAN transmitter but only length bytes will
|
||||
* be sent.
|
||||
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
|
||||
* mailbox.
|
||||
*
|
||||
* Returned value:
|
||||
* The CAN_OK of the data sent or CAN_ERROR if a time out occurred
|
||||
*
|
||||
****************************************************************************/
|
||||
uint8_t can_tx(uint32_t message_id, size_t length, const uint8_t *message, uint8_t mailbox)
|
||||
{
|
||||
timer_hrt_clear_wrap();
|
||||
uint32_t cnt = CAN_TX_TIMEOUT_MS;
|
||||
|
||||
uint32_t mbi = NumMBinFiFoAndFilters + mailbox;
|
||||
uint32_t mb_bit = 1 << mbi;
|
||||
MessageBufferType *mb = &CAN0->MB[mbi].mb;
|
||||
|
||||
/* Wait while all the MB are busy */
|
||||
|
||||
while ((CAN0->ESR2 & (CAN_ESR2_IMB | CAN_ESR2_VPS)) == (CAN_ESR2_VPS)) {
|
||||
if (timer_hrt_wrap()) {
|
||||
timer_hrt_clear_wrap();
|
||||
|
||||
if (--cnt == 0) {
|
||||
return CAN_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Wait it the requested mailbox is busy */
|
||||
|
||||
while ((CAN0->IFLAG1 & mb_bit) == 0) {
|
||||
|
||||
/* Not indicated, but it may be:
|
||||
* Inactive, aborted,
|
||||
*/
|
||||
|
||||
if (mb->CS.code != TxMbDataOrRemote) {
|
||||
break;
|
||||
}
|
||||
|
||||
if (timer_hrt_wrap()) {
|
||||
timer_hrt_clear_wrap();
|
||||
|
||||
if (--cnt == 0) {
|
||||
return CAN_ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Reset the flag */
|
||||
|
||||
CAN0->IFLAG1 = mb_bit;
|
||||
|
||||
/* Construct the frame */
|
||||
|
||||
MBcsType cs;
|
||||
cs.code = TxMbDataOrRemote;
|
||||
mb->CS.code = TxMbInactive;
|
||||
|
||||
cs.ide = 1;
|
||||
mb->ID.ext = message_id;
|
||||
cs.rtr = 0;
|
||||
cs.dlc = length;
|
||||
mb->data.l = __builtin_bswap32(*(uint32_t *)&message[0]);
|
||||
mb->data.h = __builtin_bswap32(*(uint32_t *)&message[4]);
|
||||
mb->CS = cs; // Go.
|
||||
return CAN_OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_rx
|
||||
*
|
||||
* Description:
|
||||
* This function is called to receive a CAN frame from a supplied fifo.
|
||||
* It does not block if there is not available, but returns 0
|
||||
*
|
||||
* Input Parameters:
|
||||
* message_id - A pointer to return the CAN message's EXID field
|
||||
* length - A pointer to return the number of bytes of data - the DLC field
|
||||
* message - A pointer to return 8 bytes of data to be sent (all 8 bytes will
|
||||
* be written from the CAN receiver but only length bytes will be sent.
|
||||
* fifo A can_fifo_mailbox_t fifixxx value to choose the incoming fifo.
|
||||
*
|
||||
* Returned value:
|
||||
* The length of the data read or 0 if the fifo was empty
|
||||
*
|
||||
****************************************************************************/
|
||||
uint8_t can_rx(uint32_t *message_id, size_t *length, uint8_t *message, uint8_t fifo)
|
||||
{
|
||||
uint8_t rv = 0;
|
||||
|
||||
uint32_t flags = CAN0->IFLAG1 & FIFO_IFLAG1;
|
||||
|
||||
if ((flags & FIFO_IFLAG1)) {
|
||||
|
||||
if (flags & CAN_FIFO_OV) {
|
||||
CAN0->IFLAG1 = CAN_FIFO_OV;
|
||||
}
|
||||
|
||||
if (flags & CAN_FIFO_WARN) {
|
||||
CAN0->IFLAG1 = CAN_FIFO_WARN;
|
||||
}
|
||||
|
||||
if (flags & CAN_FIFO_NE) {
|
||||
const RxFiFoType *rf = &CAN0->MB[FiFo].fifo;
|
||||
/*
|
||||
* Read the frame contents
|
||||
*/
|
||||
*message_id = rf->ID.ext;
|
||||
*length = rf->CS.dlc;
|
||||
*(uint32_t *)&message[0] = __builtin_bswap32(rf->data.l);
|
||||
*(uint32_t *)&message[4] = __builtin_bswap32(rf->data.h);
|
||||
(void)CAN0->TIMER;
|
||||
CAN0->IFLAG1 = CAN_FIFO_NE;
|
||||
rv = 1;
|
||||
}
|
||||
}
|
||||
|
||||
return rv;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_autobaud
|
||||
*
|
||||
* Description:
|
||||
* This function will attempt to detect the bit rate in use on the CAN
|
||||
* interface until the timeout provided expires or the successful detection
|
||||
* occurs.
|
||||
*
|
||||
* It will initialize the CAN block for a given bit rate
|
||||
* to test that a message can be received. The CAN interface is left
|
||||
* operating at the detected bit rate and in CAN_Mode_Normal mode.
|
||||
*
|
||||
* Input Parameters:
|
||||
* can_speed - A pointer to return detected can_speed_t from CAN_UNKNOWN to
|
||||
* CAN_1MBAUD
|
||||
* timeout - The timer id of a timer to use as the maximum time to wait for
|
||||
* successful bit rate detection. This timer may be not running
|
||||
* in which case the auto baud code will try indefinitely to
|
||||
* detect the bit rate.
|
||||
*
|
||||
* Returned value:
|
||||
* CAN_OK - on Success or a CAN_BOOT_TIMEOUT
|
||||
*
|
||||
****************************************************************************/
|
||||
int can_autobaud(can_speed_t *can_speed, bl_timer_id timeout)
|
||||
{
|
||||
uint32_t message_id;
|
||||
size_t length;
|
||||
uint8_t message[8];
|
||||
int rv = CAN_ERROR;
|
||||
|
||||
while (rv == CAN_ERROR) {
|
||||
for (can_speed_t speed = CAN_125KBAUD; rv == CAN_ERROR && speed <= CAN_1MBAUD; speed++) {
|
||||
|
||||
can_init(speed, CAN_Mode_Silent);
|
||||
|
||||
bl_timer_id baudtimer = timer_allocate(modeTimeout | modeStarted, 600, 0);
|
||||
|
||||
do {
|
||||
|
||||
if (timer_expired(timeout)) {
|
||||
rv = CAN_BOOT_TIMEOUT;
|
||||
break;
|
||||
}
|
||||
|
||||
if (can_rx(&message_id, &length, message, 0)) {
|
||||
*can_speed = speed;
|
||||
can_init(speed, CAN_Mode_Normal);
|
||||
rv = CAN_OK;
|
||||
break;
|
||||
}
|
||||
|
||||
} while (!timer_expired(baudtimer));
|
||||
|
||||
timer_free(baudtimer);
|
||||
}
|
||||
}
|
||||
|
||||
return rv;
|
||||
}
|
||||
|
||||
|
||||
static bool waitMCRChange(uint32_t mask, bool target_state)
|
||||
{
|
||||
const unsigned Timeout = 1000;
|
||||
|
||||
for (unsigned wait_ack = 0; wait_ack < Timeout; wait_ack++) {
|
||||
const bool state = (CAN0->MCR & mask) != 0;
|
||||
|
||||
if (state == target_state) {
|
||||
return true;
|
||||
}
|
||||
|
||||
up_udelay(10);
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
static void setMCR(uint32_t mask, bool target_state)
|
||||
{
|
||||
if (target_state) {
|
||||
CAN0->MCR |= mask;
|
||||
|
||||
} else {
|
||||
CAN0->MCR &= ~mask;
|
||||
}
|
||||
}
|
||||
|
||||
static bool waitFreezeAckChange(bool target_state)
|
||||
{
|
||||
return waitMCRChange(CAN_MCR_FRZACK, target_state);
|
||||
}
|
||||
|
||||
static void setFreeze(bool freeze_true)
|
||||
{
|
||||
{
|
||||
if (freeze_true) {
|
||||
CAN0->MCR |= CAN_MCR_FRZ;
|
||||
CAN0->MCR |= CAN_MCR_HALT;
|
||||
|
||||
} else {
|
||||
CAN0->MCR &= ~CAN_MCR_HALT;
|
||||
CAN0->MCR &= ~CAN_MCR_FRZ;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static bool setEnable(bool enable_true)
|
||||
{
|
||||
setMCR(CAN_MCR_MDIS, !enable_true);
|
||||
return waitMCRChange(CAN_MCR_LPMACK, !enable_true);
|
||||
}
|
||||
|
||||
static int16_t doReset(Timings timings)
|
||||
{
|
||||
setMCR(CAN_MCR_SOFTRST, true);
|
||||
|
||||
if (!waitMCRChange(CAN_MCR_SOFTRST, false)) {
|
||||
return -ETIME;
|
||||
}
|
||||
|
||||
uint8_t tasd = 25 - ((2 * (HWMaxMB + 1)) + 4 / ((1 + timings.pseg1 + timings.pseg2 + timings.propseg) *
|
||||
timings.prescaler));
|
||||
|
||||
setMCR(CAN_MCR_SUPV, false);
|
||||
|
||||
for (int i = 0; i < HWMaxMB; i++) {
|
||||
CAN0->MB[i].mb.CS.w = 0x0;
|
||||
CAN0->MB[i].mb.ID.w = 0x0;
|
||||
CAN0->MB[i].mb.data.l = 0x0;
|
||||
CAN0->MB[i].mb.data.h = 0x0;
|
||||
}
|
||||
|
||||
setMCR((useFIFO ? CAN_MCR_RFEN : 0) | CAN_MCR_SLFWAK | CAN_MCR_WRNEN | CAN_MCR_SRXDIS | CAN_MCR_IRMQ |
|
||||
CAN_MCR_AEN | (((HWMaxMB - 1) << CAN_MCR_MAXMB_SHIFT) & CAN_MCR_MAXMB_MASK), true);
|
||||
|
||||
CAN0->CTRL2 = numberFIFOFilters | ((tasd << CAN_CTRL2_TASD_SHIFT) & CAN_CTRL2_TASD_MASK) | CAN_CTRL2_RRS |
|
||||
CAN_CTRL2_EACEN;
|
||||
|
||||
for (int i = 0; i < HWMaxMB; i++) {
|
||||
CAN0->RXIMR[i].w = 0x0;
|
||||
}
|
||||
|
||||
CAN0->RX14MASK = 0x3FFFFFFF;
|
||||
CAN0->RX15MASK = 0x3FFFFFFF;
|
||||
CAN0->RXMGMASK = 0x3FFFFFFF;
|
||||
CAN0->RXFGMASK = 0x0;
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int computeTimings(const uint32_t target_bitrate, Timings *out_timings)
|
||||
{
|
||||
if (target_bitrate < 1) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/*
|
||||
* From FlexCAN Bit Timing Calculation by: Petr Stancik TIC
|
||||
* buadrate = 1 / tNBT -The tNBT represents a period of the Nominal Bit Time (NBT).
|
||||
* The NBT is separated into four non-overlaping segments,
|
||||
* SYNC_SEG, PROP_SEG,PHASE_SEG1 and PHASE_SEG2. Each of
|
||||
* these segments is an integer multiple of Time Quantum tQ
|
||||
* tNBT= tQ+PROP_SEG* tQ + PHASE_SEG1* tQ + PHASE_SEG2* tQ = NBT * tQ
|
||||
* tQ = 1/bitrate = 1/[BOARD_EXTAL_FREQ /(PRESDIV+1)].
|
||||
* NBT is 8..25
|
||||
* SYNC_SEG = 1 tQ
|
||||
* PROP_SEG = 1..8 tQ
|
||||
* PHASE1_SEG = 1,2..8 tQ 1..8 for 1 Sample per bit (Spb), 2..8 for 3 Spb
|
||||
* PHASE2_SEG = 1..8
|
||||
*
|
||||
*/
|
||||
/*
|
||||
* Hardware configuration
|
||||
*/
|
||||
|
||||
/* Maximize NBT
|
||||
* NBT * Prescaler = BOARD_EXTAL_FREQ / baud rate.
|
||||
*
|
||||
*/
|
||||
|
||||
const uint32_t nbt_prescaler = CLK_FREQ / target_bitrate;
|
||||
const int max_quanta_per_bit = 17;
|
||||
|
||||
out_timings->prescaler = 0;
|
||||
|
||||
/*
|
||||
* Searching for such prescaler value so that the number of quanta per bit is highest.
|
||||
*/
|
||||
|
||||
/* tNBT - tQ = PROP_SEG* tQ + PHASE_SEG1* tQ + PHASE_SEG2* tQ = NBT * tQ - tQ */
|
||||
|
||||
for (uint32_t prescaler = 1; prescaler < 256; prescaler++) {
|
||||
if (prescaler > nbt_prescaler) {
|
||||
return -EINVAL; // No solution
|
||||
}
|
||||
|
||||
if ((0 == nbt_prescaler % prescaler) && (nbt_prescaler / prescaler) < max_quanta_per_bit) {
|
||||
out_timings->prescaler = prescaler;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
const uint32_t NBT = nbt_prescaler / out_timings->prescaler;
|
||||
|
||||
/* Choose a reasonable and some what arbitrary value for Propseg */
|
||||
|
||||
out_timings->propseg = 5;
|
||||
|
||||
|
||||
/* Ideal sampling point = 87.5% given by (SYNC_SEG + PROP_SEG + PHASE_SEG1) / (PHASE_SEG2) */
|
||||
|
||||
uint32_t sp = (7 * NBT) / 8;
|
||||
|
||||
out_timings->pseg1 = sp - 1 - out_timings->propseg;
|
||||
out_timings->pseg2 = NBT - (1 + out_timings->pseg1 + out_timings->propseg);
|
||||
out_timings->rjw = MIN(4, out_timings->pseg2);
|
||||
|
||||
return ((out_timings->pseg1 <= 8) && (out_timings->pseg2 <= 8) && (out_timings->propseg <= 8)) ? 0 :
|
||||
-EINVAL;
|
||||
}
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_init
|
||||
*
|
||||
* Description:
|
||||
* This function is used to initialize the CAN block for a given bit rate and
|
||||
* mode.
|
||||
*
|
||||
* Input Parameters:
|
||||
* speed - A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
|
||||
* mode - One of the can_mode_t of Normal, LoopBack and Silent or
|
||||
* combination thereof.
|
||||
*
|
||||
* Returned value:
|
||||
* OK - on Success or a negate errno value
|
||||
*
|
||||
****************************************************************************/
|
||||
int can_init(can_speed_t speed, can_mode_t mode)
|
||||
{
|
||||
|
||||
/* Set the module disabled */
|
||||
|
||||
if (!setEnable(false)) {
|
||||
return -ETIME;
|
||||
}
|
||||
|
||||
/* Set the Clock */
|
||||
|
||||
CAN0->CTRL1 |= CAN_CTRL1_CLKSRC;
|
||||
|
||||
/* Set the module enabled */
|
||||
|
||||
if (!setEnable(true)) {
|
||||
return -ETIME;
|
||||
}
|
||||
|
||||
/*
|
||||
* CAN timings for this bitrate
|
||||
*/
|
||||
Timings timings;
|
||||
const int timings_res = computeTimings(can_speed2freq(speed), &timings);
|
||||
|
||||
if (timings_res < 0) {
|
||||
setEnable(false);
|
||||
return timings_res;
|
||||
}
|
||||
|
||||
/*
|
||||
* Hardware initialization from reset state
|
||||
*/
|
||||
|
||||
int16_t rv = doReset(timings);
|
||||
|
||||
if (rv != 0) {
|
||||
return -rv;
|
||||
}
|
||||
|
||||
uint32_t ctl1 = 0;
|
||||
ctl1 |= CAN_CTRL1_PRESDIV(timings.prescaler - 1);
|
||||
ctl1 |= CAN_CTRL1_RJW(timings.rjw - 1);
|
||||
ctl1 |= CAN_CTRL1_PSEG1(timings.pseg1 - 1);
|
||||
ctl1 |= CAN_CTRL1_PSEG2(timings.pseg2 - 1);
|
||||
ctl1 |= ((mode == CAN_Mode_Silent) ? CAN_CTRL1_LOM : 0);
|
||||
ctl1 |= CAN_CTRL1_PROPSEG(timings.propseg - 1);
|
||||
CAN0->CTRL1 = ctl1;
|
||||
|
||||
/*
|
||||
* Default filter configuration
|
||||
*/
|
||||
volatile FilterType *filterBase = (FilterType *) &CAN0->MB[FirstFilter].mb;
|
||||
|
||||
for (uint32_t i = 0; i < NumHWFilters; i++) {
|
||||
volatile FilterType *filter = &filterBase[i];
|
||||
filter->w = 0; // All bits do not care
|
||||
}
|
||||
|
||||
CAN0->RXFGMASK = 0; // All bits do not care
|
||||
|
||||
for (uint32_t mb = 0; mb < HWMaxMB; mb++) {
|
||||
CAN0->RXIMR[mb].w = 0; // All bits do not care
|
||||
}
|
||||
|
||||
CAN0->IFLAG1 = FIFO_IFLAG1 | TXMBMask;
|
||||
CAN0->IMASK1 = FIFO_IFLAG1;
|
||||
|
||||
setFreeze(false);
|
||||
return waitFreezeAckChange(false) ? 0 : -ETIME;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: can_cancel_on_error
|
||||
*
|
||||
* Description:
|
||||
* This function will test for transition completion or any error.
|
||||
* If the is a error the the transmit will be aborted.
|
||||
*
|
||||
* Input Parameters:
|
||||
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
|
||||
* mailbox.
|
||||
*
|
||||
* Returned value:
|
||||
* CAN_OK - on Success or a CAN_ERROR if the cancellation was needed
|
||||
*
|
||||
****************************************************************************/
|
||||
void can_cancel_on_error(uint8_t mailbox)
|
||||
{
|
||||
/* Wait for completion the all 1's wat set in the tx code*/
|
||||
while (CAN_ESR1_TX == (CAN0->ESR1 & CAN_ESR1_TX));
|
||||
|
||||
volatile uint32_t esr1 = CAN0->ESR1 & (CAN_ESR1_STFERR | CAN_ESR1_FRMERR |
|
||||
CAN_ESR1_CRCERR | CAN_ESR1_ACKERR |
|
||||
CAN_ESR1_BIT0ERR | CAN_ESR1_BIT1ERR | CAN_ESR1_TXWRN);
|
||||
|
||||
/* Any errors */
|
||||
if (esr1) {
|
||||
|
||||
uint32_t mbi = NumMBinFiFoAndFilters + mailbox;
|
||||
uint32_t mb_bit = 1 << mbi;
|
||||
MessageBufferType *mb = &CAN0->MB[mbi].mb;
|
||||
|
||||
CAN0->ESR1 = esr1;
|
||||
CAN0->IFLAG1 = mb_bit;
|
||||
mb->CS.code = TxMbAbort;
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,217 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david.sidrane@nscdg.com>
|
||||
*
|
||||
* 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 PX4 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 AND CONTRIBUTORS
|
||||
* "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 OWNER OR CONTRIBUTORS 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
enum { HWMaxMB = 16 };
|
||||
|
||||
typedef union MBcsType {
|
||||
volatile uint32_t w;
|
||||
struct {
|
||||
volatile uint32_t time_stamp : 16;
|
||||
volatile uint32_t dlc : 4;
|
||||
volatile uint32_t rtr : 1;
|
||||
volatile uint32_t ide : 1;
|
||||
volatile uint32_t srr : 1;
|
||||
volatile uint32_t res : 1;
|
||||
volatile uint32_t code : 4;
|
||||
volatile uint32_t res2 : 4;
|
||||
};
|
||||
} MBcsType;
|
||||
|
||||
typedef union FIFOcsType {
|
||||
volatile uint32_t cs;
|
||||
struct {
|
||||
volatile uint32_t time_stamp : 16;
|
||||
volatile uint32_t dlc : 4;
|
||||
volatile uint32_t rtr : 1;
|
||||
volatile uint32_t ide : 1;
|
||||
volatile uint32_t srr : 1;
|
||||
volatile uint32_t res : 9;
|
||||
};
|
||||
} FIFOcsType;
|
||||
|
||||
typedef union IDType {
|
||||
volatile uint32_t w;
|
||||
struct {
|
||||
volatile uint32_t ext : 29;
|
||||
volatile uint32_t resex : 3;
|
||||
};
|
||||
struct {
|
||||
volatile uint32_t res : 18;
|
||||
volatile uint32_t std : 11;
|
||||
volatile uint32_t resstd : 3;
|
||||
};
|
||||
} IDType;
|
||||
|
||||
typedef union FilterType {
|
||||
volatile uint32_t w;
|
||||
struct {
|
||||
volatile uint32_t res : 1; // Bit 0 - Reserved
|
||||
volatile uint32_t ext : 29; // Bits 1 - 29 EID
|
||||
};
|
||||
struct {
|
||||
volatile uint32_t ress : 19; // Bits 0, 1-18 Reserved
|
||||
volatile uint32_t std : 11; // StD ID
|
||||
};
|
||||
struct {
|
||||
volatile uint32_t resc : 30; // Bits 0 - 29 Reserved
|
||||
volatile uint32_t ide : 1; // Bit 30 - EID
|
||||
volatile uint32_t rtr : 1; // Bit 31 Remote
|
||||
};
|
||||
} FilterType;
|
||||
|
||||
typedef union DataType {
|
||||
struct {
|
||||
volatile uint32_t l;
|
||||
volatile uint32_t h;
|
||||
};
|
||||
struct {
|
||||
volatile uint32_t b3 : 8;
|
||||
volatile uint32_t b2 : 8;
|
||||
volatile uint32_t b1 : 8;
|
||||
volatile uint32_t b0 : 8;
|
||||
volatile uint32_t b7 : 8;
|
||||
volatile uint32_t b6 : 8;
|
||||
volatile uint32_t b5 : 8;
|
||||
volatile uint32_t b4 : 8;
|
||||
};
|
||||
} DataType;
|
||||
|
||||
|
||||
typedef struct MessageBufferType {
|
||||
MBcsType CS;
|
||||
IDType ID;
|
||||
DataType data;
|
||||
} MessageBufferType;
|
||||
|
||||
enum mb_code_tx {
|
||||
TxMbInactive = 0x8, /*!< MB is not active.*/
|
||||
TxMbAbort = 0x9, /*!< MB is aborted.*/
|
||||
TxMbDataOrRemote = 0xC, /*!< MB is a TX Data Frame(when MB RTR = 0) or */
|
||||
/*!< MB is a TX Remote Request Frame (when MB RTR = 1).*/
|
||||
TxMbTanswer = 0xE, /*!< MB is a TX Response Request Frame from */
|
||||
/*! an incoming Remote Request Frame.*/
|
||||
TxMbNotUsed = 0xF, /*!< Not used.*/
|
||||
};
|
||||
|
||||
typedef struct RxFiFoType {
|
||||
FIFOcsType CS;
|
||||
IDType ID;
|
||||
DataType data;
|
||||
} RxFiFoType;
|
||||
|
||||
enum mb_code_rx {
|
||||
kRxMbInactive = 0x0, /*!< MB is not active.*/
|
||||
kRxMbFull = 0x2, /*!< MB is full.*/
|
||||
kRxMbEmpty = 0x4, /*!< MB is active and empty.*/
|
||||
kRxMbOverrun = 0x6, /*!< MB is overwritten into a full buffer.*/
|
||||
kRxMbBusy = 0x8, /*!< FlexCAN is updating the contents of the MB.*/
|
||||
/*! The CPU must not access the MB.*/
|
||||
kRxMbRanswer = 0xA, /*!< A frame was configured to recognize a Remote Request Frame */
|
||||
/*! and transmit a Response Frame in return.*/
|
||||
kRxMbNotUsed = 0xF, /*!< Not used.*/
|
||||
};
|
||||
|
||||
typedef struct CanType {
|
||||
volatile uint32_t MCR; /*!< Module Configuration Register, Address offset: 0x0000 */
|
||||
volatile uint32_t CTRL1; /*!< Control 1 Register, Address offset: 0x0004 */
|
||||
volatile uint32_t TIMER; /*!< Free Running Timer, Address offset: 0x0008 */
|
||||
uint32_t Reserved0; /*!< Reserved Address offset: 0x000c */
|
||||
volatile uint32_t RXMGMASK; /*!< Rx Mailboxes Global Mask Register, Address offset: 0x0010 */
|
||||
volatile uint32_t RX14MASK; /*!< Rx 14 Mask Register, Address offset: 0x0014 */
|
||||
volatile uint32_t RX15MASK; /*!< Rx 15 Mask Register, Address offset: 0x0018 */
|
||||
volatile uint32_t ECR; /*!< Error Counter, Address offset: 0x001c */
|
||||
volatile uint32_t ESR1; /*!< Error and Status 1 Register, Address offset: 0x0020 */
|
||||
uint32_t Reserved1; /*!< Reserved Address offset: 0x0024 */
|
||||
volatile uint32_t IMASK1; /*!< Interrupt Masks 1 Register, Address offset: 0x0028 */
|
||||
uint32_t Reserved2; /*!< Reserved Address offset: 0x002C */
|
||||
volatile uint32_t IFLAG1; /*!< Interrupt Flags 1 Register, Address offset: 0x0030 */
|
||||
volatile uint32_t CTRL2; /*!< Control 2 Register, Address offset: 0x0034 */
|
||||
volatile uint32_t ESR2; /*!< Error and Status 2 Register, Address offset: 0x0038 */
|
||||
uint32_t Reserved3; /*!< Reserved Address offset: 0x003c */
|
||||
uint32_t Reserved4; /*!< Reserved Address offset: 0x0040 */
|
||||
volatile uint32_t CRCR; /*!< CRC Register, Address offset: 0x0044 */
|
||||
volatile uint32_t RXFGMASK; /*!< Rx FIFO Global Mask Register, Address offset: 0x0048 */
|
||||
volatile uint32_t RXFIR; /*!< Rx FIFO Information Register, Address offset: 0x004c */
|
||||
uint32_t RESERVED5[12]; /*!< Reserved Address offset: 0x0050 */
|
||||
union {
|
||||
RxFiFoType fifo;
|
||||
MessageBufferType mb;
|
||||
} MB[HWMaxMB];
|
||||
uint32_t RESERVED6[448]; /*!< Reserved Address offset: 0x0180 */
|
||||
volatile FilterType RXIMR[HWMaxMB]; /*!< R0 Individual Mask Registers, Address offset: 0x0880
|
||||
*/
|
||||
} CanType;
|
||||
|
||||
/* Layout of Fifo, filters and Message buffers */
|
||||
|
||||
enum { FiFo = 0 };
|
||||
/* 0 */
|
||||
/* 1 */
|
||||
/* 2 */
|
||||
/* 3 Fifo */
|
||||
/* 4 */
|
||||
/* 5 */
|
||||
enum { FirstFilter = 6 };
|
||||
/* 6 */
|
||||
/* 7 */
|
||||
/* 8 Filters */
|
||||
/* 9 */
|
||||
enum { NumHWFilters = 16 };
|
||||
enum { NumMBinFiFoAndFilters = 10 };
|
||||
/* 10 */
|
||||
/* 11 */
|
||||
/* 12 */
|
||||
/* 13 Tx Message Buffers */
|
||||
/* 14 */
|
||||
/* 15 */
|
||||
/*-- ----------------------*/
|
||||
|
||||
enum { TXMBMask = (0b111111 << NumMBinFiFoAndFilters) };
|
||||
|
||||
|
||||
#define CAN_IFLAG1_0 CAN_IFLAG1(0) /* Bit 0: Buffer MB0 Interrupt */
|
||||
#define CAN_IFLAG1_1 CAN_IFLAG1(1) /* Bit 1: Buffer MB1 Interrupt */
|
||||
#define CAN_IFLAG1_2 CAN_IFLAG1(2) /* Bit 2: Buffer MB2 Interrupt */
|
||||
#define CAN_IFLAG1_3 CAN_IFLAG1(3) /* Bit 3: Buffer MB3 Interrupt */
|
||||
#define CAN_IFLAG1_4 CAN_IFLAG1(4) /* Bit 4: Buffer MB4 Interrupt */
|
||||
#define CAN_IFLAG1_5 CAN_IFLAG1(5) /* Bit 5: Buffer MB5 Interrupt */
|
||||
#define CAN_FIFO_NE CAN_IFLAG1_5 /* Bit 5: Fifo almost Not empty Interrupt */
|
||||
#define CAN_IFLAG1_6 CAN_IFLAG1(6) /* Bit 6: Buffer MB6 Interrupt */
|
||||
#define CAN_FIFO_WARN CAN_IFLAG1_6 /* Bit 6: Fifo almost full Interrupt */
|
||||
#define CAN_IFLAG1_7 CAN_IFLAG1(7) /* Bit 7: Buffer MB7 Interrupt */
|
||||
#define CAN_FIFO_OV CAN_IFLAG1_7 /* Bit 7: Fifo Overflowed Interrupt */
|
|
@ -0,0 +1,226 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
|
||||
* Author: David Sidrane <david.sidrane@nscdg.com>
|
||||
*
|
||||
* 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 PX4 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 AND CONTRIBUTORS
|
||||
* "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 OWNER OR CONTRIBUTORS 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 <nuttx/config.h>
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
#include "boot_config.h"
|
||||
#include "flash.h"
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <limits.h>
|
||||
|
||||
#include "hardware/s32k1xx_ftfc.h"
|
||||
|
||||
|
||||
#define S32K1XX_PROGMEM_BLOCK_SECTOR_SIZE 4096
|
||||
#define S32K1XX_FLASH_BASE_ADDRESS 0
|
||||
#define S32K1XX_PROGMEM_PAGE_SIZE 8
|
||||
|
||||
CCASSERT(S32K1XX_PROGMEM_PAGE_SIZE == LATER_FLAHSED_WORDS *sizeof(uint32_t));
|
||||
|
||||
|
||||
|
||||
typedef union fccob_flash_addr_t {
|
||||
uint32_t addr;
|
||||
struct {
|
||||
uint8_t fccob3;
|
||||
uint8_t fccob2;
|
||||
uint8_t fccob1;
|
||||
uint8_t pad;
|
||||
} fccobs;
|
||||
} fccob_flash_addr_t;
|
||||
|
||||
|
||||
static uint8_t zero_dirty = 0xff;
|
||||
|
||||
ssize_t up_progmem_getpage(size_t addr);
|
||||
|
||||
locate_code(".ramfunc")
|
||||
static inline void wait_ftfc_ready(void)
|
||||
{
|
||||
while ((getreg8(S32K1XX_FTFC_FSTAT) & FTTC_FSTAT_CCIF) == 0) {
|
||||
/* Busy */
|
||||
}
|
||||
}
|
||||
|
||||
locate_code(".ramfunc")
|
||||
static uint32_t execute_ftfc_command(void)
|
||||
{
|
||||
uint8_t regval;
|
||||
uint32_t retval;
|
||||
|
||||
/* Clear CCIF to launch command */
|
||||
|
||||
regval = getreg8(S32K1XX_FTFC_FSTAT);
|
||||
regval |= FTTC_FSTAT_CCIF;
|
||||
|
||||
irqstate_t flags;
|
||||
|
||||
flags = enter_critical_section();
|
||||
|
||||
putreg8(regval, S32K1XX_FTFC_FSTAT);
|
||||
|
||||
wait_ftfc_ready();
|
||||
|
||||
leave_critical_section(flags);
|
||||
|
||||
retval = getreg8(S32K1XX_FTFC_FSTAT);
|
||||
|
||||
if (retval & (FTTC_FSTAT_MGSTAT0 | FTTC_FSTAT_FPVIOL |
|
||||
FTTC_FSTAT_ACCERR | FTTC_FSTAT_RDCOLERR)) {
|
||||
return retval; /* Error has occured */
|
||||
|
||||
} else {
|
||||
return 0; /* success */
|
||||
}
|
||||
}
|
||||
|
||||
locate_code(".ramfunc")
|
||||
ssize_t up_progmem_getpage(size_t addr)
|
||||
{
|
||||
return addr / S32K1XX_PROGMEM_BLOCK_SECTOR_SIZE;
|
||||
}
|
||||
|
||||
|
||||
locate_code(".ramfunc")
|
||||
ssize_t up_progmem_eraseblock(size_t block)
|
||||
{
|
||||
static bool once = false;
|
||||
|
||||
if (!once) {
|
||||
once = true;
|
||||
zero_dirty = 0xff;
|
||||
}
|
||||
|
||||
fccob_flash_addr_t dest;
|
||||
dest.addr = (block * S32K1XX_PROGMEM_BLOCK_SECTOR_SIZE) + S32K1XX_FLASH_BASE_ADDRESS;
|
||||
|
||||
/* Clear FSTAT error bits */
|
||||
|
||||
putreg8(FTTC_FSTAT_FPVIOL | FTTC_FSTAT_ACCERR | FTTC_FSTAT_RDCOLERR,
|
||||
S32K1XX_FTFC_FSTAT);
|
||||
|
||||
/* Set FTFC command */
|
||||
|
||||
putreg8(S32K1XX_FTFC_ERASE_SECTOR, S32K1XX_FTFC_FCCOB0);
|
||||
|
||||
/* Destination address of sector to erase */
|
||||
|
||||
putreg8(dest.fccobs.fccob1, S32K1XX_FTFC_FCCOB1);
|
||||
putreg8(dest.fccobs.fccob2, S32K1XX_FTFC_FCCOB2);
|
||||
putreg8(dest.fccobs.fccob3, S32K1XX_FTFC_FCCOB3);
|
||||
|
||||
if (execute_ftfc_command() & (FTTC_FSTAT_MGSTAT0 | FTTC_FSTAT_FPVIOL |
|
||||
FTTC_FSTAT_ACCERR | FTTC_FSTAT_RDCOLERR)) {
|
||||
return -EIO; /* Error has occured */
|
||||
}
|
||||
|
||||
return (ssize_t)S32K1XX_PROGMEM_BLOCK_SECTOR_SIZE;
|
||||
}
|
||||
|
||||
|
||||
locate_code(".ramfunc")
|
||||
ssize_t up_progmem_write(size_t addr, FAR const void *buf, size_t count)
|
||||
{
|
||||
fccob_flash_addr_t dest;
|
||||
uint8_t *src = (uint8_t *)buf;
|
||||
ssize_t cashed = 0;
|
||||
|
||||
|
||||
if (addr == APPLICATION_LOAD_ADDRESS) {
|
||||
|
||||
/* On the first pass we will not write the first 8 bytes, and leave them erased. */
|
||||
|
||||
if (zero_dirty == 0xff) {
|
||||
cashed = S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
zero_dirty = 0;
|
||||
addr += S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
src += S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
count -= S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
|
||||
} else {
|
||||
|
||||
/* On the second pass we will write the first 8 bytes. */
|
||||
|
||||
cashed = count - S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
count = S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
zero_dirty = 0xff;
|
||||
}
|
||||
}
|
||||
|
||||
if (count % S32K1XX_PROGMEM_PAGE_SIZE != 0) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
dest.addr = addr;
|
||||
|
||||
for (size_t i = 0; i < count / S32K1XX_PROGMEM_PAGE_SIZE ; i++) {
|
||||
wait_ftfc_ready();
|
||||
|
||||
/* Clear FSTAT error bits */
|
||||
|
||||
putreg8(FTTC_FSTAT_FPVIOL | FTTC_FSTAT_ACCERR | FTTC_FSTAT_RDCOLERR,
|
||||
S32K1XX_FTFC_FSTAT);
|
||||
|
||||
/* Set FTFC command */
|
||||
|
||||
putreg8(S32K1XX_FTFC_PROGRAM_PHRASE, S32K1XX_FTFC_FCCOB0);
|
||||
|
||||
/* Destination address */
|
||||
|
||||
putreg8(dest.fccobs.fccob1, S32K1XX_FTFC_FCCOB1);
|
||||
putreg8(dest.fccobs.fccob2, S32K1XX_FTFC_FCCOB2);
|
||||
putreg8(dest.fccobs.fccob3, S32K1XX_FTFC_FCCOB3);
|
||||
|
||||
/* Write data */
|
||||
|
||||
for (int j = 0; j < S32K1XX_PROGMEM_PAGE_SIZE; j++) {
|
||||
putreg8(src[j], S32K1XX_FTFC_FCCOB7 + j);
|
||||
}
|
||||
|
||||
if (execute_ftfc_command() & (FTTC_FSTAT_MGSTAT0 | FTTC_FSTAT_FPVIOL |
|
||||
FTTC_FSTAT_ACCERR | FTTC_FSTAT_RDCOLERR)) {
|
||||
return -EIO; /* Error has occured */
|
||||
}
|
||||
|
||||
dest.addr = dest.addr + S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
src = src + S32K1XX_PROGMEM_PAGE_SIZE;
|
||||
}
|
||||
|
||||
return count + cashed;
|
||||
}
|
|
@ -0,0 +1,34 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2019 PX4 Development Team. 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 PX4 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 AND CONTRIBUTORS
|
||||
# "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 OWNER OR CONTRIBUTORS 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(${PX4_CHIP})
|
|
@ -0,0 +1,44 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2019 PX4 Development Team. 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 PX4 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 AND CONTRIBUTORS
|
||||
# "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 OWNER OR CONTRIBUTORS 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_directories(../../../include)
|
||||
|
||||
px4_add_library(arch_canbootloader
|
||||
board_identity.c
|
||||
drivers/can/driver.c
|
||||
)
|
||||
|
||||
target_link_libraries(arch_canbootloader
|
||||
PRIVATE
|
||||
arch_watchdog_iwdg
|
||||
)
|
|
@ -41,10 +41,15 @@
|
|||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <nuttx/progmem.h>
|
||||
/* Force the interface to be defined. Even if the NuttX config is not
|
||||
* providing the driver, but the the bootloader is.
|
||||
*/
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32.h"
|
||||
#if !defined(CONFIG_ARCH_HAVE_PROGMEM)
|
||||
# define CONFIG_ARCH_HAVE_PROGMEM
|
||||
#endif
|
||||
|
||||
#include <nuttx/progmem.h>
|
||||
|
||||
#include "flash.h"
|
||||
#include "blsched.h"
|
||||
|
|
|
@ -46,6 +46,15 @@ typedef enum {
|
|||
|
||||
} flash_error_t;
|
||||
|
||||
#if defined(OPT_LATER_FLAHSED_WORDS)
|
||||
# define LATER_FLAHSED_WORDS OPT_LATER_FLAHSED_WORDS /* The number of 32 bit words not written until
|
||||
* after CRC verification
|
||||
*/
|
||||
#else
|
||||
# define LATER_FLAHSED_WORDS 1 /* The number of 32 bit words not written until
|
||||
* after CRC verification
|
||||
*/
|
||||
#endif
|
||||
/****************************************************************************
|
||||
* Name: bl_flash_erase
|
||||
*
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include "px4_micro_hal.h"
|
||||
#include <px4_arch/micro_hal.h>
|
||||
#include <board_config.h>
|
||||
|
||||
#elif defined (__PX4_POSIX)
|
||||
|
|
|
@ -48,11 +48,9 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "stm32.h"
|
||||
#include <px4_arch/micro_hal.h>
|
||||
#include "nvic.h"
|
||||
|
||||
#define TIMER_HRT_CYCLES_PER_US (STM32_HCLK_FREQUENCY/1000000)
|
||||
#define TIMER_HRT_CYCLES_PER_MS (STM32_HCLK_FREQUENCY/1000)
|
||||
|
||||
/* Types for timer access */
|
||||
typedef uint8_t bl_timer_id; /* A timer handle */
|
||||
|
|
|
@ -45,9 +45,6 @@
|
|||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32.h"
|
||||
|
||||
#include "timer.h"
|
||||
#include "uavcan.h"
|
||||
#include "can.h"
|
||||
|
|
|
@ -45,7 +45,6 @@
|
|||
#include <string.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32.h"
|
||||
#include "nvic.h"
|
||||
|
||||
#include "board.h"
|
||||
|
@ -100,7 +99,7 @@ typedef volatile struct bootloader_t {
|
|||
union {
|
||||
uint32_t l;
|
||||
uint8_t b[sizeof(uint32_t)];
|
||||
} fw_word0;
|
||||
} fw_word0[LATER_FLAHSED_WORDS];
|
||||
|
||||
} bootloader_t;
|
||||
|
||||
|
@ -341,14 +340,14 @@ static void find_descriptor(void)
|
|||
*
|
||||
*
|
||||
* Input Parameters:
|
||||
* first_word - the value read from the first word of the Application's
|
||||
* first_word - pointer the value read from the first 2 words of the Application's
|
||||
* in FLASH image.
|
||||
*
|
||||
* Returned Value:
|
||||
* true if the application in flash is valid., false otherwise.
|
||||
*
|
||||
****************************************************************************/
|
||||
static bool is_app_valid(uint32_t first_word)
|
||||
static bool is_app_valid(volatile uint32_t *first_words)
|
||||
{
|
||||
uint32_t block_crc1;
|
||||
uint32_t block_crc2;
|
||||
|
@ -356,7 +355,7 @@ static bool is_app_valid(uint32_t first_word)
|
|||
|
||||
find_descriptor();
|
||||
|
||||
if (!bootloader.fw_image_descriptor || first_word == 0xFFFFFFFFu) {
|
||||
if (!bootloader.fw_image_descriptor || first_words[0] == 0xFFFFFFFFu) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -373,9 +372,9 @@ static bool is_app_valid(uint32_t first_word)
|
|||
return false;
|
||||
}
|
||||
|
||||
block_crc1 = crc32_signature(0, sizeof(first_word), (const uint8_t *)&first_word);
|
||||
block_crc1 = crc32_signature(0, LATER_FLAHSED_WORDS * sizeof(uint32_t), (const uint8_t *)first_words);
|
||||
block_crc1 = crc32_signature(block_crc1, (size_t)(&bootloader.fw_image_descriptor->crc32_block1) -
|
||||
(size_t)(bootloader.fw_image + 1), (const uint8_t *)(bootloader.fw_image + 1));
|
||||
(size_t)(bootloader.fw_image + LATER_FLAHSED_WORDS), (const uint8_t *)(bootloader.fw_image + LATER_FLAHSED_WORDS));
|
||||
|
||||
block_crc2 = crc32_signature(0, block2_len,
|
||||
(const uint8_t *) &bootloader.fw_image_descriptor->major_version);
|
||||
|
@ -842,10 +841,15 @@ static flash_error_t file_read_and_program(const uavcan_Path_t *fw_path, uint8_t
|
|||
data[length] = 0xff;
|
||||
}
|
||||
|
||||
/* Save the first word off */
|
||||
/* Save the first words off */
|
||||
if (request.offset == 0u) {
|
||||
bootloader.fw_word0.l = *(uint32_t *)data;
|
||||
*(uint32_t *)data = 0xffffffff;
|
||||
uint32_t *datal = (uint32_t *)data;
|
||||
bootloader.fw_word0[0].l = datal[0];
|
||||
datal[0] = 0xffffffff;
|
||||
#if LATER_FLAHSED_WORDS > 1
|
||||
bootloader.fw_word0[1].l = datal[1];
|
||||
datal[1] = 0xffffffff;
|
||||
#endif
|
||||
}
|
||||
|
||||
flash_status = bl_flash_write(flash_address + request.offset,
|
||||
|
@ -1089,12 +1093,12 @@ __EXPORT int main(int argc, char *argv[])
|
|||
*
|
||||
*/
|
||||
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
|
||||
bootloader.wait_for_getnodeinfo = (stm32_gpioread(GPIO_GETNODEINFO_JUMPER) ^
|
||||
bootloader.wait_for_getnodeinfo = (px4_arch_gpioread(GPIO_GETNODEINFO_JUMPER) ^
|
||||
OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT);
|
||||
#endif
|
||||
|
||||
/* Is the memory in the Application space occupied by a valid application? */
|
||||
bootloader.app_valid = is_app_valid(bootloader.fw_image[0]);
|
||||
bootloader.app_valid = is_app_valid(bootloader.fw_image);
|
||||
|
||||
board_indicate(reset);
|
||||
|
||||
|
@ -1312,7 +1316,6 @@ __EXPORT int main(int argc, char *argv[])
|
|||
LOGMESSAGE_STAGE_ERASE,
|
||||
LOGMESSAGE_RESULT_START);
|
||||
|
||||
|
||||
/* Need to signal that the app is no longer valid if Node Info Request are done */
|
||||
bootloader.app_valid = false;
|
||||
|
||||
|
@ -1335,7 +1338,7 @@ __EXPORT int main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
/* Did we program a valid image ?*/
|
||||
if (!is_app_valid(bootloader.fw_word0.l)) {
|
||||
if (!is_app_valid(&bootloader.fw_word0[0].l)) {
|
||||
bootloader.app_valid = 0u;
|
||||
|
||||
board_indicate(fw_update_invalid_crc);
|
||||
|
@ -1344,9 +1347,9 @@ __EXPORT int main(int argc, char *argv[])
|
|||
goto failure;
|
||||
}
|
||||
|
||||
/* Yes Commit the first word to location 0 of the Application image in flash */
|
||||
status = bl_flash_write((uint32_t) bootloader.fw_image, (uint8_t *) &bootloader.fw_word0.b[0],
|
||||
sizeof(bootloader.fw_word0.b));
|
||||
/* Yes Commit the first word(s) to location 0 of the Application image in flash */
|
||||
status = bl_flash_write((uint32_t) bootloader.fw_image, (uint8_t *) &bootloader.fw_word0[0].b[0],
|
||||
sizeof(bootloader.fw_word0));
|
||||
|
||||
if (status != FLASH_OK) {
|
||||
error_log_stage = LOGMESSAGE_STAGE_FINALIZE;
|
||||
|
|
|
@ -51,6 +51,7 @@ __BEGIN_DECLS
|
|||
#include <s32k1xx_pin.h>
|
||||
#include <s32k1xx_lpspi.h>
|
||||
#include <s32k1xx_lpi2c.h>
|
||||
#include <s32k1xx_flexcan.h>
|
||||
//#include <s32k1xx_uid.h>
|
||||
|
||||
/* s32k1xx defines the 128 bit UUID as
|
||||
|
@ -111,4 +112,16 @@ __BEGIN_DECLS
|
|||
#define px4_arch_gpiosetevent(pinset,r,f,e,fp,a) s32k1xx_gpiosetevent(pinset,r,f,e,fp,a)
|
||||
|
||||
#define I2C_RESET(q)
|
||||
|
||||
/* CAN bootloader usage */
|
||||
|
||||
#define TIMER_HRT_CYCLES_PER_US (STM32_HCLK_FREQUENCY/1000000)
|
||||
#define TIMER_HRT_CYCLES_PER_MS (STM32_HCLK_FREQUENCY/1000)
|
||||
|
||||
#define crc_HiLOC S32K1XX_CAN0_RXIMR27
|
||||
#define crc_LoLOC S32K1XX_CAN0_RXIMR28
|
||||
#define signature_LOC S32K1XX_CAN0_RXIMR29
|
||||
#define bus_speed_LOC S32K1XX_CAN0_RXIMR30
|
||||
#define node_id_LOC S32K1XX_CAN0_RXIMR31
|
||||
|
||||
__END_DECLS
|
||||
|
|
|
@ -107,4 +107,23 @@ __BEGIN_DECLS
|
|||
|
||||
#define PX4_GPIO_PIN_OFF(def) (((def) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_2MHz))
|
||||
|
||||
/* CAN bootloader usage */
|
||||
|
||||
#define TIMER_HRT_CYCLES_PER_US (STM32_HCLK_FREQUENCY/1000000)
|
||||
#define TIMER_HRT_CYCLES_PER_MS (STM32_HCLK_FREQUENCY/1000)
|
||||
|
||||
/* CAN_FiRx where (i=0..27|13, x=1, 2)
|
||||
* STM32_CAN1_FIR(i,x)
|
||||
* Using i = 2 does not requier there block
|
||||
* to be enabled nor FINIT in CAN_FMR to be set.
|
||||
* todo:Validate this claim on F2, F3
|
||||
*/
|
||||
|
||||
#define crc_HiLOC STM32_CAN1_FIR(2,1)
|
||||
#define crc_LoLOC STM32_CAN1_FIR(2,2)
|
||||
#define signature_LOC STM32_CAN1_FIR(3,1)
|
||||
#define bus_speed_LOC STM32_CAN1_FIR(3,2)
|
||||
#define node_id_LOC STM32_CAN1_FIR(4,1)
|
||||
|
||||
|
||||
__END_DECLS
|
||||
|
|
|
@ -39,11 +39,11 @@
|
|||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "stm32.h"
|
||||
|
||||
#include <errno.h>
|
||||
|
||||
#include <px4_arch/micro_hal.h>
|
||||
#include "arm_arch.h"
|
||||
#include "boot_app_shared.h"
|
||||
|
||||
#include <lib/systemlib/crc.h>
|
||||
|
@ -51,18 +51,6 @@
|
|||
#define BOOTLOADER_COMMON_APP_SIGNATURE 0xB0A04150u
|
||||
#define BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE 0xB0A0424Cu
|
||||
|
||||
/* CAN_FiRx where (i=0..27|13, x=1, 2)
|
||||
* STM32_CAN1_FIR(i,x)
|
||||
* Using i = 2 does not requier there block
|
||||
* to be enabled nor FINIT in CAN_FMR to be set.
|
||||
* todo:Validate this claim on F2, F3
|
||||
*/
|
||||
|
||||
#define crc_HiLOC STM32_CAN1_FIR(2,1)
|
||||
#define crc_LoLOC STM32_CAN1_FIR(2,2)
|
||||
#define signature_LOC STM32_CAN1_FIR(3,1)
|
||||
#define bus_speed_LOC STM32_CAN1_FIR(3,2)
|
||||
#define node_id_LOC STM32_CAN1_FIR(4,1)
|
||||
#define CRC_H 1
|
||||
#define CRC_L 0
|
||||
|
||||
|
|
Loading…
Reference in New Issue