Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found
Select Git revision

Target

Select target project
  • avn/swd/miosix-kernel
  • emilio.corigliano/miosix-kernel
2 results
Select Git revision
Show changes
Commits on Source (3)
...@@ -91,6 +91,9 @@ foreach(OPT_BOARD ${BOARDS}) ...@@ -91,6 +91,9 @@ foreach(OPT_BOARD ${BOARDS})
util/version.cpp util/version.cpp
util/crc16.cpp util/crc16.cpp
util/lcd44780.cpp util/lcd44780.cpp
util/angel/angel.cpp
util/angel/angel_serial.cpp
util/angel/angel_fs.cpp
${ARCH_SRC} ${ARCH_SRC}
) )
add_library(Miosix::Miosix::${OPT_BOARD} ALIAS ${MIOSIX_LIBRARY}) add_library(Miosix::Miosix::${OPT_BOARD} ALIAS ${MIOSIX_LIBRARY})
......
...@@ -187,7 +187,7 @@ void __attribute__((used)) SDDMAirqImpl() ...@@ -187,7 +187,7 @@ void __attribute__((used)) SDDMAirqImpl()
/** /**
* \internal * \internal
* DMA2 Stream3 interrupt handler actual implementation * SDIO interrupt handler handler actual implementation
*/ */
void __attribute__((used)) SDirqImpl() void __attribute__((used)) SDirqImpl()
{ {
......
/***************************************************************************
* Copyright (C) 2010, 2011, 2012, 2013, 2014 by Terraneo Federico *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License, or *
* (at your option) any later version. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* As a special exception, if other files instantiate templates or use *
* macros or inline functions from this file, or you compile this file *
* and link it with other works to produce a work based on this file, *
* this file does not by itself cause the resulting work to be covered *
* by the GNU General Public License. However the source code for this *
* file must still be made available in accordance with the GNU General *
* Public License. This exception does not invalidate any other reasons *
* why a work based on this file might be covered by the GNU General *
* Public License. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, see <http://www.gnu.org/licenses/> *
***************************************************************************/
#include "sd_stm32l4.h" #include "sd_stm32l4.h"
#include "interfaces/bsp.h" #include "interfaces/bsp.h"
...@@ -11,8 +37,6 @@ ...@@ -11,8 +37,6 @@
#include <cstring> #include <cstring>
#include <errno.h> #include <errno.h>
//Note: enabling debugging might cause deadlock when using sleep() or reboot() //Note: enabling debugging might cause deadlock when using sleep() or reboot()
//The bug won't be fixed because debugging is only useful for driver development //The bug won't be fixed because debugging is only useful for driver development
///\internal Debug macro, for normal conditions ///\internal Debug macro, for normal conditions
...@@ -29,8 +53,6 @@ void __attribute__((naked)) SDMMC1_IRQHandler() ...@@ -29,8 +53,6 @@ void __attribute__((naked)) SDMMC1_IRQHandler()
restoreContext(); restoreContext();
} }
namespace miosix { namespace miosix {
static volatile bool transferError; ///< \internal DMA or SDIO transfer error static volatile bool transferError; ///< \internal DMA or SDIO transfer error
...@@ -38,11 +60,9 @@ static Thread *waiting; ///< \internal Thread waiting for transfer ...@@ -38,11 +60,9 @@ static Thread *waiting; ///< \internal Thread waiting for transfer
static unsigned int dmaFlags; ///< \internal DMA status flags static unsigned int dmaFlags; ///< \internal DMA status flags
static unsigned int sdioFlags; ///< \internal SDIO status flags static unsigned int sdioFlags; ///< \internal SDIO status flags
/** /**
* \internal * \internal
* DMA2 Stream3 interrupt handler actual implementation * SDMMC interrupt handler interrupt handler actual implementation
*/ */
void __attribute__((used)) SDMMCirqImpl() void __attribute__((used)) SDMMCirqImpl()
{ {
...@@ -94,6 +114,13 @@ typedef Gpio<GPIOC_BASE,10> sdD2; ...@@ -94,6 +114,13 @@ typedef Gpio<GPIOC_BASE,10> sdD2;
typedef Gpio<GPIOC_BASE,11> sdD3; typedef Gpio<GPIOC_BASE,11> sdD3;
typedef Gpio<GPIOC_BASE,12> sdCLK; typedef Gpio<GPIOC_BASE,12> sdCLK;
typedef Gpio<GPIOD_BASE,2> sdCMD; typedef Gpio<GPIOD_BASE,2> sdCMD;
#ifdef _BOARD_STM32L4R9ZI_SENSORTILE
typedef Gpio<GPIOB_BASE,8> sdCLK_F;
typedef Gpio<GPIOC_BASE,6> sdDAT0_DIR;
typedef Gpio<GPIOC_BASE,7> sdDAT123_DIR;
typedef Gpio<GPIOB_BASE,9> sdCMD_DIR;
typedef Gpio<GPIOE_BASE,4> sdEN;
#endif
// //
// Class CmdResult // Class CmdResult
...@@ -502,7 +529,7 @@ private: ...@@ -502,7 +529,7 @@ private:
static const unsigned int CLKCR_FLAGS= SDMMC_CLKCR_PWRSAV; static const unsigned int CLKCR_FLAGS= SDMMC_CLKCR_PWRSAV;
#else //SD_ONE_BIT_DATABUS #else //SD_ONE_BIT_DATABUS
///\internal Clock enabled, bus width 4bit, clock powersave enabled. ///\internal Clock enabled, bus width 4bit, clock powersave enabled.
static const unsigned int CLKCR_FLAGS= //SDIO_CLKCR_CLKEN | static const unsigned int CLKCR_FLAGS=
SDMMC_CLKCR_WIDBUS_0 | SDMMC_CLKCR_PWRSAV; SDMMC_CLKCR_WIDBUS_0 | SDMMC_CLKCR_PWRSAV;
#endif //SD_ONE_BIT_DATABUS #endif //SD_ONE_BIT_DATABUS
...@@ -521,7 +548,6 @@ private: ...@@ -521,7 +548,6 @@ private:
void ClockController::calibrateClockSpeed(SDIODriver *sdio) void ClockController::calibrateClockSpeed(SDIODriver *sdio)
{ {
//During calibration we call readBlock() which will call reduceClockSpeed() //During calibration we call readBlock() which will call reduceClockSpeed()
//so not to invalidate calibration clock reduction must not be available //so not to invalidate calibration clock reduction must not be available
clockReductionAvailable=0; clockReductionAvailable=0;
...@@ -689,9 +715,7 @@ static bool multipleBlockRead(unsigned char *buffer, unsigned int nblk, ...@@ -689,9 +715,7 @@ static bool multipleBlockRead(unsigned char *buffer, unsigned int nblk,
if(cr.validateR1Response()) if(cr.validateR1Response())
{ {
//Block size 512 bytes, block data xfer, from card to controller //Block size 512 bytes, block data xfer, from card to controller
//DTMode set to 00 - Block Data Transfer (Not shown here)
SDMMC1->DCTRL=(9<<4) | SDMMC_DCTRL_DTDIR | SDMMC_DCTRL_DTEN; SDMMC1->DCTRL=(9<<4) | SDMMC_DCTRL_DTDIR | SDMMC_DCTRL_DTEN;
DBG("READ STARTED! WAITING FOR INTERRUPT...\n");
FastInterruptDisableLock dLock; FastInterruptDisableLock dLock;
while(waiting) while(waiting)
{ {
...@@ -701,11 +725,7 @@ static bool multipleBlockRead(unsigned char *buffer, unsigned int nblk, ...@@ -701,11 +725,7 @@ static bool multipleBlockRead(unsigned char *buffer, unsigned int nblk,
Thread::yield(); Thread::yield();
} }
} }
} else transferError=true;
} else {
transferError=true;
DBG("TRANSFER ERROR\n");
}
SDMMC1->DCTRL=0; //Disable data path state machine SDMMC1->DCTRL=0; //Disable data path state machine
SDMMC1->MASK=0; SDMMC1->MASK=0;
...@@ -770,6 +790,7 @@ static bool multipleBlockWrite(const unsigned char *buffer, unsigned int nblk, ...@@ -770,6 +790,7 @@ static bool multipleBlockWrite(const unsigned char *buffer, unsigned int nblk,
SDMMC_MASK_DTIMEOUTIE | //Interrupt on data timeout SDMMC_MASK_DTIMEOUTIE | //Interrupt on data timeout
SDMMC_MASK_IDMABTCIE | //Interrupt on IDMA events SDMMC_MASK_IDMABTCIE | //Interrupt on IDMA events
SDMMC_MASK_DABORTIE; SDMMC_MASK_DABORTIE;
SDMMC1->DLEN=nblk*512; SDMMC1->DLEN=nblk*512;
if(waiting==0) if(waiting==0)
{ {
...@@ -863,11 +884,10 @@ static void initSDIOPeripheral() ...@@ -863,11 +884,10 @@ static void initSDIOPeripheral()
RCC->AHB2ENR |= RCC_AHB2ENR_GPIOCEN RCC->AHB2ENR |= RCC_AHB2ENR_GPIOCEN
| RCC_AHB2ENR_GPIODEN | RCC_AHB2ENR_GPIODEN
| RCC_AHB2ENR_SDMMC1EN; | RCC_AHB2ENR_SDMMC1EN;
RCC_SYNC();
//RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; //RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN;
RCC->CCIPR |= RCC_CCIPR_CLK48SEL_1; RCC->CCIPR |= RCC_CCIPR_CLK48SEL_1;
//RCC_SYNC(); RCC_SYNC();
//RCC_SYNC();
sdD0::mode(Mode::ALTERNATE); sdD0::mode(Mode::ALTERNATE);
sdD0::alternateFunction(12); sdD0::alternateFunction(12);
#ifndef SD_ONE_BIT_DATABUS #ifndef SD_ONE_BIT_DATABUS
...@@ -882,19 +902,32 @@ static void initSDIOPeripheral() ...@@ -882,19 +902,32 @@ static void initSDIOPeripheral()
sdCLK::alternateFunction(12); sdCLK::alternateFunction(12);
sdCMD::mode(Mode::ALTERNATE); sdCMD::mode(Mode::ALTERNATE);
sdCMD::alternateFunction(12); sdCMD::alternateFunction(12);
#ifdef _BOARD_STM32L4R9ZI_SENSORTILE
sdCLK_F::mode(Mode::ALTERNATE);
sdCLK_F::alternateFunction(8);
sdDAT0_DIR::mode(Mode::ALTERNATE);
sdDAT0_DIR::alternateFunction(8);
sdDAT123_DIR::mode(Mode::ALTERNATE);
sdDAT123_DIR::alternateFunction(8);
sdCMD_DIR::mode(Mode::ALTERNATE);
sdCMD_DIR::alternateFunction(8);
sdEN::mode(Mode::OUTPUT);
sdEN::high();
#endif
} }
NVIC_SetPriority(SDMMC1_IRQn,15);//Low priority for SDIO NVIC_SetPriority(SDMMC1_IRQn,15);//Low priority for SDIO
NVIC_EnableIRQ(SDMMC1_IRQn); NVIC_EnableIRQ(SDMMC1_IRQn);
SDMMC1->POWER=0; //Power off state SDMMC1->POWER=0; //Power off state
delayUs(1); delayUs(1);
#ifdef _BOARD_STM32L4R9ZI_SENSORTILE
SDMMC1->POWER|=SDMMC_POWER_DIRPOL;
#endif
SDMMC1->CLKCR=0; SDMMC1->CLKCR=0;
SDMMC1->CMD=0; SDMMC1->CMD=0;
SDMMC1->DCTRL=0; SDMMC1->DCTRL=0;
SDMMC1->ICR=0x1fe007ff; //Interrupt //0xc007ff SDMMC1->ICR=0x1fe007ff;
SDMMC1->POWER=SDMMC_POWER_PWRCTRL_1 | SDMMC_POWER_PWRCTRL_0; //Power on state SDMMC1->POWER|=SDMMC_POWER_PWRCTRL_1 | SDMMC_POWER_PWRCTRL_0; //Power on state
DBG("\nIDMACTRL: 0x%x\n", SDMMC1->IDMACTRL);
//This delay is particularly important: when setting the POWER register a //This delay is particularly important: when setting the POWER register a
//glitch on the CMD pin happens. This glitch has a fast fall time and a slow //glitch on the CMD pin happens. This glitch has a fast fall time and a slow
//rise time resembling an RC charge with a ~6us rise time. If the clock is //rise time resembling an RC charge with a ~6us rise time. If the clock is
...@@ -996,6 +1029,9 @@ static CardType detectCardType() ...@@ -996,6 +1029,9 @@ static CardType detectCardType()
} }
} }
//
// class SDIODriver
//
intrusive_ref_ptr<SDIODriver> SDIODriver::instance() intrusive_ref_ptr<SDIODriver> SDIODriver::instance()
{ {
...@@ -1068,7 +1104,6 @@ int SDIODriver::ioctl(int cmd, void* arg) ...@@ -1068,7 +1104,6 @@ int SDIODriver::ioctl(int cmd, void* arg)
SDIODriver::SDIODriver() : Device(Device::BLOCK) SDIODriver::SDIODriver() : Device(Device::BLOCK)
{ {
initSDIOPeripheral(); initSDIOPeripheral();
// This is more important than it seems, since CMD55 requires the card's RCA // This is more important than it seems, since CMD55 requires the card's RCA
...@@ -1133,8 +1168,7 @@ SDIODriver::SDIODriver() : Device(Device::BLOCK) ...@@ -1133,8 +1168,7 @@ SDIODriver::SDIODriver() : Device(Device::BLOCK)
// possible read/write speed. This as a side effect enables 4bit bus width. // possible read/write speed. This as a side effect enables 4bit bus width.
ClockController::calibrateClockSpeed(this); ClockController::calibrateClockSpeed(this);
DBG("SDIO init: Success\n"); DBG("SDIO init: Success\n");
}
} }
} //namespace miosix
...@@ -90,7 +90,6 @@ void IRQbspInit() ...@@ -90,7 +90,6 @@ void IRQbspInit()
DefaultConsole::instance().IRQset(intrusive_ref_ptr<Device>( DefaultConsole::instance().IRQset(intrusive_ref_ptr<Device>(
new STM32Serial(defaultSerial,defaultSerialSpeed, new STM32Serial(defaultSerial,defaultSerialSpeed,
u2tx::getPin(), u2rx::getPin()))); u2tx::getPin(), u2rx::getPin())));
} }
......
...@@ -48,7 +48,7 @@ namespace miosix { ...@@ -48,7 +48,7 @@ namespace miosix {
* \internal * \internal
* used by the ledOn() and ledOff() implementation * used by the ledOn() and ledOff() implementation
*/ */
typedef Gpio<GPIOD_BASE,0> _led; typedef Gpio<GPIOF_BASE,2> _led;
inline void ledOn() inline void ledOn()
{ {
......
...@@ -68,7 +68,7 @@ const unsigned int defaultSerialSpeed = 115200; ...@@ -68,7 +68,7 @@ const unsigned int defaultSerialSpeed = 115200;
// #define SERIAL_3_DMA // #define SERIAL_3_DMA
// SD card driver // SD card driver
static const unsigned char sdVoltage = 33; // Board powered @ 3.3V static const unsigned char sdVoltage = 29; // Micro SD powered at 2.9V
// #define SD_ONE_BIT_DATABUS //All data lines are connected // #define SD_ONE_BIT_DATABUS //All data lines are connected
/// Analog supply voltage for ADC, DAC, Reset blocks, RCs and PLL /// Analog supply voltage for ADC, DAC, Reset blocks, RCs and PLL
......
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "angel.h"
#include <cstring>
namespace miosix {
__attribute__((target("thumb")))
int angel::angelswi(int num2, int param2) {
register int num asm("r0") = num2;
register int param asm("r1") = param2;
register int ret asm("r0");
asm(
"bkpt 0xAB"
: "=r" (ret)
: "r" (num), "r" (param)
: "memory"
);
return ret;
}
int angel::sys_open(const char *filename, Mode mode) {
struct {
const char *filename;
int mode;
int filename_len;
} params;
params.filename = filename;
params.mode = mode;
params.filename_len = strlen(filename);
return angelswi(SYS_OPEN, reinterpret_cast<int>(&params));
}
int angel::sys_close(int handle) {
struct {
int handle;
} params;
params.handle = handle;
return angelswi(SYS_CLOSE, reinterpret_cast<int>(&params));
}
void angel::sys_writec(char c) {
angelswi(SYS_WRITEC, reinterpret_cast<int>(&c));
}
void angel::sys_write0(const char *str) {
angelswi(SYS_WRITE0, reinterpret_cast<int>(str));
}
int angel::sys_write(int handle, const void *buf, int len) {
struct {
int handle;
const void *buf;
int len;
} params;
params.handle = handle;
params.buf = buf;
params.len = len;
return angelswi(SYS_WRITE, reinterpret_cast<int>(&params));
}
int angel::sys_read(int handle, void *buf, int len) {
struct {
int handle;
void *buf;
int len;
} params;
params.handle = handle;
params.buf = buf;
params.len = len;
return angelswi(SYS_READ, reinterpret_cast<int>(&params));
}
int angel::sys_readc() {
return angelswi(SYS_READC, 0);
}
int angel::sys_iserror(int code) {
struct {
int code;
} params;
params.code = code;
return angelswi(SYS_ISERROR, reinterpret_cast<int>(&params));
}
int angel::sys_istty(int handle) {
struct {
int handle;
} params;
params.handle = handle;
return angelswi(SYS_ISTTY, reinterpret_cast<int>(&params));
}
int angel::sys_seek(int handle, int pos) {
struct {
int handle;
int pos;
} params;
params.handle = handle;
params.pos = pos;
return angelswi(SYS_SEEK, reinterpret_cast<int>(&params));
}
int angel::sys_flen(int handle) {
struct {
int handle;
} params;
params.handle = handle;
return angelswi(SYS_FLEN, reinterpret_cast<int>(&params));
}
int angel::sys_tmpnam(char *buf, int id, int len) {
struct {
char *buf;
int id;
int len;
} params;
params.buf = buf;
params.id = id;
params.len = len;
return angelswi(SYS_TMPNAM, reinterpret_cast<int>(&params));
}
int angel::sys_remove(const char *filename) {
struct {
const char *filename;
int filename_len;
} params;
params.filename = filename;
params.filename_len = strlen(filename);
return angelswi(SYS_REMOVE, reinterpret_cast<int>(&params));
}
int angel::sys_rename(const char *old_filename, const char *new_filename) {
struct {
const char *old_filename;
int old_filename_len;
const char *new_filename;
int new_filename_len;
} params;
params.old_filename = old_filename;
params.old_filename_len = strlen(old_filename);
params.new_filename = new_filename;
params.new_filename_len = strlen(new_filename);
return angelswi(SYS_RENAME, reinterpret_cast<int>(&params));
}
int angel::sys_clock() {
return angelswi(SYS_CLOCK, 0);
}
int angel::sys_time() {
return angelswi(SYS_TIME, 0);
}
int angel::sys_system(const char *cmd) {
struct {
const char *cmd;
int cmd_len;
} params;
params.cmd = cmd;
params.cmd_len = strlen(cmd);
return angelswi(SYS_SYSTEM, reinterpret_cast<int>(&params));
}
int angel::sys_errno() {
return angelswi(SYS_ERRNO, 0);
}
int angel::sys_get_cmdline(char *buf, int *len) {
struct {
char *buf;
int len;
} params;
params.buf = buf;
params.len = *len;
int ret = angelswi(SYS_GET_CMDLINE, reinterpret_cast<int>(&params));
*len = params.len;
return ret;
}
void angel::sys_heapinfo(Heapinfo *heapinfo) {
angelswi(SYS_HEAPINFO, reinterpret_cast<int>(heapinfo));
}
void angel::sys_exit(int reason) {
angelswi(SYS_EXIT, reason);
}
void angel::sys_exit_extended(int reason, int code) {
struct {
int reason;
int code;
} params;
params.reason = reason;
params.code = code;
angelswi(SYS_EXIT_EXTENDED, reinterpret_cast<int>(&params));
}
int angel::sys_elapsed(long long *ticks) {
struct {
int low;
int high;
} params;
int ret = angelswi(SYS_ELAPSED, reinterpret_cast<int>(&params));
*ticks = (long long)params.low | ((long long) params.high << 32);
return ret;
}
int angel::sys_tickfreq() {
return angelswi(SYS_TICKFREQ, 0);
}
int angel::sys_open_stdout() {
return sys_open(":tt", MODE_W);
}
int angel::sys_open_stderr() {
return sys_open(":tt", MODE_A);
}
}
\ No newline at end of file
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#pragma once
namespace miosix {
namespace angel {
enum Mode {
MODE_R = 0,
MODE_RB = 1,
MODE_RP = 2,
MODE_RPB = 3,
MODE_W = 4,
MODE_WB = 5,
MODE_WP = 6,
MODE_WPB = 7,
MODE_A = 8,
MODE_AB = 9,
MODE_AP = 10,
MODE_APB = 11
};
enum OpNum {
SYS_OPEN = 0x01,
SYS_CLOSE = 0x02,
SYS_WRITEC = 0x03,
SYS_WRITE0 = 0x04,
SYS_WRITE = 0x05,
SYS_READ = 0x06,
SYS_READC = 0x07,
SYS_ISERROR = 0x08,
SYS_ISTTY = 0x09,
SYS_SEEK = 0x0a,
SYS_FLEN = 0x0c,
SYS_TMPNAM = 0x0d,
SYS_REMOVE = 0x0e,
SYS_RENAME = 0x0f,
SYS_CLOCK = 0x10,
SYS_TIME = 0x11,
SYS_SYSTEM = 0x12,
SYS_ERRNO = 0x13,
SYS_GET_CMDLINE = 0x15,
SYS_HEAPINFO = 0x16,
SYS_EXIT = 0x18,
SYS_EXIT_EXTENDED = 0x20,
SYS_ELAPSED = 0x30,
SYS_TICKFREQ = 0x31,
};
struct Heapinfo {
void *heap_base;
void *heap_limit;
void *stack_base;
void *stack_limit;
};
int angelswi(int num2, int param2);
int sys_open(const char *filename, Mode mode);
int sys_close(int handle);
void sys_writec(char inc);
void sys_write0(const char *str);
int sys_write(int handle, const void *buf, int len);
int sys_read(int handle, void *buf, int len);
int sys_readc();
int sys_iserror(int code);
int sys_istty(int handle);
int sys_seek(int handle, int pos);
int sys_flen(int handle);
int sys_tmpnam(char *buf, int id, int len);
int sys_remove(const char *filename);
int sys_rename(const char *old_filename, const char *new_filename);
int sys_clock();
int sys_time();
int sys_system(const char *cmd);
int sys_errno();
int sys_get_cmdline(char *buf, int *len);
void sys_heapinfo(Heapinfo *heapinfo);
void sys_exit(int reason);
void sys_exit_extended(int reason, int code);
int sys_elapsed(long long *ticks);
int sys_tickfreq();
int sys_open_stdout();
int sys_open_stderr();
}
}
\ No newline at end of file
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "angel_fs.h"
#include <sys/fcntl.h>
#include <errno.h>
#include "filesystem/stringpart.h"
#include "angel.h"
namespace miosix {
angel::Mode flagsToMode(int flags) {
// Try to map from flags to angel mode
// First, are we appending? This has high priority
if(flags & _FAPPEND)
// If yes, do we need to read?
return flags & _FREAD ? angel::MODE_APB : angel::MODE_AB;
// Second, do we need to both read and write?
if(flags & _FREAD && flags & _FWRITE)
// If yes, do we need to truncate the file?
return flags & _FTRUNC ? angel::MODE_WPB : angel::MODE_RPB;
// Finally, do we need to write?
return angel::MODE_WB;
}
class AngelFile : public FileBase {
public:
AngelFile(intrusive_ref_ptr<FilesystemBase> parent, int handle);
~AngelFile();
ssize_t write(const void *data, size_t len) override;
ssize_t read(void *data, size_t len) override;
off_t lseek(off_t pos, int whence) override;
int fstat(struct stat *pstat) const override;
int ioctl(int cmd, void *arg) override;
private:
int offset;
int handle;
};
AngelFile::AngelFile(intrusive_ref_ptr<FilesystemBase> parent, int handle) :
FileBase(parent),
offset(0),
handle(handle) {}
AngelFile::~AngelFile() {
angel::sys_close(handle);
}
ssize_t AngelFile::write(const void *data, size_t len) {
// TODO: Any way to detect errors?
int count = len - angel::sys_write(handle, data, len);
offset += count;
return count;
}
ssize_t AngelFile::read(void *data, size_t len) {
// TODO: Any way to detect errors?
int count = len - angel::sys_read(handle, data, len);
offset += count;
return count;
}
off_t AngelFile::lseek(off_t pos, int whence) {
int size = angel::sys_flen(handle);
if(size < 0)
return -EIO;
off_t new_offset;
switch(whence)
{
case SEEK_CUR:
new_offset = offset + pos;
break;
case SEEK_SET:
new_offset = pos;
break;
case SEEK_END:
new_offset = size - pos;
break;
default:
return -EINVAL;
}
if(new_offset < 0 || new_offset > size)
return -EOVERFLOW;
if(angel::sys_seek(handle, new_offset) < 0) {
return -angel::sys_errno();
} else {
return offset = new_offset;
}
}
int AngelFile::fstat(struct stat *pstat) const {
memset(pstat, 0, sizeof(struct stat));
// TODO: Maybe actually return this error?
int size = angel::sys_flen(handle);
if(size < 0)
return -EIO;
pstat->st_dev = getParent()->getFsId();
pstat->st_mode = S_IFREG | 0755; //-rwxr-xr-x
pstat->st_nlink = 1;
pstat->st_size = size;
pstat->st_blocks = (size + 511) / 512;
// This number needs to be very high because angel writes are very inefficient
pstat->st_blksize = 512;
return 0;
}
int AngelFile::ioctl(int cmd, void *arg) {
return -EINVAL;
}
AngelFs::AngelFs() {}
int AngelFs::open(intrusive_ref_ptr<FileBase>& file, StringPart &name, int flags, int mode) {
int handle = angel::sys_open(name.c_str(), flagsToMode(flags));
if(handle == -1) {
return -angel::sys_errno();
}
file = intrusive_ref_ptr<AngelFile>(new AngelFile(shared_from_this(), handle));
return 0;
}
int AngelFs::lstat(StringPart& name, struct stat *pstat) {
intrusive_ref_ptr<FileBase> file;
int ret = open(file, name, 0, 0);
if(ret != 0)
return ret;
// We only really support files
return file.get()->fstat(pstat);
}
int AngelFs::unlink(StringPart& name) {
if(angel::sys_remove(name.c_str()) == 0) {
return 0;
} else {
return -angel::sys_errno();
}
}
int AngelFs::rename(StringPart& oldName, StringPart& newName) {
if(angel::sys_rename(oldName.c_str(), newName.c_str()) == 0) {
return 0;
} else {
return -angel::sys_errno();
}
}
int AngelFs::mkdir(StringPart& name, int mode) {
// TODO: Maybe support these using angel::sys_system?
return -EACCES;
}
int AngelFs::rmdir(StringPart& name) {
// TODO: Maybe support these using angel::sys_system?
return -EACCES;
}
}
\ No newline at end of file
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#pragma once
#include "filesystem/file.h"
namespace miosix {
class AngelFs : public FilesystemBase {
public:
AngelFs();
int open(intrusive_ref_ptr<FileBase>& file, StringPart &name, int flags, int mode) override;
int lstat(StringPart& name, struct stat *pstat) override;
int unlink(StringPart& name) override;
int rename(StringPart& oldName, StringPart& newName) override;
int mkdir(StringPart& name, int mode) override;
int rmdir(StringPart& name) override;
};
}
\ No newline at end of file
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#include "angel_serial.h"
#include <termios.h>
#include "angel.h"
#include "filesystem/ioctl.h"
namespace miosix {
AngelSerial::AngelSerial(Stream stream) :
Device(DeviceType::TTY),
handle(stream == Stream::Stdout ? angel::sys_open_stdout() : angel::sys_open_stderr()) {}
AngelSerial::~AngelSerial() {
if(handle != -1) {
angel::sys_close(handle);
}
}
ssize_t AngelSerial::readBlock(void *buffer, size_t size, off_t where) {
if(handle == -1)
return -EIO;
return size - angel::sys_read(handle, buffer, size);
}
ssize_t AngelSerial::writeBlock(const void *buffer, size_t size, off_t where) {
if(handle == -1)
return -EIO;
return size - angel::sys_write(handle, buffer, size);
}
int AngelSerial::ioctl(int cmd, void *arg) {
if(reinterpret_cast<unsigned>(arg) & 0b11)
return -EFAULT; // Unaligned
termios *t = reinterpret_cast<termios*>(arg);
switch(cmd)
{
case IOCTL_SYNC:
return 0;
case IOCTL_TCGETATTR:
t->c_iflag = IGNBRK | IGNPAR;
t->c_oflag = 0;
t->c_cflag = CS8;
t->c_lflag = 0;
return 0;
case IOCTL_TCSETATTR_NOW:
case IOCTL_TCSETATTR_DRAIN:
case IOCTL_TCSETATTR_FLUSH:
// Changing things at runtime unsupported, so do nothing, but don't
// return error as console_device.h implements some attribute changes
return 0;
default:
return -ENOTTY; // Means the operation does not apply to this descriptor
}
}
}
\ No newline at end of file
/* Copyright (c) 2023 Skyward Experimental Rocketry
* Author: Davide Mor
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#pragma once
#include <filesystem/devfs/devfs.h>
namespace miosix {
class AngelSerial : public miosix::Device {
public:
enum class Stream {
Stdout,
Stderr,
};
AngelSerial(Stream stream);
~AngelSerial();
ssize_t readBlock(void *buffer, size_t size, off_t where) override;
ssize_t writeBlock(const void *buffer, size_t size, off_t where) override;
int ioctl(int cmd, void *arg) override;
private:
int handle;
};
}
\ No newline at end of file