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/skyward-boardcore
  • emilio.corigliano/skyward-boardcore
  • ettore.pane/skyward-boardcore
  • giulia.facchi/skyward-boardcore
  • valerio.flamminii/skyward-boardcore
  • nicolo.caruso/skyward-boardcore
6 results
Select Git revision
Show changes
Showing
with 0 additions and 4593 deletions
/* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 <stddef.h>
#include <cstdint>
#include <cstdio>
#include <cstring>
#include "miosix.h"
/* This class is a kind of driver to be used to excange data between the
* stormtrooper master and the other stormtrooper slave boards through the
* RS485 lines. The communication model is this: all the boards are connected
* on the same bus and each board has a unique node address. To avoid conflicts,
* the master is the only device on the bus that can initiate a communication;
* thus, to communicate with a specific slave, the master sends a packet
* containing the targeted slave address and the data and then waits for the
* response (if expected). Owing to this model, if two stormtrooper slaves need
* to exchange data they have to rely on the stormtrooper master acting as a
* router between them.
*
* The packet structure is this:
*
* +------+-----+------+-----+
* | addr | len | data | CRC |
* +------+-----+------+-----+
*
* -> addr: target node address, 8 bit
* -> len: lenght of the data field, 8 bit
* -> data: data bytes, up to 255
* -> CRC: 16 bit field calculated on addr, len and data using the ccitt CRC16
* formula
*
* On the bus data is sent using 9 bit long frames with one stop bit. If the 9th
* bit is set to 1 means that the byte received is an address byte and so a
* packet is incoming
*
*
* Here is a sample code about this class' usage:
*
* auto comm = IsbProtocol_serial2::instance();
*
* comm.setBaud(9600); //set baud to 9600 bps
* comm.setNodeAddress(0xAB); //set node ID
*
* // this to check if new data arrived and to copy the bytes into a local
* buffer
*
* uint8_t rx_buf[256];
*
* if(comm.newDataAvailable() > 0)
* {
* comm.getData(rx_buf);
* }
*
* // this to send data
*
* uint8_t tx_buf[] = "Some data for you! :)";
*
* comm.sendData(0xE0, tx_buf, sizeof(tx_buf));
*
*/
class IsbProtocol_serial2
{
public:
/**
* @return singleton intance of the class
*/
static IsbProtocol_serial2& instance();
~IsbProtocol_serial2();
/**
* Set the USART baud rate.
* @param baud baud rate to be set
*/
void setBaud(uint32_t baud);
/**
* Set the node's address in the network
*/
void setNodeAddress(uint8_t address);
/**
* @return number of payload data bytes received or 0 if none received
*/
size_t newDataAvailable();
/**
* Get the latest payload data received.
* @param buffer pointer to buffer in which copy the new data, it must have
* dimension greater than or equal to the value returned by
* newDataAvailable()
*/
void getData(uint8_t* buffer);
/**
* Send a packet, this function blocks until all data is sent
*
* @param dstAddr destination node address
* @param data pointer to a buffer containing the payload data
* @param len payload size in bytes
*/
void sendData(uint8_t dstAddr, uint8_t* data, size_t len);
/**
* Interrupt handler. DON'T CALL IT ANYWHERE!!
*/
void IRQHandler();
private:
uint8_t rxBuf[300];
struct R
{
uint16_t packetSize;
uint16_t rxIndex;
bool rxInProgress;
bool dataLenPending;
} rxStatus;
uint8_t txBuf[300];
uint8_t nodeAddress;
uint16_t CRC16(uint8_t* data, size_t len);
IsbProtocol_serial2();
IsbProtocol_serial2(const IsbProtocol_serial2& other);
IsbProtocol_serial2& operator=(const IsbProtocol_serial2& other);
bool operator==(const IsbProtocol_serial2& other);
};
/*
* Inter Stormtrooper Boards communication protocol through STM32's
* USART3 interface
*
* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 3 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.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 "IsbProtocol_serial3.h"
using namespace std;
using namespace miosix;
typedef Gpio<GPIOB_BASE, 10> u3tx;
typedef Gpio<GPIOB_BASE, 11> u3rx;
typedef Gpio<GPIOB_BASE, 14> u3rts;
void __attribute__((weak)) USART3_IRQHandler()
{
saveContext();
asm volatile("bl _Z11Serial3_Irqv");
restoreContext();
}
void __attribute__((used)) Serial3_Irq()
{
auto inst = IsbProtocol_serial3::instance();
inst.IRQHandler();
}
IsbProtocol_serial3::IsbProtocol_serial3()
{
{
FastInterruptDisableLock dLock;
RCC->APB1ENR |= RCC_APB1ENR_USART3EN;
RCC_SYNC();
u3tx::mode(Mode::ALTERNATE);
u3tx::alternateFunction(7);
#ifdef _ARCH_CORTEXM3_STM32F1
u3rx::mode(Mode::INPUT);
#else
u3rx::mode(Mode::ALTERNATE);
u3rx::alternateFunction(7);
#endif
u3rts::mode(Mode::OUTPUT);
u3rts::low();
}
/*** USART 3 configuration ***/
// Enable parity, 9 bit frame length, no parity,
// generate interrupt in case a new byte is received
USART3->CR1 |= USART_CR1_M | USART_CR1_RXNEIE | USART_CR1_TE // enable tx
| USART_CR1_RE; // enable rx
// CR2 and CR3 registers are left untouched since their default values are
// OK
NVIC_SetPriority(USART3_IRQn, 15); // Lowest priority for serial
NVIC_ClearPendingIRQ(USART3_IRQn);
NVIC_EnableIRQ(USART3_IRQn);
}
IsbProtocol_serial3::~IsbProtocol_serial3()
{
FastInterruptDisableLock dLock;
RCC->APB1ENR &= ~RCC_APB1ENR_USART3EN;
RCC_SYNC();
}
void IsbProtocol_serial3::IRQHandler()
{
if (USART3->SR & USART_SR_RXNE)
{
/* This protocol uses 9 bit long usart frames.
* The STM32's data register is 9 bit long, so the
* lower 8 bits are used to transport the data byte and
* the MSB - the 9th bit - is used to select between
* data or address byte
*/
uint16_t byte = USART->DR;
uint16_t checkMask = 0x100 | nodeAddress;
if (byte == checkMask)
{
rxStatus.rxIndex = 0;
rxStatus.rxInProgress = true;
rxStatus.dataLenPending = true;
rxBuf[rxStatus.rxIndex] = byte & 0xFF; // strip away the 9th byte
rxStatus.rxIndex++;
}
else if (rxStatus.rxInProgress)
{
if (rxStatus.dataLenPending)
{
// Second byte in the packet is the data len field. To this
// value we have to add 4 bytes: address, data len and two bytes
// of CRC
rxStatus.packetSize = (byte & 0xFF) + 4;
rxStatus.dataLenPending = false;
}
rxBuf[rxStatus.rxIndex] = byte & 0xFF;
rxStatus.rxIndex++;
if (rxStatus.rxIndex >= rxStatus.packetSize)
{
rxStatus.rxInProgress = false;
}
}
}
}
size_t IsbProtocol_serial3::newDataAvailable()
{
if ((rxStatus.rxInProgress == true) || (rxStatus.packetSize = 0))
{
return 0;
}
// we pass packetSize - 2 in order to avoid including in the CRC calculation
// the CRC value inserted from the sender
uint16_t crc = CRC16(rxBuf, rxStatus.packetSize - 2);
uint16_t pktCrc =
(rxBuf[rxStatus.packetSize - 2] << 8) | rxBuf[rxStatus.packetSize - 1];
// Packet length check: the value contained in the second byte must be
// equal to the number of bytes received minus 4
bool checkLen = (rxBuf[1] == (rxStatus.packetSize - 4)) ? true : false;
if ((crc != pktCrc) || (!checkLen))
{
rxStatus.packetSize = 0; // packet is corrupt, discard it
return 0;
}
// Return length of the data field
return rxBuf[1];
}
void IsbProtocol_serial3::getData(uint8_t* buffer)
{
std::memcpy(buffer, rxBuf[2], rxBuf[1]);
}
void IsbProtocol_serial3::sendData(uint8_t dstAddr, uint8_t* data, size_t len)
{
// packet too long
if (len > 0xFF)
{
return;
}
txBuf[0] = dstAddr;
txBuf[1] = len;
std::memcpy(txBuf[2], data, len);
// Include in CRC also address and data len field
uint16_t crc = CRC16(txBuf, len + 2);
size_t crcBegin = len + 2;
txBuf[crcBegin] = crc >> 8;
txBuf[crcBegin + 1] = crc & 0xFF;
u3rts::high();
for (size_t i = 0; i < len + 4; i++)
{
// the first byte is the address, so it has to be sent with the 9th bit
// set to 1
if (i == 0)
{
USART3->DR = txBuf[i] | 0x100;
}
else
{
USART3->DR = txBuf[i];
}
// Wait until tx buffer is empty again
while ((USART3->SR & USART_SR_TXE) == 0)
;
}
u3rts::low();
}
void IsbProtocol_serial3::setBaud(uint32_t baud)
{
uint32_t busFreq = SystemCoreClock;
#ifdef _ARCH_CORTEXM3_STM32F1
if (RCC->CFGR & RCC_CFGR_PPRE1_2)
{
busFreq /= 1 << (((RCC->CFGR >> 8) & 0x3) + 1);
}
#else
if (RCC->CFGR & RCC_CFGR_PPRE1_2)
{
busFreq /= 1 << (((RCC->CFGR >> 10) & 0x3) + 1);
}
#endif
uint32_t quot = 2 * busFreq / baud; // 2*freq for round to nearest
USART3->BRR = quot / 2 + (quot & 1);
}
void IsbProtocol_serial3::setNodeAddress(uint8_t address)
{
nodeAddress = address;
}
uint16_t IsbProtocol_serial3::CRC16(uint8_t* data, size_t len)
{
uint16_t crc = 0xFFFF;
for (size_t i = 0; i < len; i++)
{
uint16_t x = ((crc >> 8) ^ data[i]) & 0xff;
x ^= x >> 4;
crc = (crc << 8) ^ (x << 12) ^ (x << 5) ^ x;
}
return crc;
}
IsbProtocol_serial3& IsbProtocol_serial3::instance()
{
static IsbProtocol_serial3 inst;
return inst;
}
/* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 <stddef.h>
#include <cstdint>
#include <cstdio>
#include <cstring>
#include "miosix.h"
/* This class is a kind of driver to be used to excange data between the
* stormtrooper master and the other stormtrooper slave boards through the
* RS485 lines. The communication model is this: all the boards are connected
* on the same bus and each board has a unique node address. To avoid conflicts,
* the master is the only device on the bus that can initiate a communication;
* thus, to communicate with a specific slave, the master sends a packet
* containing the targeted slave address and the data and then waits for the
* response (if expected). Owing to this model, if two stormtrooper slaves need
* to exchange data they have to rely on the stormtrooper master acting as a
* router between them.
*
* The packet structure is this:
*
* +------+-----+------+-----+
* | addr | len | data | CRC |
* +------+-----+------+-----+
*
* -> addr: target node address, 8 bit
* -> len: lenght of the data field, 8 bit
* -> data: data bytes, up to 255
* -> CRC: 16 bit field calculated on addr, len and data using the ccitt CRC16
* formula
*
* On the bus data is sent using 9 bit long frames with one stop bit. If the 9th
* bit is set to 1 means that the byte received is an address byte and so a
* packet is incoming
*
*
* Here is a sample code about this class' usage:
*
* auto comm = IsbProtocol_serial2::instance();
*
* comm.setBaud(9600); //set baud to 9600 bps
* comm.setNodeAddress(0xAB); //set node ID
*
* // this to check if new data arrived and to copy the bytes into a local
* buffer
*
* uint8_t rx_buf[256];
*
* if(comm.newDataAvailable() > 0)
* {
* comm.getData(rx_buf);
* }
*
* // this to send data
*
* uint8_t tx_buf[] = "Some data for you! :)";
*
* comm.sendData(0xE0, tx_buf, sizeof(tx_buf));
*
*/
class IsbProtocol_serial3
{
public:
/**
* @return singleton intance of the class
*/
static IsbProtocol_serial3& instance();
~IsbProtocol_serial3();
/**
* Set the USART baud rate.
* @param baud baud rate to be set
*/
void setBaud(uint32_t baud);
/**
* Set the node's address in the network
*/
void setNodeAddress(uint8_t address);
/**
* @return number of payload data bytes received or 0 if none received
*/
size_t newDataAvailable();
/**
* Get the latest payload data received.
* @param buffer pointer to buffer in which copy the new data, it must have
* dimension greater than or equal to the value returned by
* newDataAvailable()
*/
void getData(uint8_t* buffer);
/**
* Send a packet, this function blocks until all data is sent
*
* @param dstAddr destination node address
* @param data pointer to a buffer containing the payload data
* @param len payload size in bytes
*/
void sendData(uint8_t dstAddr, uint8_t* data, size_t len);
/**
* Interrupt handler. DON'T CALL IT ANYWHERE!!
*/
void IRQHandler();
private:
uint8_t rxBuf[300];
struct R
{
uint16_t packetSize;
uint16_t rxIndex;
bool rxInProgress;
bool dataLenPending;
} rxStatus;
uint8_t txBuf[300];
uint8_t nodeAddress;
uint16_t CRC16(uint8_t* data, size_t len);
IsbProtocol_serial3();
IsbProtocol_serial3(const IsbProtocol_serial3& other);
IsbProtocol_serial3& operator=(const IsbProtocol_serial3& other);
bool operator==(const IsbProtocol_serial3& other);
};
/* Copyright (c) 2016-2017 Skyward Experimental Rocketry
* Authors: Alain Carlucci, Federico Terraneo
*
* 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 "Leds.h"
// Relying on the BSP to provide leds and configure them as output
#define LED(x) miosix::leds::led##x::getPin()
std::array<miosix::GpioPin, Leds::numLeds> Leds::pins{
{LED(0), LED(1), LED(2), LED(3), LED(4), LED(5), LED(6), LED(7), LED(8),
LED(9)}};
#undef LED
/* Copyright (c) 2016-2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 "PacketBuffer.h"
#include <utils/Debug.h>
using namespace std;
using namespace miosix;
PacketBuffer::PacketBuffer(size_t storageSize)
: storageSize(storageSize), usedSize(0), writeIndex(0), readIndex(0),
valid(true)
{
#ifndef __NO_EXCEPTIONS
try
{
buffer = new uint8_t[storageSize];
}
catch (std::bad_alloc& exc)
{
TRACE("bad alloc!\n");
valid = false;
}
#else
buffer = new (std::nothrow) uint8_t[storageSize];
if (buffer == nullptr)
{
valid = false;
}
#endif
}
PacketBuffer::~PacketBuffer()
{
if (valid)
delete[] buffer;
}
bool PacketBuffer::push(packet_header_t& header, const uint8_t* payload)
{
if (!valid)
return false;
size_t packetSize = sizeof(packet_header_t) + header.payloadSize;
// Simple technique to avoid ring buffer writeIndex slip ahead readIndex:
// we keep track of the amount of space used and we reject a new incoming
// packet if usedSize + packetSize is greater that the ring buffer size.
if (usedSize + packetSize >= storageSize)
return false;
// to store the packet into the ring buffer first copy the header
// and then copy the payload
{
Lock<FastMutex> l(mutex);
uint8_t* head = reinterpret_cast<uint8_t*>(&header);
for (unsigned int i = 0; i < sizeof(packet_header_t); i++)
{
buffer[(writeIndex + i) % storageSize] = head[i];
}
writeIndex = (writeIndex + sizeof(packet_header_t)) % storageSize;
for (unsigned int i = 0; i < header.payloadSize; i++)
{
buffer[(writeIndex + i) % storageSize] = payload[i];
}
writeIndex = (writeIndex + header.payloadSize) % storageSize;
usedSize += packetSize;
}
return true;
}
packet_header_t PacketBuffer::getHeader()
{
packet_header_t header = {};
uint8_t* dest = reinterpret_cast<uint8_t*>(&header);
memset(dest, 0x00, sizeof(packet_header_t));
if (valid)
{
Lock<FastMutex> l(mutex);
for (unsigned int i = 0; i < sizeof(packet_header_t); i++)
dest[i] = buffer[(readIndex + i) % storageSize];
}
return header;
}
void PacketBuffer::getData(uint8_t* data)
{
if (!valid)
return;
/* Packet size is stored in header, so first get the payloadSize.
* The data is stored sizeof(packet_header_t) bytes next the read pointer,
* since a packet is stored as header followed by payload, so we have to
* add sizeof(packet_header_t) to the read pointer to reach the first data
* byte
*/
packet_header_t frontHead = getHeader();
{
Lock<FastMutex> l(mutex);
int start = readIndex + sizeof(packet_header_t);
for (unsigned int i = 0; i < frontHead.payloadSize; i++)
{
data[i] = buffer[(start + i) % storageSize];
}
}
}
void PacketBuffer::popFront()
{
if ((!valid) || empty()) // this means that list is empty
return;
/* Popping a packet out of list simply means move the readIndex forward
* of the size of the packet at list's head.
* The size of a packet is made of two parts: a fixed one which is
* constituded by the size of IP address, port and packet length fields
* and a variable one that is the size of the payload. The latter is stored
* into the len field of the packet.
* What we do here is gather the fixed and variable sizes and sum them
* together to obtain the readIndex's needed increment
*/
packet_header_t head = getHeader();
size_t packetSize = sizeof(packet_header_t) + head.payloadSize;
{
Lock<FastMutex> l(mutex);
readIndex = (readIndex + packetSize) % storageSize;
usedSize -= packetSize;
}
}
bool PacketBuffer::empty()
{
Lock<FastMutex> l(mutex);
return usedSize == 0;
}
/* Copyright (c) 2016-2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 "UdpManager.h"
using namespace std;
using namespace miosix;
void __attribute__((naked)) EXTI1_IRQHandler()
{
saveContext();
asm volatile("bl _Z13EXTIrqHandlerv");
restoreContext();
}
void __attribute__((used)) EXTIrqHandler()
{
EXTI->PR |= EXTI_PR_PR1;
Singleton<UdpManager>::getInstance().phyIrqHandler();
}
void _evt_mgmt_thread(void* args)
{
Singleton<UdpManager>::getInstance().evtQueue.run();
}
UdpManager::UdpManager()
{
eth::int1::mode(Mode::INPUT);
// Configure STM32 to generate an interrupt on
// falling edge of chip's INT line
{
FastInterruptDisableLock dLock;
RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN;
RCC_SYNC();
}
SYSCFG->EXTICR[0] |= SYSCFG_EXTICR1_EXTI1_PC;
EXTI->IMR |= EXTI_IMR_MR1;
EXTI->FTSR |= EXTI_FTSR_TR1;
NVIC_SetPriority(EXTI1_IRQn, 10);
NVIC_ClearPendingIRQ(EXTI1_IRQn);
NVIC_EnableIRQ(EXTI1_IRQn);
phy.setModeReg(0x00);
phy.setSocketInterruptMask(0xFF);
txBuffer = new PacketBuffer(TX_BUF_SIZE);
rxBuffer = new PacketBuffer(RX_BUF_SIZE);
wdt->setDuration(TX_TIMEOUT);
wdt->setCallback(bind(&UdpManager::wdtIrqHandler, this));
if (!txBuffer->isValid() || !rxBuffer->isValid())
{
// TODO log!
}
else
{
Thread::create(_evt_mgmt_thread, 1024);
}
}
UdpManager::~UdpManager()
{
delete txBuffer;
delete rxBuffer;
}
void UdpManager::setTxPort(uint16_t port)
{
// Open transmitting socket
phy.setSocketModeReg(PHY_TX_SOCK_NUM, SOCKn_MR_UDP);
phy.setSocketSourcePort(PHY_TX_SOCK_NUM, port);
// Enable timeout & send ok interrupts
phy.setSocketInterruptMaskReg(PHY_TX_SOCK_NUM, 0x18);
phy.setSocketCommandReg(PHY_TX_SOCK_NUM, SOCKn_CR_OPEN);
}
void UdpManager::setRxPort(uint16_t port)
{
// Open receiving socket
phy.setSocketModeReg(PHY_RX_SOCK_NUM, SOCKn_MR_UDP);
phy.setSocketSourcePort(PHY_RX_SOCK_NUM, port);
// Enable recv interrupt only
phy.setSocketInterruptMaskReg(PHY_RX_SOCK_NUM, 0x04);
phy.setSocketCommandReg(PHY_RX_SOCK_NUM, SOCKn_CR_OPEN);
phy.setSocketCommandReg(PHY_RX_SOCK_NUM, SOCKn_CR_RECV);
}
/** Legacy code, uncomment if we want tx @ port and rx @ port+1 **/
// void UdpManager::setPort(uint16_t port) {
//
// //Open transmitting socket
// phy.setSocketModeReg(PHY_TX_SOCK_NUM,SOCKn_MR_UDP);
// phy.setSocketSourcePort(PHY_TX_SOCK_NUM,port);
// // Enable timeout & send ok interrupts
// phy.setSocketInterruptMaskReg(PHY_TX_SOCK_NUM,0x18);
// phy.setSocketCommandReg(PHY_TX_SOCK_NUM,SOCKn_CR_OPEN);
//
// //Open receiving socket
// phy.setSocketModeReg(PHY_RX_SOCK_NUM,SOCKn_MR_UDP);
// phy.setSocketSourcePort(PHY_RX_SOCK_NUM,port+1);
// // Enable recv interrupt only
// phy.setSocketInterruptMaskReg(PHY_RX_SOCK_NUM,0x04);
// phy.setSocketCommandReg(PHY_RX_SOCK_NUM,SOCKn_CR_OPEN);
// phy.setSocketCommandReg(PHY_RX_SOCK_NUM,SOCKn_CR_RECV);
// }
bool UdpManager::newReceivedPackets() { return !rxBuffer->empty(); }
void UdpManager::sendPacketTo(const uint8_t* ip, const uint16_t port,
const void* data, size_t len)
{
packet_header_t header;
header.ipAddress = *(reinterpret_cast<const uint32_t*>(ip));
header.port = port;
header.payloadSize = len;
bool wasEmpty = txBuffer->empty();
bool ok = txBuffer->push(header, reinterpret_cast<const uint8_t*>(data));
if (!ok)
{
// TODO: better failure logging
puts("UDP->sendPacketTo: failed to enqueue the new packet\n");
}
else if (wasEmpty)
{
bool pok =
evtQueue.postNonBlocking(bind(&UdpManager::tx_handler, this));
if (!pok)
{
// TODO: better failure logging
puts(
"UDP->sendPacketTo: job queue full."
"Failed to post tx_handler.\n");
}
}
}
size_t UdpManager::recvPacketSize()
{
if (rxBuffer->empty())
return 0;
packet_header_t hdr = rxBuffer->getHeader();
return hdr.payloadSize;
}
void UdpManager::readPacket(uint8_t* ip, uint16_t& port, void* data)
{
packet_header_t header = rxBuffer->getHeader();
// IP address is 4 bytes long
memcpy(ip, reinterpret_cast<uint8_t*>(&(header.ipAddress)), 4);
port = header.port;
// The copy of the exact number of bytes is guaranteed by getData. We only
// have to be sure that the receiving buffer has the right capacity,
// which is given by UdpManager::recvPacketSize()
rxBuffer->getData(reinterpret_cast<uint8_t*>(data));
rxBuffer->popFront();
}
/** Interrupt and event handlers **/
void UdpManager::phyIrqHandler()
{
bool hppw = false;
uint8_t sockInt = phy.readSocketInterruptReg();
// TX socket interrupts management
if (sockInt & (0x01 << PHY_TX_SOCK_NUM))
{
// Stopping watchdog inside an IRQ is safe to do
wdt->stop();
uint8_t txFlags = phy.getSocketInterruptReg(PHY_TX_SOCK_NUM);
phy.clearSocketInterruptReg(PHY_TX_SOCK_NUM);
// Send OK interrupt flag set
if (txFlags & 0x10)
evtQueue.IRQpost(bind(&UdpManager::tx_end_handler, this), hppw);
// Timeout flag set, problems with ARP
if (txFlags & 0x08)
evtQueue.IRQpost(bind(&UdpManager::timeout_handler, this), hppw);
}
// RX socket interrupts management
if (sockInt & (0x01 << PHY_RX_SOCK_NUM))
{
uint8_t rxFlags = phy.getSocketInterruptReg(PHY_RX_SOCK_NUM);
phy.clearSocketInterruptReg(PHY_RX_SOCK_NUM);
if (rxFlags & 0x04)
evtQueue.IRQpost(bind(&UdpManager::rx_handler, this), hppw);
}
if (hppw)
Scheduler::IRQfindNextThread();
}
void UdpManager::wdtIrqHandler()
{
bool hppw = false;
evtQueue.IRQpost(bind(&UdpManager::timeout_handler, this), hppw);
if (hppw)
Scheduler::IRQfindNextThread();
}
void UdpManager::tx_handler()
{
if (txBuffer->empty())
return;
packet_header_t header = txBuffer->getHeader();
uint8_t* addr = reinterpret_cast<uint8_t*>(&header.ipAddress);
uint8_t payload[header.payloadSize];
txBuffer->getData(payload);
txBuffer->popFront();
phy.setSocketDestIp(PHY_TX_SOCK_NUM, addr);
phy.setSocketDestPort(PHY_TX_SOCK_NUM, header.port);
phy.writeData(PHY_TX_SOCK_NUM, payload, header.payloadSize);
phy.setSocketCommandReg(PHY_TX_SOCK_NUM, SOCKn_CR_SEND);
wdt->clear();
wdt->start();
}
void UdpManager::tx_end_handler()
{
if (txBuffer->empty())
return;
bool ok = evtQueue.postNonBlocking(bind(&UdpManager::tx_handler, this));
if (!ok)
{
// TODO: better failure logging
puts("UDP->tx_end_handler:job queue full, failed to post tx_handler");
}
}
void UdpManager::timeout_handler()
{
if (wdt->expired())
puts("Tx timeout due to watchdog expiration");
else
puts("Tx timeout due to phy error");
bool ok = evtQueue.postNonBlocking(bind(&UdpManager::tx_end_handler, this));
if (!ok)
puts(
"UDP->timeout_handler: job queue full, "
"failed to post tx_end_handler");
}
void UdpManager::rx_handler()
{
// get new packet len, in bytes
uint16_t len = phy.getReceivedSize(PHY_RX_SOCK_NUM);
uint8_t buffer[len];
// read all the packet, that is made of so30urceIp + sourcePort +
// payload len + payload. Since the header length is of 8 bytes,
// the payload length is len - 8 bytes! :-)
phy.readData(PHY_RX_SOCK_NUM, buffer, len);
// Set back to listening mode
phy.setSocketCommandReg(PHY_RX_SOCK_NUM, SOCKn_CR_RECV);
packet_header_t header;
memcpy(reinterpret_cast<uint8_t*>(&(header.ipAddress)), buffer, 4);
header.port = (buffer[4] << 8) | buffer[5];
header.payloadSize = len - 8;
bool pushOk = rxBuffer->push(header, &buffer[8]);
if (!pushOk)
puts(
"rx_handler error: rxBuffer is full,"
"cannot enqueue a new packet!");
}
/* Copyright (c) 2016-2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 <Common.h>
#include <Singleton.h>
#include <W5200/w5200.h>
#include <e20/e20.h>
#include "PacketBuffer.h"
#include "WatchdogTimer.h"
class UdpManager : Singleton<UdpManager>
{
friend class Singleton<UdpManager>;
public:
/**
* Open a transmitting UDP socket which source port is @param port
*/
void setTxPort(uint16_t port);
/**
* Open a receiving UDP socket that will listen on @param port, listening
* starts as soon as this function is called
*/
void setRxPort(uint16_t port);
/**
* Send an UDP packet.
* @param ip: destination IP address
* @param port: destination port
* @param data: pointer to payload data
* @param len: payload lenght in bytes
*/
void sendPacketTo(const uint8_t* ip, const uint16_t port, const void* data,
size_t len);
/**
* @return true if there are new packets in the rx buffer
*/
bool newReceivedPackets();
/**
* @return payload size of the packet stored at the head of the internal
* buffer, in other words the packet that will be read if readPacket() is
* called.
*/
size_t recvPacketSize();
/**
* Read the packet placed at rx buffer's head popping it out of the queue.
* @param ip: source ip address
* @param port: source port
* @param data: pointer to a buffer in which store the payload data. It must
* have a size greater than or equal to that returned by recvPacketSize()
*/
void readPacket(uint8_t* ip, uint16_t& port, void* data);
/**
* IRQ handler for interrupts coming from the phy interface chip
* WARNING: DON'T call this!!
*/
void phyIrqHandler();
/**
* IRQ handler for interrupts coming from the tx watchdog timer
* WARNING: DON'T call this!!
*/
void wdtIrqHandler();
private:
// TX timeout time, in ms
static constexpr unsigned int TX_TIMEOUT = 500; // 500ms timeout
// Size of the event queue, used for event handling
static constexpr unsigned int EVT_QUEUE_SIZE = 20;
// Size of buffer used to store packets still to be sent, IN BYTES
static constexpr unsigned int TX_BUF_SIZE = 100000;
// Size of buffer used to store packets received, IN BYTES
static constexpr unsigned int RX_BUF_SIZE = 100000;
// TX and RX socket number, used by the phy interface
static constexpr uint8_t PHY_TX_SOCK_NUM = 0;
static constexpr uint8_t PHY_RX_SOCK_NUM = 1;
miosix::FixedEventQueue<EVT_QUEUE_SIZE> evtQueue;
PacketBuffer* txBuffer;
PacketBuffer* rxBuffer;
W5200& phy = W5200::instance();
WatchdogTimer* wdt = Singleton<WatchdogTimer>::getInstance();
// Function used by the event management thread
friend void _evt_mgmt_thread(void* args);
void tx_handler(); //< Tx event handler function
void tx_end_handler(); //< Tx end event handler function
void rx_handler(); //< New packet Rx handler function
void timeout_handler(); //< Tx timeout handler function
UdpManager();
UdpManager(const UdpManager& other);
UdpManager& operator=(const UdpManager& other);
~UdpManager();
};
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
/* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 "Common.h"
namespace modbus
{
static constexpr uint8_t EXC_ILLEGAL_FUN = 0x01; ///< Illegal function
static constexpr uint8_t EXC_ILLEGAL_ADDR = 0x02; ///< Illegal data address
static constexpr uint8_t EXC_ILLEGAL_VAL = 0x03; ///< Illegal data value
static constexpr uint8_t EXC_SLAVE_FAILURE = 0x04; ///< Slave internal failure
static constexpr uint8_t ACKNOWLEDGE = 0x05; ///< Acknowledge
static constexpr uint8_t SLAVE_BUSY = 0x06; ///< Slave busy
static constexpr uint8_t EXC_MEM_PARITY = 0x08; ///< Memory parity error
} // namespace modbus
/* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 <slave/SlaveEngine.h>
#include <slave/SlaveInterface.h>
#include "ExceptionCodes.h"
#include "PDU.h"
/* Copyright (c) 2017 Skyward Experimental Rocketry
* Author: Silvano Seva
*
* 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 <interfaces/endianness.h>
#include <memory>
#include "../HooksInterface.h"
#include "../PDU.h"
#include "Common.h"
class SlaveEngine
{
public:
/**
* Creates an instance of the engine
* @param hook pointer to an instance of a HooksInterface class, if not
* provided the SlaveEngine will use a default instance of HooksInterface
* class.
* The instance pointed by @param hook will be deleted when the destructor
* of SlaveEngine is called
*/
explicit SlaveEngine(HooksInterface* hook = nullptr);
~SlaveEngine();
/**
* Process a request received from the master.
* @param request PDU that contains the master's request
* @return a PDU with the either the response or the exception message
*/
std::unique_ptr<PDU> ProcessRequest(std::unique_ptr<PDU> request);
private:
HooksInterface* handlers; ///< pointer to the handlers' class
// Helper functions, one for each function code supported
PDU* DoReadCoils(uint8_t* data);
PDU* DoWriteCoil(uint8_t* data);
PDU* DoWriteMultipleCoils(uint8_t* data);
PDU* DoReadRegisters(uint8_t* data);
PDU* DoWriteRegister(uint8_t* data);
PDU* DoWriteMultipleRegisters(uint8_t* data);
// Unsupported functions
SlaveEngine(const SlaveEngine& other) = delete;
SlaveEngine& operator=(const SlaveEngine& other) = delete;
bool operator==(const SlaveEngine& other) = delete;
};