Browse Source
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 definedrelease/1.12
David Sidrane
4 years ago
committed by
Lorenz Meier
20 changed files with 1303 additions and 62 deletions
@ -0,0 +1,34 @@
@@ -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 @@
@@ -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 |
||||
) |
@ -0,0 +1,607 @@
@@ -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 @@
@@ -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 @@
@@ -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 @@
@@ -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 @@
@@ -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 |
||||
) |
Loading…
Reference in new issue