newcode
parent
5e699fc082
commit
b47e101b33
@ -0,0 +1,39 @@
|
|||||||
|
#include "fifo.h"
|
||||||
|
|
||||||
|
uint8_t fifo_push(Fifo_t * fifo, uint8_t byte)
|
||||||
|
{
|
||||||
|
//if (fifo.write >= FIFO_SIZE)
|
||||||
|
// fifo.write = 0; // erhöht sicherheit
|
||||||
|
|
||||||
|
|
||||||
|
if ( ( fifo->write + 1 == fifo->read ) ||
|
||||||
|
( fifo->read == 0 && fifo->write + 1 == FIFO_SIZE ) )
|
||||||
|
return FIFO_FAIL; // voll
|
||||||
|
|
||||||
|
fifo->data[fifo->write] = byte;
|
||||||
|
|
||||||
|
fifo->write++;
|
||||||
|
if (fifo->write >= FIFO_SIZE)
|
||||||
|
fifo->write = 0;
|
||||||
|
|
||||||
|
return FIFO_SUCCESS;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t fifo_pop(Fifo_t * fifo, uint8_t *pByte)
|
||||||
|
{
|
||||||
|
if (fifo->read == fifo->write){
|
||||||
|
return FIFO_FAIL;
|
||||||
|
}
|
||||||
|
|
||||||
|
*pByte = fifo->data[fifo->read];
|
||||||
|
|
||||||
|
fifo->read++;
|
||||||
|
if (fifo->read >= FIFO_SIZE)
|
||||||
|
fifo->read = 0;
|
||||||
|
|
||||||
|
return FIFO_SUCCESS;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t fifo_peek(Fifo_t * fifo){
|
||||||
|
return fifo->data[fifo->read];
|
||||||
|
}
|
||||||
@ -0,0 +1,20 @@
|
|||||||
|
#ifndef _FIFO_H_
|
||||||
|
#define _FIFO_H_
|
||||||
|
|
||||||
|
#include <avr/io.h>
|
||||||
|
|
||||||
|
#define FIFO_FAIL 0
|
||||||
|
#define FIFO_SUCCESS 1
|
||||||
|
|
||||||
|
#define FIFO_SIZE 128
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
uint8_t data[FIFO_SIZE];
|
||||||
|
uint8_t read; // zeigt auf das Feld mit dem ältesten Inhalt
|
||||||
|
uint8_t write; // zeigt immer auf leeres Feld
|
||||||
|
} Fifo_t;
|
||||||
|
|
||||||
|
uint8_t fifo_push(Fifo_t * fifo, uint8_t byte);
|
||||||
|
uint8_t fifo_pop(Fifo_t * fifo, uint8_t *pByte);
|
||||||
|
|
||||||
|
#endif
|
||||||
@ -0,0 +1,45 @@
|
|||||||
|
#include <avr/io.h>
|
||||||
|
#include <util/delay.h>
|
||||||
|
#include "uart.h"
|
||||||
|
#include <avr/interrupt.h>
|
||||||
|
|
||||||
|
void init_clk(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
// ========= System Clock configuration =========
|
||||||
|
// Set to external 16Mhz crystal, using the PLL at *2
|
||||||
|
// set it to be a 12-16Mhz crystal with a slow start-up time.
|
||||||
|
OSC.XOSCCTRL = OSC_FRQRANGE_2TO9_gc | OSC_XOSCSEL_XTAL_16KCLK_gc ;
|
||||||
|
OSC.CTRL |= OSC_XOSCEN_bm ; // enable it
|
||||||
|
while( (OSC.STATUS & OSC_XOSCRDY_bm) == 0 ){} // wait until it's stable
|
||||||
|
|
||||||
|
// The external crystal is now running and stable.
|
||||||
|
// (Note that it's not yet selected as the clock source)
|
||||||
|
// Now configure the PLL to be eXternal oscillator * 2
|
||||||
|
OSC.PLLCTRL = OSC_PLLSRC_XOSC_gc | 2;
|
||||||
|
|
||||||
|
// now enable the PLL...
|
||||||
|
OSC.CTRL |= OSC_PLLEN_bm ; // enable the PLL...
|
||||||
|
while( (OSC.STATUS & OSC_PLLRDY_bm) == 0 ){} // wait until it's stable
|
||||||
|
|
||||||
|
// And now, *finally*, we can switch from the internal 2Mhz clock to the PLL
|
||||||
|
CCP = CCP_IOREG_gc; // protected write follows
|
||||||
|
CLK.CTRL = CLK_SCLKSEL_PLL_gc; // The System clock is now PLL (16Mhz * 2)
|
||||||
|
// ==============================================
|
||||||
|
}
|
||||||
|
|
||||||
|
int main(void){
|
||||||
|
init_clk();
|
||||||
|
init_uart();
|
||||||
|
PORTD.DIRSET = 1 << 5;
|
||||||
|
sei();
|
||||||
|
|
||||||
|
for(;;){
|
||||||
|
char tmp = USARTD0.DATA;
|
||||||
|
if(!tmp)
|
||||||
|
tmp='a';
|
||||||
|
USARTD0.DATA = tmp;
|
||||||
|
PORTD.OUTTGL = 1 << 5;
|
||||||
|
_delay_ms(1000);
|
||||||
|
}
|
||||||
|
}
|
||||||
@ -0,0 +1,40 @@
|
|||||||
|
TARGET = main.elf
|
||||||
|
FILES = main fifo uart yaMBSiavr
|
||||||
|
MCU = atxmega32a4
|
||||||
|
PROGC = x32a4
|
||||||
|
CC = avr-gcc
|
||||||
|
TOOL = atmelice_pdi
|
||||||
|
|
||||||
|
BUILDDIR = build
|
||||||
|
|
||||||
|
DEFINES = -DF_CPU=32000000UL
|
||||||
|
|
||||||
|
CFLAGS =-mmcu=$(MCU) -O2 -Wall $(DEFINES) -std=c99 -ffunction-sections -fdata-sections
|
||||||
|
LDFLAGS =-mmcu=$(MCU) -Wl,--gc-sections
|
||||||
|
|
||||||
|
LDFILES = $(foreach FILE,$(FILES),$(BUILDDIR)/$(FILE).o)
|
||||||
|
|
||||||
|
all: clean $(BUILDDIR)/$(TARGET).elf
|
||||||
|
|
||||||
|
$(BUILDDIR)/%.o: %.c
|
||||||
|
@mkdir -p $(BUILDDIR)
|
||||||
|
$(CC) $(CFLAGS) -c $< -o $(BUILDDIR)/$*.o
|
||||||
|
|
||||||
|
$(BUILDDIR)/$(TARGET).elf: $(LDFILES)
|
||||||
|
mkdir -p $(BUILDDIR)
|
||||||
|
$(CC) $(LDFLAGS) $(LDFILES) -o $(BUILDDIR)/$(TARGET).elf
|
||||||
|
|
||||||
|
$(BUILDDIR)/$(TARGET).hex : $(BUILDDIR)/$(TARGET).elf
|
||||||
|
avr-objcopy -j .data -j .text -O ihex $< $@
|
||||||
|
|
||||||
|
fuse:
|
||||||
|
avrdude -p $(PROGC) -c $(TOOL) -U lfuse:w:0xE8:m -U hfuse:w:0xD1:m
|
||||||
|
|
||||||
|
load: $(BUILDDIR)/$(TARGET).hex
|
||||||
|
avrdude -p $(PROGC) -c $(TOOL) -U flash:w:$(BUILDDIR)/$(TARGET).hex -v -B 2
|
||||||
|
|
||||||
|
size: $(BUILDDIR)/$(TARGET).elf
|
||||||
|
avr-size -C --mcu=$(MCU) $(BUILDDIR)/$(TARGET).elf
|
||||||
|
|
||||||
|
clean:
|
||||||
|
rm -rf $(BUILDDIR)
|
||||||
@ -0,0 +1,72 @@
|
|||||||
|
#include <avr/interrupt.h>
|
||||||
|
#include "uart.h"
|
||||||
|
#include "fifo.h"
|
||||||
|
|
||||||
|
Fifo_t uart0_rx_buffer = {{}, 0, 0};
|
||||||
|
Fifo_t uart0_tx_buffer = {{}, 0, 0};
|
||||||
|
|
||||||
|
const uint16_t bsel = 208;
|
||||||
|
const int8_t bscale = 0;
|
||||||
|
|
||||||
|
//FILE uart_output = FDEV_SETUP_STREAM(uart_putchar, NULL, _FDEV_SETUP_WRITE);
|
||||||
|
|
||||||
|
void init_uart(void){
|
||||||
|
USARTD0_CTRLC= USART_CHSIZE0_bm | USART_CHSIZE1_bm;
|
||||||
|
//USARTD0_BAUDCTRLB = 0;
|
||||||
|
//USARTD0_BAUDCTRLA = 0;
|
||||||
|
USARTD0.BAUDCTRLA = bsel;
|
||||||
|
USARTD0.BAUDCTRLB = 0 | (bsel >> 8) | (bscale << USART_BSCALE0_bp);
|
||||||
|
USARTD0_CTRLB = USART_TXEN_bm | USART_RXEN_bm;
|
||||||
|
|
||||||
|
//USARTD0_CTRLA=USART_RXCINTLVL0_bm;
|
||||||
|
|
||||||
|
PORTD_OUTSET = PIN3_bm;
|
||||||
|
PORTD_DIRSET = PIN3_bm;
|
||||||
|
PORTD_OUTCLR = PIN2_bm;
|
||||||
|
PORTD_DIRCLR = PIN2_bm;
|
||||||
|
|
||||||
|
//stdout = &uart_output;
|
||||||
|
}
|
||||||
|
|
||||||
|
void uart_putchar(char c, FILE *stream)
|
||||||
|
{
|
||||||
|
fifo_push(&uart0_tx_buffer, c);
|
||||||
|
USARTD0_CTRLA |= USART_DREINTLVL_LO_gc;
|
||||||
|
}
|
||||||
|
|
||||||
|
//void puts(char * s){
|
||||||
|
// while (*s) {
|
||||||
|
// putchar(*s++);
|
||||||
|
// }
|
||||||
|
//}
|
||||||
|
|
||||||
|
char get_uart0_char(void)
|
||||||
|
{
|
||||||
|
while(1){
|
||||||
|
char buffer;
|
||||||
|
|
||||||
|
while( !(USARTD0_STATUS & USART_RXCIF_bm) );
|
||||||
|
buffer=USARTD0_DATA;
|
||||||
|
if ((USARTD0_STATUS & (USART_FERR_bm | USART_PERR_bm | USART_BUFOVF_bm))==0)
|
||||||
|
return buffer;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ISR(USARTD0_RXC_vect)
|
||||||
|
{
|
||||||
|
uint8_t tmp = get_uart0_char();
|
||||||
|
putchar(tmp);
|
||||||
|
if(( tmp == 0x0D || tmp == 0x0A))
|
||||||
|
printf("wurst\n\r");
|
||||||
|
else
|
||||||
|
fifo_push(&uart0_rx_buffer, tmp);
|
||||||
|
}
|
||||||
|
|
||||||
|
ISR(USARTD0_DRE_vect){
|
||||||
|
uint8_t tmp;
|
||||||
|
if(fifo_pop(&uart0_tx_buffer, &tmp) == FIFO_SUCCESS){
|
||||||
|
USARTD0_DATA = tmp;
|
||||||
|
} else {
|
||||||
|
USARTD0_CTRLA &= ~USART_DREINTLVL_LO_gc;
|
||||||
|
}
|
||||||
|
}
|
||||||
@ -0,0 +1,15 @@
|
|||||||
|
#ifndef _UART_H_
|
||||||
|
#define _UART_H_
|
||||||
|
|
||||||
|
#include <stdio.h>
|
||||||
|
#include "fifo.h"
|
||||||
|
|
||||||
|
extern Fifo_t uart0_rx_buffer;
|
||||||
|
extern Fifo_t uart0_tx_buffer;
|
||||||
|
|
||||||
|
|
||||||
|
void init_uart(void);
|
||||||
|
void uart_putchar(char c, FILE *stream);
|
||||||
|
char get_uart0_char(void);
|
||||||
|
|
||||||
|
#endif
|
||||||
@ -0,0 +1,413 @@
|
|||||||
|
/*************************************************************************
|
||||||
|
Title: Yet another (small) modbus (server) implementation for the avr.
|
||||||
|
Author: Max Brueggemann
|
||||||
|
Hardware: any AVR with hardware UART, tested on Atmega 88/168 at 20Mhz
|
||||||
|
License: BSD-3-Clause
|
||||||
|
|
||||||
|
DESCRIPTION:
|
||||||
|
Refer to the header file yaMBSiavr.h.
|
||||||
|
|
||||||
|
USAGE:
|
||||||
|
Refer to the header file yaMBSiavr.h.
|
||||||
|
|
||||||
|
LICENSE:
|
||||||
|
|
||||||
|
Copyright 2017 Max Brueggemann, www.maxbrueggemann.de
|
||||||
|
|
||||||
|
Redistribution and use in source and binary forms, with or without
|
||||||
|
modification, are permitted provided that the following conditions are met:
|
||||||
|
|
||||||
|
1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
this list of conditions and the following disclaimer.
|
||||||
|
|
||||||
|
2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
this list of conditions and the following disclaimer in the documentation
|
||||||
|
and/or other materials provided with the distribution.
|
||||||
|
|
||||||
|
3. Neither the name of the copyright holder 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 HOLDER 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 <avr/io.h>
|
||||||
|
#include "yaMBSiavr.h"
|
||||||
|
#include <avr/interrupt.h>
|
||||||
|
#include "aBusIO.h"
|
||||||
|
|
||||||
|
volatile unsigned char BusState = 0;
|
||||||
|
volatile uint16_t modbusTimer = 0;
|
||||||
|
volatile unsigned char rxbuffer[MaxFrameIndex+1];
|
||||||
|
volatile uint16_t DataPos = 0;
|
||||||
|
volatile unsigned char PacketTopIndex = 7;
|
||||||
|
volatile unsigned char modBusStaMaStates = 0;
|
||||||
|
|
||||||
|
uint8_t modbusGetBusState(void)
|
||||||
|
{
|
||||||
|
return BusState;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ADDRESS_MODE == SINGLE_ADR
|
||||||
|
volatile unsigned char Address = 0x00;
|
||||||
|
uint8_t modbusGetAddress(void)
|
||||||
|
{
|
||||||
|
return Address;
|
||||||
|
}
|
||||||
|
|
||||||
|
void modbusSetAddress(unsigned char newadr)
|
||||||
|
{
|
||||||
|
Address = newadr;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if PHYSICAL_TYPE == 485
|
||||||
|
void transceiver_txen(void)
|
||||||
|
{
|
||||||
|
#if BOARD_TYPE == bType5chLedDim
|
||||||
|
PORTD|=(1<<7);
|
||||||
|
#endif
|
||||||
|
TRANSCEIVER_ENABLE_PORT|=(1<<TRANSCEIVER_ENABLE_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
|
void transceiver_rxen(void)
|
||||||
|
{
|
||||||
|
TRANSCEIVER_ENABLE_PORT&=~(1<<TRANSCEIVER_ENABLE_PIN);
|
||||||
|
#if BOARD_TYPE == bType5chLedDim
|
||||||
|
PORTD&=~(1<<7);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* @brief: A fairly simple Modbus compliant 16 Bit CRC algorithm.
|
||||||
|
*
|
||||||
|
* Returns 1 if the crc check is positive, returns 0 and saves the calculated CRC bytes
|
||||||
|
* at the end of the data array if it fails.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
uint8_t crc16(volatile uint8_t *ptrToArray,uint8_t inputSize) //A standard CRC algorithm
|
||||||
|
{
|
||||||
|
uint16_t out=0xffff;
|
||||||
|
uint16_t carry;
|
||||||
|
unsigned char n;
|
||||||
|
inputSize++;
|
||||||
|
for (int l=0; l<inputSize; l++) {
|
||||||
|
out ^= ptrToArray[l];
|
||||||
|
for (n = 0; n < 8; n++) {
|
||||||
|
carry = out & 1;
|
||||||
|
out >>= 1;
|
||||||
|
if (carry) out ^= 0xA001;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
//out=0x1234;
|
||||||
|
if ((ptrToArray[inputSize]==out%256) && (ptrToArray[inputSize+1]==out/256)) //check
|
||||||
|
{
|
||||||
|
return 1;
|
||||||
|
} else {
|
||||||
|
ptrToArray[inputSize]=out%256; //append Lo
|
||||||
|
ptrToArray[inputSize+1]=out/256; //append Hi
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: copies a single or multiple words from one array of bytes to another array of bytes
|
||||||
|
* amount must not be bigger than 255...
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void listRegisterCopy(volatile uint8_t *source, volatile uint8_t *target, uint8_t amount)
|
||||||
|
{
|
||||||
|
for (uint8_t c=0; c<amount; c++)
|
||||||
|
{
|
||||||
|
*(target+c)=*(source+c);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: copies a single bit from one char to another char (or arrays thereof)
|
||||||
|
*
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void listBitCopy(volatile uint8_t *source, uint16_t sourceNr,volatile uint8_t *target, uint16_t targetNr)
|
||||||
|
{
|
||||||
|
if(*(source+(sourceNr/8))&(1<<(sourceNr-((sourceNr/8)*8))))
|
||||||
|
{
|
||||||
|
*(target+(targetNr/8))|=(1<<(targetNr-((targetNr/8)*8)));
|
||||||
|
} else *(target+(targetNr/8))&=~(1<<(targetNr-((targetNr/8)*8)));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: Back to receiving state.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void modbusReset(void)
|
||||||
|
{
|
||||||
|
BusState=(1<<TimerActive); //stop receiving (error)
|
||||||
|
modbusTimer=0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void modbusTickTimer(void)
|
||||||
|
{
|
||||||
|
if (BusState&(1<<TimerActive))
|
||||||
|
{
|
||||||
|
modbusTimer++;
|
||||||
|
if (BusState&(1<<Receiving)) //we are in receiving mode
|
||||||
|
{
|
||||||
|
if ((modbusTimer==modbusInterCharTimeout)) {
|
||||||
|
BusState|=(1<<GapDetected);
|
||||||
|
} else if ((modbusTimer==modbusInterFrameDelayReceiveEnd)) { //end of message
|
||||||
|
BusState=(1<<ReceiveCompleted);
|
||||||
|
#if ADDRESS_MODE == MULTIPLE_ADR
|
||||||
|
if (crc16(rxbuffer,DataPos-3)) { //perform crc check only. This is for multiple/all address mode.
|
||||||
|
} else modbusReset();
|
||||||
|
#endif
|
||||||
|
#if ADDRESS_MODE == SINGLE_ADR
|
||||||
|
if (rxbuffer[0]==Address && crc16(rxbuffer,DataPos-3)) { //is the message for us? => perform crc check
|
||||||
|
} else modbusReset();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
} else if (modbusTimer==modbusInterFrameDelayReceiveStart) BusState|=(1<<BusTimedOut);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ISR(UART_RECEIVE_INTERRUPT)
|
||||||
|
{
|
||||||
|
unsigned char data;
|
||||||
|
data = UART_DATA;
|
||||||
|
modbusTimer=0; //reset timer
|
||||||
|
if (!(BusState & (1<<ReceiveCompleted)) && !(BusState & (1<<TransmitRequested)) && !(BusState & (1<<Transmitting)) && (BusState & (1<<Receiving)) && !(BusState & (1<<BusTimedOut)))
|
||||||
|
{
|
||||||
|
if (DataPos>MaxFrameIndex) modbusReset();
|
||||||
|
else
|
||||||
|
{
|
||||||
|
rxbuffer[DataPos]=data;
|
||||||
|
DataPos++; //TODO: maybe prevent this from exceeding 255?
|
||||||
|
}
|
||||||
|
} else
|
||||||
|
if (!(BusState & (1<<ReceiveCompleted)) && !(BusState & (1<<TransmitRequested)) && !(BusState & (1<<Transmitting)) && !(BusState & (1<<Receiving)) && (BusState & (1<<BusTimedOut)))
|
||||||
|
{
|
||||||
|
rxbuffer[0]=data;
|
||||||
|
BusState=((1<<Receiving)|(1<<TimerActive));
|
||||||
|
DataPos=1;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ISR(UART_TRANSMIT_INTERRUPT)
|
||||||
|
{
|
||||||
|
BusState&=~(1<<TransmitRequested);
|
||||||
|
BusState|=(1<<Transmitting);
|
||||||
|
UART_DATA=rxbuffer[DataPos];
|
||||||
|
DataPos++;
|
||||||
|
if (DataPos==(PacketTopIndex+1)) {
|
||||||
|
UART_CONTROL&=~(1<<UART_UDRIE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
ISR(UART_TRANSMIT_COMPLETE_INTERRUPT)
|
||||||
|
{
|
||||||
|
#if PHYSICAL_TYPE == 485
|
||||||
|
transceiver_rxen();
|
||||||
|
#endif
|
||||||
|
modbusReset();
|
||||||
|
}
|
||||||
|
|
||||||
|
void modbusInit(void)
|
||||||
|
{
|
||||||
|
UBRRH = (unsigned char)((UBRR) >> 8);
|
||||||
|
UBRRL = (unsigned char) UBRR;
|
||||||
|
UART_STATUS = (1<<U2X); //double speed mode.
|
||||||
|
#ifdef URSEL // if UBRRH and UCSRC share the same I/O location , e.g. ATmega8
|
||||||
|
UCSRC = (1<<URSEL)|(3<<UCSZ0); //Frame Size
|
||||||
|
#else
|
||||||
|
UCSRC = (3<<UCSZ0); //Frame Size
|
||||||
|
#endif
|
||||||
|
UART_CONTROL = (1<<TXCIE)|(1<<RXCIE)|(1<<RXEN)|(1<<TXEN); // USART receiver and transmitter and receive complete interrupt
|
||||||
|
#if PHYSICAL_TYPE == 485
|
||||||
|
TRANSCEIVER_ENABLE_PORT_DDR|=(1<<TRANSCEIVER_ENABLE_PIN);
|
||||||
|
transceiver_rxen();
|
||||||
|
#endif
|
||||||
|
BusState=(1<<TimerActive);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: Sends a response.
|
||||||
|
*
|
||||||
|
* Arguments: - packtop: Position of the last byte containing data.
|
||||||
|
* modbusSendException is a good usage example.
|
||||||
|
*/
|
||||||
|
void modbusSendMessage(unsigned char packtop)
|
||||||
|
{
|
||||||
|
PacketTopIndex=packtop+2;
|
||||||
|
crc16(rxbuffer,packtop);
|
||||||
|
BusState|=(1<<TransmitRequested);
|
||||||
|
DataPos=0;
|
||||||
|
#if PHYSICAL_TYPE == 485
|
||||||
|
transceiver_txen();
|
||||||
|
#endif
|
||||||
|
UART_CONTROL|=(1<<UART_UDRIE);
|
||||||
|
BusState&=~(1<<ReceiveCompleted);
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: Sends an exception response.
|
||||||
|
*
|
||||||
|
* Arguments: - exceptionCode
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void modbusSendException(unsigned char exceptionCode)
|
||||||
|
{
|
||||||
|
rxbuffer[1]|=(1<<7); //setting MSB of the function code (the exception flag)
|
||||||
|
rxbuffer[2]=exceptionCode; //Exceptioncode. Also the last byte containing data
|
||||||
|
modbusSendMessage(2);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
/* @brief: Returns the amount of requested data objects (coils, discretes, registers)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
uint16_t modbusRequestedAmount(void)
|
||||||
|
{
|
||||||
|
return (rxbuffer[5]|(rxbuffer[4]<<8));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: Returns the address of the first requested data object (coils, discretes, registers)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
uint16_t modbusRequestedAddress(void)
|
||||||
|
{
|
||||||
|
return (rxbuffer[3]|(rxbuffer[2]<<8));
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: copies a single or multiple bytes from one array of bytes to an array of 16-bit-words
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void intToModbusRegister(volatile uint16_t *inreg, volatile uint8_t *outreg, uint8_t amount)
|
||||||
|
{
|
||||||
|
for (uint8_t c=0; c<amount; c++)
|
||||||
|
{
|
||||||
|
*(outreg+c*2) = (uint8_t)(*(inreg+c) >> 8);
|
||||||
|
*(outreg+1+c*2) = (uint8_t)(*(inreg+c));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: copies a single or multiple 16-bit-words from one array of integers to an array of bytes
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
void modbusRegisterToInt(volatile uint8_t *inreg, volatile uint16_t *outreg, uint8_t amount)
|
||||||
|
{
|
||||||
|
for (uint8_t c=0; c<amount; c++)
|
||||||
|
{
|
||||||
|
*(outreg+c) = (*(inreg+c*2) << 8) + *(inreg+1+c*2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: Handles single/multiple register reading and single/multiple register writing.
|
||||||
|
*
|
||||||
|
* Arguments: - ptrToInArray: pointer to the user's data array containing registers
|
||||||
|
* - startAddress: address of the first register in the supplied array
|
||||||
|
* - size: input array size in the requested format (16bit-registers)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
uint8_t modbusExchangeRegisters(volatile uint16_t *ptrToInArray, uint16_t startAddress, uint16_t size)
|
||||||
|
{
|
||||||
|
uint16_t requestedAmount = modbusRequestedAmount();
|
||||||
|
uint16_t requestedAdr = modbusRequestedAddress();
|
||||||
|
if (rxbuffer[1]==fcPresetSingleRegister) requestedAmount=1;
|
||||||
|
if ((requestedAdr>=startAddress) && ((startAddress+size)>=(requestedAmount+requestedAdr))) {
|
||||||
|
|
||||||
|
if ((rxbuffer[1]==fcReadHoldingRegisters) || (rxbuffer[1]==fcReadInputRegisters) )
|
||||||
|
{
|
||||||
|
if ((requestedAmount*2)<=(MaxFrameIndex-4)) //message buffer big enough?
|
||||||
|
{
|
||||||
|
rxbuffer[2]=(unsigned char)(requestedAmount*2);
|
||||||
|
intToModbusRegister(ptrToInArray+(requestedAdr-startAddress),rxbuffer+3,requestedAmount);
|
||||||
|
modbusSendMessage(2+rxbuffer[2]);
|
||||||
|
return 1;
|
||||||
|
} else modbusSendException(ecIllegalDataValue);
|
||||||
|
}
|
||||||
|
else if (rxbuffer[1]==fcPresetMultipleRegisters)
|
||||||
|
{
|
||||||
|
if (((rxbuffer[6])>=requestedAmount*2) && ((DataPos-9)>=rxbuffer[6])) //enough data received?
|
||||||
|
{
|
||||||
|
modbusRegisterToInt(rxbuffer+7,ptrToInArray+(requestedAdr-startAddress),(unsigned char)(requestedAmount));
|
||||||
|
modbusSendMessage(5);
|
||||||
|
return 1;
|
||||||
|
} else modbusSendException(ecIllegalDataValue);//too few data bytes received
|
||||||
|
}
|
||||||
|
else if (rxbuffer[1]==fcPresetSingleRegister)
|
||||||
|
{
|
||||||
|
modbusRegisterToInt(rxbuffer+4,ptrToInArray+(requestedAdr-startAddress),1);
|
||||||
|
modbusSendMessage(5);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
//modbusSendException(ecSlaveDeviceFailure); //inapropriate call of modbusExchangeRegisters
|
||||||
|
return 0;
|
||||||
|
} else {
|
||||||
|
modbusSendException(ecIllegalDataValue);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* @brief: Handles single/multiple input/coil reading and single/multiple coil writing.
|
||||||
|
*
|
||||||
|
* Arguments: - ptrToInArray: pointer to the user's data array containing bits
|
||||||
|
* - startAddress: address of the first bit in the supplied array
|
||||||
|
* - size: input array size in the requested format (bits)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
uint8_t modbusExchangeBits(volatile uint8_t *ptrToInArray, uint16_t startAddress, uint16_t size)
|
||||||
|
{
|
||||||
|
uint16_t requestedAmount = modbusRequestedAmount();
|
||||||
|
uint16_t requestedAdr = modbusRequestedAddress();
|
||||||
|
if (rxbuffer[1]==fcForceSingleCoil) requestedAmount=1;
|
||||||
|
if ((requestedAdr>=startAddress) && ((startAddress+size)>=(requestedAmount+requestedAdr)))
|
||||||
|
{
|
||||||
|
if ((rxbuffer[1]==fcReadInputStatus) || (rxbuffer[1]==fcReadCoilStatus))
|
||||||
|
{
|
||||||
|
if (requestedAmount<=((MaxFrameIndex-4)*8)) //message buffer big enough?
|
||||||
|
{
|
||||||
|
rxbuffer[2]=(requestedAmount/8);
|
||||||
|
if (requestedAmount%8>0)
|
||||||
|
{
|
||||||
|
rxbuffer[(uint8_t)(requestedAmount/8)+3]=0x00; //fill last data byte with zeros
|
||||||
|
rxbuffer[2]++;
|
||||||
|
}
|
||||||
|
for (uint16_t c = 0; c<requestedAmount; c++)
|
||||||
|
{
|
||||||
|
listBitCopy(ptrToInArray,requestedAdr-startAddress+c,rxbuffer+3,c);
|
||||||
|
}
|
||||||
|
modbusSendMessage(rxbuffer[2]+2);
|
||||||
|
return 1;
|
||||||
|
} else modbusSendException(ecIllegalDataValue); //too many bits requested within single request
|
||||||
|
}
|
||||||
|
else if (rxbuffer[1]==fcForceMultipleCoils)
|
||||||
|
{
|
||||||
|
if (((rxbuffer[6]*8)>=requestedAmount) && ((DataPos-9)>=rxbuffer[6])) //enough data received?
|
||||||
|
{
|
||||||
|
for (uint16_t c = 0; c<requestedAmount; c++)
|
||||||
|
{
|
||||||
|
listBitCopy(rxbuffer+7,c,ptrToInArray,requestedAdr-startAddress+c);
|
||||||
|
}
|
||||||
|
modbusSendMessage(5);
|
||||||
|
return 1;
|
||||||
|
} else modbusSendException(ecIllegalDataValue);//exception too few data bytes received
|
||||||
|
}
|
||||||
|
else if (rxbuffer[1]==fcForceSingleCoil) {
|
||||||
|
listBitCopy(rxbuffer+4,0,ptrToInArray,requestedAdr-startAddress);
|
||||||
|
modbusSendMessage(5);
|
||||||
|
return 1;
|
||||||
|
}
|
||||||
|
//modbusSendException(ecSlaveDeviceFailure); //inanpropriate call of modbusExchangeBits
|
||||||
|
return 0;
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
modbusSendException(ecIllegalDataValue);
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
@ -0,0 +1,392 @@
|
|||||||
|
#ifndef yaMBSiavr_H
|
||||||
|
#define yaMBSiavr_H
|
||||||
|
#endif
|
||||||
|
/************************************************************************
|
||||||
|
Title: Yet another (small) Modbus (server) implementation for the avr.
|
||||||
|
Author: Max Brueggemann
|
||||||
|
Hardware: any AVR with hardware UART, tested on Atmega 88/168 at 20Mhz
|
||||||
|
License: BSD-3-Clause
|
||||||
|
|
||||||
|
LICENSE:
|
||||||
|
|
||||||
|
Copyright 2017 Max Brueggemann, www.maxbrueggemann.de
|
||||||
|
|
||||||
|
Redistribution and use in source and binary forms, with or without
|
||||||
|
modification, are permitted provided that the following conditions are met:
|
||||||
|
|
||||||
|
1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
this list of conditions and the following disclaimer.
|
||||||
|
|
||||||
|
2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
this list of conditions and the following disclaimer in the documentation
|
||||||
|
and/or other materials provided with the distribution.
|
||||||
|
|
||||||
|
3. Neither the name of the copyright holder 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 HOLDER 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 <avr/io.h>
|
||||||
|
#include "aBusIO.h"
|
||||||
|
/**
|
||||||
|
* @code #include <yaMBSIavr.h> @endcode
|
||||||
|
*
|
||||||
|
* @brief Interrupt-based Modbus implementation for small avr microcontrollers.
|
||||||
|
* The Modbus implementation guidelines at modbus.org call for response
|
||||||
|
* timeouts in the range of several seconds , hence only timing critical
|
||||||
|
* parts have been implemented within ISRs. The actual handling of the Modbus
|
||||||
|
* frame can easily be done in the main while loop.
|
||||||
|
*
|
||||||
|
* @author Max Brueggemann www.maxbrueggemann.de
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* define baudrate of modbus */
|
||||||
|
#define BAUD 38400L
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Definitions for transceiver enable pin.
|
||||||
|
*/
|
||||||
|
#if BOARD_TYPE == bType5chLedDim
|
||||||
|
#define TRANSCEIVER_ENABLE_PORT PORTD
|
||||||
|
#define TRANSCEIVER_ENABLE_PIN 5
|
||||||
|
#define TRANSCEIVER_ENABLE_PORT_DDR DDRD
|
||||||
|
#else
|
||||||
|
#define TRANSCEIVER_ENABLE_PORT PORTD
|
||||||
|
#define TRANSCEIVER_ENABLE_PIN 2
|
||||||
|
#define TRANSCEIVER_ENABLE_PORT_DDR DDRD
|
||||||
|
#endif
|
||||||
|
/**
|
||||||
|
* @brief
|
||||||
|
* At the moment the user has to set the value for Baudrate and
|
||||||
|
* speed mode manually. The values depend on the operating frequency
|
||||||
|
* of your AVR and can be found in its datasheet.
|
||||||
|
*/
|
||||||
|
#if defined(__AVR_ATtiny2313__)
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART_TX_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART_RX_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART_UDRE_vect
|
||||||
|
#define UART_STATUS UCSRA
|
||||||
|
#define UART_CONTROL UCSRB
|
||||||
|
#define UART_DATA UDR
|
||||||
|
#define UART_UDRIE UDRIE
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega164P__)
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART1_TX_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART1_RX_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART1_UDRE_vect
|
||||||
|
#define UART_STATUS UCSR1A
|
||||||
|
#define UART_CONTROL UCSR1B
|
||||||
|
#define UART_DATA UDR1
|
||||||
|
#define UART_UDRIE UDRIE1
|
||||||
|
#define UCSRC UCSR1C
|
||||||
|
#define RXCIE RXCIE1
|
||||||
|
#define TXCIE TXCIE1
|
||||||
|
#define RXEN RXEN1
|
||||||
|
#define TXEN TXEN1
|
||||||
|
#define UCSZ0 UCSZ10
|
||||||
|
#define U2X U2X1
|
||||||
|
#define UBRRH UBRR1H
|
||||||
|
#define UBRRL UBRR1L
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega168PA__)|(__AVR_ATmega88P__)|(__AVR_ATmega328P__)|(__AVR_ATmega168P__)
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART_TX_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART_RX_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART_UDRE_vect
|
||||||
|
#define UART_STATUS UCSR0A
|
||||||
|
#define UART_CONTROL UCSR0B
|
||||||
|
#define UART_DATA UDR0
|
||||||
|
#define UART_UDRIE UDRIE0
|
||||||
|
#define UCSRC UCSR0C
|
||||||
|
#define RXCIE RXCIE0
|
||||||
|
#define TXCIE TXCIE0
|
||||||
|
#define RXEN RXEN0
|
||||||
|
#define TXEN TXEN0
|
||||||
|
#define UCSZ0 UCSZ00
|
||||||
|
#define U2X U2X0
|
||||||
|
#define UBRRH UBRR0H
|
||||||
|
#define UBRRL UBRR0L
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega328PB__) && BOARD_TYPE != bType5chLedDim
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART0_TX_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART0_RX_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART0_UDRE_vect
|
||||||
|
#define UART_STATUS UCSR0A
|
||||||
|
#define UART_CONTROL UCSR0B
|
||||||
|
#define UART_DATA UDR0
|
||||||
|
#define UART_UDRIE UDRIE0
|
||||||
|
#define UCSRC UCSR0C
|
||||||
|
#define RXCIE RXCIE0
|
||||||
|
#define TXCIE TXCIE0
|
||||||
|
#define RXEN RXEN0
|
||||||
|
#define TXEN TXEN0
|
||||||
|
#define UCSZ0 UCSZ00
|
||||||
|
#define U2X U2X0
|
||||||
|
#define UBRRH UBRR0H
|
||||||
|
#define UBRRL UBRR0L
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega328PB__) && BOARD_TYPE == bType5chLedDim
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART1_TX_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART1_RX_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART1_UDRE_vect
|
||||||
|
#define UART_STATUS UCSR1A
|
||||||
|
#define UART_CONTROL UCSR1B
|
||||||
|
#define UART_DATA UDR1
|
||||||
|
#define UART_UDRIE UDRIE1
|
||||||
|
#define UCSRC UCSR1C
|
||||||
|
#define RXCIE RXCIE1
|
||||||
|
#define TXCIE TXCIE1
|
||||||
|
#define RXEN RXEN1
|
||||||
|
#define TXEN TXEN1
|
||||||
|
#define UCSZ0 UCSZ10
|
||||||
|
#define U2X U2X1
|
||||||
|
#define UBRRH UBRR1H
|
||||||
|
#define UBRRL UBRR1L
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Change this value if you are using a different frequency and/or
|
||||||
|
* different baudrate.
|
||||||
|
*/
|
||||||
|
#define Baud 64 //38400@20e6Hz
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATtiny441__)
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART0_TX_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART0_RX_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART0_UDRE_vect
|
||||||
|
#define UART_STATUS UCSR0A
|
||||||
|
#define UART_CONTROL UCSR0B
|
||||||
|
#define UART_DATA UDR0
|
||||||
|
#define UART_UDRIE UDRIE0
|
||||||
|
#define UCSRC UCSR0C
|
||||||
|
#define RXCIE RXCIE0
|
||||||
|
#define TXCIE TXCIE0
|
||||||
|
#define RXEN RXEN0
|
||||||
|
#define TXEN TXEN0
|
||||||
|
#define UCSZ0 UCSZ00
|
||||||
|
#define U2X U2X0
|
||||||
|
#define UBRRH UBRR0H
|
||||||
|
#define UBRRL UBRR0L
|
||||||
|
|
||||||
|
#elif defined(__AVR_ATmega8__)|| defined(__AVR_ATmega16__) || defined(__AVR_ATmega32__) || defined(__AVR_ATmega323__)
|
||||||
|
#define UART_TRANSMIT_COMPLETE_INTERRUPT USART_TXC_vect
|
||||||
|
#define UART_RECEIVE_INTERRUPT USART_RXC_vect
|
||||||
|
#define UART_TRANSMIT_INTERRUPT USART_UDRE_vect
|
||||||
|
#define UART_STATUS UCSRA
|
||||||
|
#define UART_CONTROL UCSRB
|
||||||
|
#define UART_DATA UDR
|
||||||
|
#define UART_UDRIE UDRIE
|
||||||
|
|
||||||
|
#else
|
||||||
|
#error "no definition available"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef F_CPU
|
||||||
|
#error " F_CPU not defined "
|
||||||
|
#else
|
||||||
|
#define UBRR (F_CPU / 8 / BAUD ) -1
|
||||||
|
#endif /* F_CPU */
|
||||||
|
/*
|
||||||
|
* Available address modes.
|
||||||
|
*/
|
||||||
|
#define MULTIPLE_ADR 2
|
||||||
|
#define SINGLE_ADR 1
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Use SINGLE_ADR or MULTIPLE_ADR, default: SINGLE_ADR
|
||||||
|
* This is useful for building gateways, routers or clients that for whatever reason need multiple addresses.
|
||||||
|
*/
|
||||||
|
#define ADDRESS_MODE SINGLE_ADR
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Use 485 or 232, default: 485
|
||||||
|
* Use 232 for testing purposes or very simple applications that do not require RS485 and bus topology.
|
||||||
|
*/
|
||||||
|
#define PHYSICAL_TYPE 485 //possible values: 485, 232
|
||||||
|
|
||||||
|
/*
|
||||||
|
#define modbusBaudrate 38400
|
||||||
|
#define modbusBlocksize 10
|
||||||
|
#define modbusBlockTime ((float)modbusBlocksize*1000000)/((float) modbusBaudrate) //is 260 fuer 38400
|
||||||
|
#define timerISROccurenceTime 102
|
||||||
|
|
||||||
|
#define TimeoutStartOfMessage (uint16_t)(modbusBlockTime*3.5/(float)timerISROccurenceTime)
|
||||||
|
#define TimeoutEndOfMessage (uint16_t)(modbusBlockTime*4/(float)timerISROccurenceTime)
|
||||||
|
#define ReceiveMaxGap (uint16_t)(modbusBlockTime*1.5/(float)timerISROccurenceTime)
|
||||||
|
*/
|
||||||
|
#define modbusInterFrameDelayReceiveStart (uint8_t)(F_CPU/1843200) //18432000Hz => 10
|
||||||
|
#define modbusInterFrameDelayReceiveEnd (uint8_t)(F_CPU/1024000) //18432000Hz => 18
|
||||||
|
#define modbusInterCharTimeout (uint8_t)(F_CPU/3686400) //18432000Hz => 5
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Defines the maximum Modbus frame size accepted by the device. 255 is the default
|
||||||
|
* and also the maximum value. However, it might be useful to set this to lower
|
||||||
|
* values, with 8 being the lowest possible value, in order to save on ram space.
|
||||||
|
*/
|
||||||
|
#define MaxFrameIndex 100
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Modbus Function Codes
|
||||||
|
* Refer to modbus.org for further information.
|
||||||
|
* It's good practice to return exception code 01 in case you receive a function code
|
||||||
|
* that you haven't implemented in your application.
|
||||||
|
*/
|
||||||
|
#define fcReadCoilStatus 1 //read single/multiple coils
|
||||||
|
#define fcReadInputStatus 2 //read single/multiple inputs
|
||||||
|
#define fcReadHoldingRegisters 3 //read analog output registers
|
||||||
|
#define fcReadInputRegisters 4 //read analog input registers (2 Bytes per register)
|
||||||
|
#define fcForceSingleCoil 5 //write single bit
|
||||||
|
#define fcPresetSingleRegister 6 //write analog output register (2 Bytes)
|
||||||
|
#define fcForceMultipleCoils 15 //write multiple bits
|
||||||
|
#define fcPresetMultipleRegisters 16 //write multiple analog output registers (2 Bytes each)
|
||||||
|
#define fcReportSlaveID 17 //read device description, run status and other device specific information
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Modbus Exception Codes
|
||||||
|
* Refer to modbus.org for further information.
|
||||||
|
* It's good practice to return exception code 01 in case you receive a function code
|
||||||
|
* that you haven't implemented in your application.
|
||||||
|
*/
|
||||||
|
#define ecIllegalFunction 1
|
||||||
|
#define ecIllegalDataAddress 2
|
||||||
|
#define ecIllegalDataValue 3
|
||||||
|
#define ecSlaveDeviceFailure 4
|
||||||
|
#define ecAcknowledge 5
|
||||||
|
#define ecSlaveDeviceBusy 6
|
||||||
|
#define ecNegativeAcknowledge 7
|
||||||
|
#define ecMemoryParityError 8
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal bit definitions
|
||||||
|
*/
|
||||||
|
#define BusTimedOut 0
|
||||||
|
#define Receiving 1
|
||||||
|
#define Transmitting 2
|
||||||
|
#define ReceiveCompleted 3
|
||||||
|
#define TransmitRequested 4
|
||||||
|
#define TimerActive 5
|
||||||
|
#define GapDetected 6
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Configures the UART. Call this function only once.
|
||||||
|
*/
|
||||||
|
extern void modbusInit(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief receive/transmit data array
|
||||||
|
*/
|
||||||
|
volatile unsigned char rxbuffer[MaxFrameIndex+1];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Current receive/transmit position
|
||||||
|
*/
|
||||||
|
volatile uint16_t DataPos;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This only applies to single address mode.
|
||||||
|
*/
|
||||||
|
#if ADDRESS_MODE == SINGLE_ADR
|
||||||
|
/**
|
||||||
|
* @brief: Read the device address
|
||||||
|
*/
|
||||||
|
extern uint8_t modbusGetAddress(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief: Set the device address
|
||||||
|
* Arguments: - newadr: the new device address
|
||||||
|
*/
|
||||||
|
extern void modbusSetAddress(unsigned char newadr);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* @brief: Sends a response.
|
||||||
|
*
|
||||||
|
* Arguments: - packtop, index of the last byte in rxbuffer
|
||||||
|
* that contains payload. Maximum value is
|
||||||
|
* MaxFrameIndex-2.
|
||||||
|
*/
|
||||||
|
extern void modbusSendMessage(unsigned char packtop);
|
||||||
|
|
||||||
|
/* @brief: Sends a Modbus exception.
|
||||||
|
*
|
||||||
|
* Arguments: - exceptionCode
|
||||||
|
*/
|
||||||
|
extern void modbusSendException(unsigned char exceptionCode);
|
||||||
|
|
||||||
|
/* @brief: Discards the current transaction. For MULTIPLE_ADR-mode and general
|
||||||
|
* testing purposes. Call this function if you don't want to reply at all.
|
||||||
|
*/
|
||||||
|
void modbusReset(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Call this function whenever possible and check if its return value has the ReceiveCompleted Bit set.
|
||||||
|
* Preferably do this in the main while. I do not recommend calling this function within ISRs.
|
||||||
|
* @example if (modbusGetBusState() & (1<<ReceiveCompleted)) {
|
||||||
|
* modbusSendExcepton(ecIllegalFunction);
|
||||||
|
* }
|
||||||
|
*/
|
||||||
|
extern uint8_t modbusGetBusState(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Call every 100us using a timer ISR.
|
||||||
|
*/
|
||||||
|
extern void modbusTickTimer(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns amount of bits/registers requested.
|
||||||
|
*/
|
||||||
|
extern uint16_t modbusRequestedAmount(void);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Returns the address of the first requested bit/register.
|
||||||
|
*/
|
||||||
|
extern uint16_t modbusRequestedAddress(void);
|
||||||
|
|
||||||
|
/* A fairly simple and hopefully Modbus compliant 16 Bit CRC algorithm.
|
||||||
|
* Returns 1 if the crc check is positive, returns 0 if it fails.
|
||||||
|
* Appends two crc bytes to the array.
|
||||||
|
*/
|
||||||
|
extern uint8_t crc16(volatile uint8_t *ptrToArray,uint8_t inputSize);
|
||||||
|
|
||||||
|
/* @brief: Handles single/multiple input/coil reading and single/multiple coil writing.
|
||||||
|
*
|
||||||
|
* Arguments: - ptrToInArray: pointer to the user's data array containing bits
|
||||||
|
* - startAddress: address of the first bit in the supplied array
|
||||||
|
* - size: input array size in the requested format (bits)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
extern uint8_t modbusExchangeBits(volatile uint8_t *ptrToInArray, uint16_t startAddress, uint16_t size);
|
||||||
|
|
||||||
|
/* @brief: Handles single/multiple register reading and single/multiple register writing.
|
||||||
|
*
|
||||||
|
* Arguments: - ptrToInArray: pointer to the user's data array containing registers
|
||||||
|
* - startAddress: address of the first register in the supplied array
|
||||||
|
* - size: input array size in the requested format (16bit-registers)
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
extern uint8_t modbusExchangeRegisters(volatile uint16_t *ptrToInArray, uint16_t startAddress, uint16_t size);
|
||||||
|
|
||||||
|
/* @brief: Handles function code "report slave id".
|
||||||
|
*
|
||||||
|
* Arguments: - in: MUST BE NULL-TERMINATED and shorter than MaxFrameIndex-4
|
||||||
|
* (without NULL-Byte, the NULL-Byte is not transmitted).
|
||||||
|
* Pointer to the user's data array containing user specific
|
||||||
|
* information, typically a string (hence the null termination).
|
||||||
|
* The last byte should (according to spec) contain the 'run indication"
|
||||||
|
* (running: 0xFF, not running: 0x00). This seems to be originating
|
||||||
|
* from PLC terminology and is often omitted nowadays.
|
||||||
|
*
|
||||||
|
* @example: char myDeviceDescription[] = {"modbus capable device that is always running V1.0\0xFF\0x00"}
|
||||||
|
* modbusSendSlaveID(myDeviceDescription);
|
||||||
|
*/
|
||||||
|
extern void modbusSendSlaveID(char *in);
|
||||||
Loading…
Reference in New Issue