UART bluetooth communication problem What is the proper format to send data to the UART (integer values) - bluetooth

I have created my functions to send and receive from the UART, and sending the data does not seem to be a problem. In the data visualizer we can see the values and even plot them.
However when sending these data through the bluetooth, we cannot get the values to plot them in any of many available apps.
I believe there is a problem with the way we are sending data through the UART and to the bluetooth and that is why we cannot then get the values to be plotted.
Being a starter at all this, I would like to someone please advice us if the code below is ok, if there is a mistake and if there is a better way to send the data through the UART so as to make the Bluetooth work properly. Target is to be able to plot (graph) the values on the phone.
Many thanks
#define F_CPU 16000000UL
#include <avr/io.h>
#include <util/delay.h>
#include <avr/interrupt.h>
#include <stdio.h>
#define BAUDRATE 9600
#define BAUD_PRESCALLER (((F_CPU / (BAUDRATE * 16UL))) - 1)
//----------VARIABLES
float V_n,V_nm1,V_measure=0;
volatile int Velo_pulse;
float Exp_fltr_Coeff=0.2;
unsigned int Counter_ADC=0b0001;
unsigned int Value1;
char String[]="";
//----------Functions Definition
//---timers
void Timer1_Control();
void AttachInterrupt();
//---AnalogueRead
void Set_Ports();
void AnalogRead_Setup();
unsigned int AnalogRead();
//---UART
void USART_init(void);
unsigned char USART_receive(void);
void USART_send( unsigned char data);
void USART_putstring(char* StringPtr, unsigned int Value1);
int main(void){
USART_init(); //Call the USART initialization code
Set_Ports();
AnalogRead_Setup();
AttachInterrupt();
Timer1_Control();
sei();
while(1){
_delay_ms(1);
}
return 0;
}
void USART_init(void){
UBRR0H = (unsigned char)(BAUD_PRESCALLER>>8); //UBRR0H = (uint8_t)(BAUD_PRESCALLER>>8);
UBRR0L = (unsigned char)(BAUD_PRESCALLER);
UCSR0B = (1<<RXEN0)|(1<<TXEN0); //Enable receiver / transmitter
UCSR0C = (1<<USBS0)|(3<<UCSZ00); //Set frame format: 8data, 2stop bit
}
unsigned char USART_receive(void){
while(!(UCSR0A & (1<<RXC0))); //Wait for data to be received (buffer RXCn in the UCSRnA register)
return UDR0;
}
void USART_send( unsigned char data){
while(!(UCSR0A & (1<<UDRE0))); //Waiting for empty transmit buffer (buffer UDREn in the UCSRnA register)
UDR0 = data; //Loading Data on the transmit buffer
}
void USART_putstring(char* String, unsigned int Value1){
sprintf(String,"%d\r\n",Value1);
while(*String != 0x00){
USART_send(*String);
String++;}
}
void Set_Ports()
{
DDRD = 0b11111111; //All port is output
DDRD ^= (1 << DDD5); // PD5 is now input
}
ISR(ADC_vect)
{
//ADMUX ^= Counter_ADC; //Swapping between ADC0 an ADC1
}
void AnalogRead_Setup()
{
ADCSRA |= (1 << ADPS2) | (0 << ADPS1) | (0 << ADPS0); // Set ADC prescaler to 16 - 1 MHz sample rate # 16MHz
ADMUX |= (1 << REFS0); // Set ADC reference to AVCC
ADMUX |= (1 << ADLAR); // Left adjust ADC result to allow easy 8 bit reading
ADCSRA |= (1 << ADATE); // Set ADC to Free-Running Mode
ADCSRA |= (1 << ADIE); // Interrupt in Conversion Complete
ADCSRA |= (1 << ADEN); // Enable ADC
}
unsigned int AnalogRead(unsigned int PortVal)
{
if (PortVal==5){
ADMUX |= (0 << MUX3) | (1 << MUX2) | (0 << MUX1) | (1 << MUX0); //sets the pin 0101 sets pin5
} else if (PortVal==4){
ADMUX |= (0 << MUX3) | (1 << MUX2) | (0 << MUX1) | (0 << MUX0); //sets the pin 0101 sets pin4
}
ADCSRA |= (1 << ADSC); // Start A2D Conversions
//while(ADCSRA & (1 << ADSC));
return ADCH;
}
//----------Timer Functions
ISR (TIMER1_COMPA_vect) // Timer1 ISR (compare A vector - Compare Interrupt Mode)
{
cli();
V_measure=(Velo_pulse*60/0.250);
//USART_putstring(String,Velo_pulse);
Velo_pulse=0;
V_n=Exp_fltr_Coeff*V_measure+(1-Exp_fltr_Coeff)*V_nm1;
V_nm1=V_n;
USART_putstring(String,(int)V_n);
sei();
}
ISR (INT0_vect)
{
Velo_pulse++;
//USART_putstring(String,Velo_pulse);
}
void Timer1_Control()
{
TCCR1A=0b00000000; //Clear the timer1 registers
TCCR1B=0b00000000;
TCNT1=0b00000000;
TCCR1B=0b00001101; //Sets prescaler (1024) & Compare mode
OCR1A=2604; // 160ms - 6 Hz
TIMSK1=0b00000010;
}
void AttachInterrupt()
{
DDRD ^= (1 << DDD2); // PD2 (PCINT0 pin) is now an input
PORTD |= (1 << PORTD2); // turn On the Pull-up // PD2 is now an input with pull-up enabled
EICRA = 0b00000011; // set INT0 to trigger on rising edge change
EIMSK = 0b00000001; // Turns on INT0
}

Look at string initialization:
char String[]="";
this allocates an array of chars with a size of 1 item (which is terminating zero).
Then you make a call, passing this array reference as the first parameter:
USART_putstring(String,(int)V_n);
And the USART_putstring is as follows:
void USART_putstring(char* String, unsigned int Value1){
sprintf(String,"%d\r\n",Value1);
while(*String != 0x00){
USART_send(*String);
String++;}
}
Note sprintf(String,"%d\r\n",Value1); it converts numeric value into the char buffer. I.e. the buffer should be large enough to contain the text representation of the number, line feeds \r\n\ and zero - the string terminator.
But since your string buffer has size for only 1 char, it totally depends on luck, what will happen after sprintf: maybe there is some unused memory area, so the whole thing will look as if it working. Maybe there are some other variables, and their value will be overwritten, which makes the program behavior unexpected in the future. Or maybe there is some essential data, and your app will be crashing. Behavior may change after you adding several lines and recompile the code.
The point is: be careful with your buffers. Instead of using constants for initialization, set the exact size for the buffer. The number length is maximum 6 symbols (1 possible sign and 5 digits, assuming you're using AVR-GCC, which has the int 16-bits wide, thus has -32768 as the minimum) + 2 for \r\n\ + 1 for terminating zero. I.e. size of the buffer should be 9 at least.
char String[9];

Related

Linux usb serial line input may lose the trailing new line

I am testing a serial communication protocol based on printable characters only.
The setup has a pc connected to an arduino board by USB. The PC USB serial is operated in canonical mode, with no echo, no flow control, 9600 baud.
Since a read timeout is requested, pselect is called before the serial read. The arduino board simply echoes back every received character without any processing. The PC OS is Linux Neon with kernel 5.13.0-40-generic.
When lines of a specific length are transmitted from the PC and echoed back by the arduino, they are received correctly except for the final new line that is missing.
A further read, returns an empty line (the previously missing NL).
Lines with different length are transmitted and received correctly, including the trailing NL.
This behavior is fully repeatable and stable. The following code reproduce the problem for a line transmitted with a length of 65 characters (including NL) and received with a length of 64 (NL missing). Other line lengths work fine.
Thanks for any hints.
/* remote serial loop test 20220626 */
#include <errno.h>
#include <fcntl.h>
#include <stdio.h>
#include <stdint.h>
#include <stdlib.h>
#include <sys/select.h>
#include <string.h>
#include <termios.h>
#include <time.h>
#include <unistd.h>
#define TX_MINLEN 63
#define TX_MAXLEN 66
#define DATA_MAXLEN 128
#define LINK_DEVICE "/dev/ttyUSB0"
#define LINK_SPEED B9600
#define RECEIVE_TIMEOUT 2000
int main()
{
int wlen;
int retval;
int msglen;
uint8_t tx_data[257] = {'0','1','2','3','4','5','6','7','8','9','A','B','C','D','E','F'};
for (int i=16; i < 256; i++) tx_data[i] = tx_data[i & 0xf];
uint8_t rx_data[257];
/* serial interface */
char * device;
int speed;
int fd;
fd_set fdset;
struct timespec receive_timeout;
struct timespec *p_receive_timeout = &receive_timeout;
struct termios tty;
/* open serial device in blocking mode */
fd = open(LINK_DEVICE, O_RDWR | O_NOCTTY);
if (fd < 0) {
printf("Error opening %s: %s\n",LINK_DEVICE,strerror(errno));
return -1;
}
/* prepare serial read by select to have read timeout */
FD_ZERO(&(fdset));
FD_SET(fd,&(fdset));
if (RECEIVE_TIMEOUT >= 0) {
p_receive_timeout->tv_sec = RECEIVE_TIMEOUT / 1000;
p_receive_timeout->tv_nsec = RECEIVE_TIMEOUT % 1000 * 1000000;
}
else
p_receive_timeout = NULL;
/* get termios structure */
if (tcgetattr(fd, &tty) < 0) {
printf("Error from tcgetattr: %s\n", strerror(errno));
return -1;
}
/* set tx and rx baudrate */
cfsetospeed(&tty, (speed_t)LINK_SPEED);
cfsetispeed(&tty, (speed_t)LINK_SPEED);
/* set no modem ctrl, 8 bit, no parity, 1 stop */
tty.c_cflag |= (CLOCAL | CREAD); /* ignore modem controls */
tty.c_cflag &= ~CSIZE;
tty.c_cflag |= CS8; /* 8-bit characters */
tty.c_cflag &= ~PARENB; /* no parity bit */
tty.c_cflag &= ~CSTOPB; /* only need 1 stop bit */
tty.c_cflag &= ~CRTSCTS; /* no hardware flowcontrol */
/* canonical mode: one line at a time (\n is line terminator) */
tty.c_lflag |= ICANON | ISIG;
tty.c_lflag &= ~(ECHO | ECHOE | ECHONL | IEXTEN);
/* input control */
tty.c_iflag &= ~IGNCR; /* preserve carriage return */
tty.c_iflag &= ~INPCK; /* no parity checking */
tty.c_iflag &= ~INLCR; /* no NL to CR traslation */
tty.c_iflag &= ~ICRNL; /* no CR to NL traslation */
tty.c_iflag &= ~IUCLC; /* no upper to lower case mapping */
tty.c_iflag &= ~IMAXBEL;/* no ring bell at rx buffer full */
tty.c_iflag &= ~(IXON | IXOFF | IXANY);/* no SW flowcontrol */
/* no output remapping, no char dependent delays */
tty.c_oflag = 0;
/* no additional EOL chars, confirm EOF to be 0x04 */
tty.c_cc[VEOL] = 0x00;
tty.c_cc[VEOL2] = 0x00;
tty.c_cc[VEOF] = 0x04;
/* set changed attributes really */
if (tcsetattr(fd, TCSANOW, &tty) != 0) {
printf("Error from tcsetattr: %s\n", strerror(errno));
return -1;
}
/* wait for serial link hardware to settle, required by arduino reset
* triggered by serial control lines */
sleep(2);
/* empty serial buffers, both tx and rx */
tcflush(fd,TCIOFLUSH);
/* repeat transmit and receive, each time reducing data length by 1 char */
for (int l=TX_MAXLEN; l > TX_MINLEN - 1; l--) {
/* prepare data: set EOL and null terminator for current length */
tx_data[l] = '\n';
tx_data[l+1] = 0;
/* send data */
int sent = write(fd,tx_data,l+1);
/* receive data */
/* wait for received data or for timeout */
retval = pselect(fd+1,&(fdset),NULL,NULL,p_receive_timeout,NULL);
/* check for error or timeout */
if (retval < 0)
printf("pselect error: %d - %s\n",retval,strerror(errno));
else if (retval == 0)
printf("serial read timeout\n");
/* there is enough data for a non block read: do read */
msglen = read(fd,&rx_data,DATA_MAXLEN);
/* check rx data length */
if (msglen != l+1)
printf("******** RX ERROR: sent %d, received %d\n",l+1,msglen);
else
continue;
/* check received data, including new line if present */
for (int i=0; i < msglen; i++) {
if (tx_data[i] == rx_data[i])
continue;
else {
printf("different rx data:|%s|\n",rx_data);
break;
}
}
/* clear RX buffer */
for (int i=0; i < msglen + 1; i++) rx_data[i] = 0;
}
}
When performing stream-based communication, be it via pipes, serial ports, or TCP sockets, you can never rely on reads to always return a full "unit of transmission" (in this case a line, but could also be a fixed-size block). The reason is that stream-based communication can always be split by any part of the transmission stack (even potentially the sender) into multiple blocks, and there is never a guarantee that a single read will always read a full block.
For example, you could always run into the race condition that your microcontroller is still sending parts of the message when you call read(), so not all characters are read exactly. In your case, that's not what you're seeing, because that would be more of a stochastic phenomenon (that would be worse with an increased interrupt load on the computer) and not so easily reproducible. Instead, because you're talking about the number 64 here, you're running into the static buffer size used in the kernel's tty driver that will only ever return at most 64 bytes at once, regardless of what the specified read size actually is. However, in other cases it could still be that you'll see additional failures by the kernel returning only the first couple of characters of a line in the first read(), and the rest in the second, depending on precise timing details -- you've probably not seen that yet, but it's bound to happen at some point.
The only reliable way to properly implement communication protocols in streaming situations (serial port, pipes, TCP sockets, etc.) is to consider the following:
For fixed-size data (e.g. communication units that are always N bytes in size) to loop around a read() call until you've read exactly the right amount of bytes (reads that follow an incomplete read would obviously ask for less bytes than the original read, just to make up the difference)
For variable-size data (for example communication units that are separated by a line end character) you have two options: either you read only one character at a time until you reach the end-of-line character (inefficient, uses lots of syscalls), or you keep track of the communication state via a large enough buffer that you constantly fill with read() operations until the buffer contains a line-end character, at which point you remove that line from the buffer (but keep the rest) and process that.
As a complete aside, if you're doing anything with serial communication, I can very much recommend the excellent libserialport library (LGPLv3 license) that makes working with serial ports a lot easier -- and has the benefit of being cross-platform. (Doesn't help with your issue, just thought that I'd mention it.)
Upgrading from linux kernel version 5.13.0-40-generic to 5.13.0-51-generic solved the problem.

VGA pixel grouping on STM32

I have some code that displays a single pixel on screen through VGA but am a bit stuck on how I could set multiple pixels on screen where I want them. I set up two Timers for Vertical Sync and Horizontal Sync then using the V-Sync interrupt, I set a flag to allow PA8 to toggle and output a pixel at the correct timing based on the SetCompare value I set on the timer's channel. The STM32f103c8 is also overclocked to 128MHz. Here's the code:
#include "Arduino.h"
//640x480 at 60Hz
static volatile int vflag = 0;
void setup() {
#define FLASH_ACR (*(volatile uint32_t*)(0x40022000))
FLASH_ACR = 0b110010; //enable flash prefetch and wait state to increase stability at higher freq
pinMode(PA0, PWM); //31,468.75Hz (Horizontal Sync) (Channel 1)
Timer2.pause();
Timer2.setOverflow(4067); //reload register value
Timer2.setPrescaleFactor(1); //number that divides main clock
Timer2.setCompare(1, 488); //12% duty cycle (Syncpulse/Wholeline)
Timer2.setCompare(2, 2000); //0-4067 = vertical line going left or right respectively
Timer2.attachInterrupt(2, TRIGGER);
Timer2.refresh();
Timer2.resume();
pinMode(PA6, PWM); //60Hz (Vertical Sync) (Channel 1)
Timer3.pause();
Timer3.setOverflow(4183); //reload register value
Timer3.setPrescaleFactor(510); //number that divides main clock
Timer3.setCompare(1, 16); //0.38% duty cycle (Syncpulse/Wholeframe)
Timer3.setCompare(2, 2000); //0-4183 = horizontal line going up or down respectively
Timer3.attachInterrupt(2, TRIGGER2);
Timer3.refresh();
Timer3.resume();
pinMode(PA8, OUTPUT); //need to set PinMode in order for the ODR register to work
}
void loop() {
}
void TRIGGER(){
if(vflag==1){
__asm__ volatile (
"ldr r0, =(0x4001080C) \n\t" //GPIOA base address is 0x40010800 and ODR offset is 0x0C
"ldr r1, =(1<<8) \n\t" //turn on PA8
"ldr r2, =0 \n\t" //turn off PA8
"str r1, [r0] \n\t" //turn on PA8
"str r2, [r0] \n\t" //turn off PA8
);
vflag = 0; //we set the vflag back to zero when were done outputing pixels.
}
}
I understand there's graphical defects/glitches and the code can be improved on but I'm trying to focus on how in theory this works. What I want to do is have a word display on screen, that word will be made up of letters, and those letters will be made up of groups of pixels. So then whats the best (or simplest) way to group pixels and execute them multiple times on-screen? Or how is this usually done?
I do not code for STM32 so even the code looks foreign to me however it sounds like you are hard-coding the individual pixels with timer... and generating VGA signal by some GPIO. That combination of methods is problematic to use for programmable graphics.
I am using AVR32 (UC3A with much slower clock then yours) to doing VGA image using:
screen buffer (videoram)
simply I have entire screen image stored in MCU memory. So you can simply change it contents without changing the VGA output code ...
The problem is you need to have enough memory for the image (encoded in a way to enable direct transfer to VGA connector). I am using AVR32 with 16+32+32 KByte of RAM but most MCUs have much less RAM (static images can be stored in EPROM but then it would not be possible to change the image output). So in case you do not have enough either lower resolution to fit into memory or add external memory to your system.
use integrated HW peripherial for VGA signal generation
I have more versions of VGA signal generation working:
SDRAM ... using SDRAM interface of the MCU
SMC ... using SMC interface of the MCU
SSC ... using synchronous serial interface
It all boils down to copying the screen buffer to IO interface at the VGA dot clock (~30MHz). Then on HW side combining the used MCU pins into VGA signals
for speed you can use DMA.
On top of all this you need to generate the sync signals and that is all.
So look at your MCU datasheet and find interface capable of synchronous transfer at least 3 bit data (R,G,B) with VGA dot clock speed. The closer the clock is to VGA dot clock the better (as some VGA monitors and LCDs do not tolerate too big difference)
the sync signals can be hardcoded or even encoded in the video ram.
The fastest is to use serial interface but the output is just B&W instead of RGB (unless you got 3 SSC units/channels) however you can send entire 8/16/32 pixels at once or by DMA directly so the MCU has time for other stuff and also requires much less VRAM.
My favourite is SDRAM interface (using just its data bus)
Here image from mine system:
Mine interconnection looks like this (using MCUs SDRAM interface version):
VGA <- AT32UC3A0512
R PX10 (EBI_D0)
G PX09 (EBI_D1)
B PX08 (EBI_D2)
Bright PX07 (EBI_D3)*
HS PA03
VS PA04
Here the relevant source:
VGA_EBI_SDRAMC.h:
//------------------------------------------------------------------------------------------------
#define _PA_VGA_HS 8
#define _PA_VGA_VS 16
#define _PAmo 24
volatile avr32_gpio_port_t *port_PA=&GPIO.port[AVR32_PIN_PA00>>5];
volatile U8 *SDRAM=(U8*)AVR32_EBI_CS0_ADDRESS;
//------------------------------------------------------------------------------------------------
//--- VGA 640x480x4 60Hz -------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
#define VRAM_xs 304
#define VRAM_ys 400
#define VRAM_bs 4
#define VRAM_ls (VRAM_xs>>1)
U8 VRAM[VRAM_ls*VRAM_ys];
U8 VRAM_empty[VRAM_ls];
// Horizontal timing [us]
#define VGA_t0 3
#define VGA_t1 5
#define VGA_t2 32
// Vertikal timing [lines ~31.817us] aby voslo viac bodov tak je to natiahnute na 32us++
#define VGA_ys 525
#define VGA_VS 2
#define VGA_y0 (36+40)
#define VGA_y1 (VGA_y0+VRAM_ys)
//------------------------------------------------------------------------------------------------
void VGA_init();
void VGA_screen();
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
void VGA_init()
{
system_init();
Disable_global_interrupt();
gpio_configure_pins(port_PA,_PAmo,GPIO_DIR_OUTPUT|GPIO_INIT_HIGH);
static const gpio_map_t EBI_GPIO_MAP[] =
{
{ AVR32_EBI_DATA_0_PIN, AVR32_EBI_DATA_0_FUNCTION},
{ AVR32_EBI_DATA_1_PIN, AVR32_EBI_DATA_1_FUNCTION},
{ AVR32_EBI_DATA_2_PIN, AVR32_EBI_DATA_2_FUNCTION},
{ AVR32_EBI_DATA_3_PIN, AVR32_EBI_DATA_3_FUNCTION},
};
gpio_enable_module(EBI_GPIO_MAP, sizeof(EBI_GPIO_MAP) / sizeof(EBI_GPIO_MAP[0]));
AVR32_SDRAMC.mr=0; // normal mode
AVR32_SDRAMC.tr=0; // no refresh (T=0)
AVR32_SDRAMC.cr=
(AVR32_SDRAMC_CR_NC_11_COLUMN_BITS <<AVR32_SDRAMC_CR_NC_OFFSET)
|(AVR32_SDRAMC_CR_NR_13_ROW_BITS <<AVR32_SDRAMC_CR_NR_OFFSET)
|(AVR32_SDRAMC_CR_NB_TWO_BANKS <<AVR32_SDRAMC_CR_NB_OFFSET)
|(AVR32_SDRAMC_CAS_ONE_CYCLE <<AVR32_SDRAMC_CR_CAS_OFFSET)
|(AVR32_SDRAMC_DBW_16_BITS <<AVR32_SDRAMC_CR_DBW_OFFSET)
|(0 <<AVR32_SDRAMC_TWR_OFFSET)
|(0 <<AVR32_SDRAMC_TRC_OFFSET)
|(0 <<AVR32_SDRAMC_TRP_OFFSET)
|(0 <<AVR32_SDRAMC_TRCD_OFFSET)
|(0 <<AVR32_SDRAMC_TRAS_OFFSET)
|(0 <<AVR32_SDRAMC_TXSR_OFFSET);
AVR32_SDRAMC.hsr=AVR32_SDRAMC_HSR_DA_MASK;
AVR32_SDRAMC.mdr=AVR32_SDRAMC_MDR_MD_SDRAM;
// map SDRAM CS -> memory space
AVR32_HMATRIX.sfr[AVR32_EBI_HMATRIX_NR]|=1<<AVR32_EBI_SDRAM_CS;
AVR32_HMATRIX.sfr[AVR32_EBI_HMATRIX_NR];
U32 a;
for (a=0;a<VRAM_ls*VRAM_ys;a++) VRAM[a]=0;
for (a=0;a<VRAM_ls;a++) VRAM_empty[a]=0;
}
//------------------------------------------------------------------------------------------------
void VGA_screen()
{
U32 a,x,y,c,PA,t0;
wait_start(t0);
for (;;)
{
for (PA=_PAmo,a=0,y=0;y<VGA_ys;y++)
{
wait_start(t0);
if (y== 0) PA^=_PA_VGA_VS; else PA^=0; // VS on
if (y==VGA_VS) PA^=_PA_VGA_VS; else PA^=0; // VS off
PA^=_PA_VGA_HS; // HS on
port_PA->ovrc=PA^_PAmo;
port_PA->ovrs=PA;
wait_us(t0,VGA_t0);
PA^=_PA_VGA_HS; // HS off
port_PA->ovrc=PA^_PAmo;
port_PA->ovrs=PA;
wait_us(t0,VGA_t1);
*SDRAM=0; // blank (black)
if ((y>=VGA_y0)&&(y<VGA_y1))
for (x=0;x<VRAM_ls;x++)
{
c=VRAM[a];
*SDRAM=c>>4; // write pixel into SDRAM interface (address is ignored as I use only data bus pins)
a++;
*SDRAM=c; // write pixel into SDRAM interface (address is ignored as I use only data bus pins)
}
*SDRAM=0; // blank (black)
wait_us(t0,VGA_t2);
}
}
}
//------------------------------------------------------------------------------------------------
Main.cpp:
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
#include "System\include.h"
#include "pic_zilog_inside.h"
//#include "VGA_EBI_SMC.h"
#include "VGA_EBI_SDRAMC.h"
//#include "VGA_SSC.h"
//------------------------------------------------------------------------------------------------
void pic_copy(U8 *dst,U32 dst_xs,U32 dst_ys,U32 dst_bs,U8 *src,U32 src_xs,U32 src_ys,U32 src_bs)
{
U32 x0,y0,a0,l0;
U32 x1,y1,a1,l1;
U32 a; U8 c,m;
l0=1; l1=1;
if (dst_bs==1) l0=dst_xs>>3;
if (dst_bs==2) l0=dst_xs>>2;
if (dst_bs==4) l0=dst_xs>>1;
if (dst_bs==8) l0=dst_xs;
if (src_bs==1) l1=src_xs>>3;
if (src_bs==2) l1=src_xs>>2;
if (src_bs==4) l1=src_xs>>1;
if (src_bs==8) l1=src_xs;
for (a0=0;a0<dst_ys*l0;a0++) dst[a0]=0;
for (y0=0;y0<dst_ys;y0++)
{
y1=(y0*(src_ys-1))/(dst_ys-1);
a0=l0*y0;
a1=l1*y1;
for (x0=0;x0<dst_xs;x0++)
{
x1=(x0*(src_xs-1))/(dst_xs-1);
c=0;
if (src_bs==1)
{
c=src[a1+(x1>>3)];
c>>=7-(x1&7);
c&=1;
}
if (src_bs==4)
{
c=src[a1+(x1>>1)];
if (U32(x0&1)==0) c>>=4;
c&=15;
}
if (dst_bs==1)
{
c<<=7-(x0&7);
a=a0+(x0>>3);
dst[a]|=c; if (!c) dst[a]^=c;
}
if (dst_bs==4)
{
if (c) c=15;
if (U32(x0&1)==0) { c<<=4; m=0x0F; } else m=0xF0;
a=a0+(x0>>1);
dst[a]&=m;
dst[a]|=c;
}
}
}
}
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
int main(void)
{
VGA_init();
pic_copy
(
(U8*)VRAM,
VRAM_xs,
VRAM_ys,
VRAM_bs,
(U8*)pic_zilog_inside,
pic_zilog_inside_xs,
pic_zilog_inside_ys,
pic_zilog_inside_bs
);
VGA_screen();
}
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
pic_zilog_inside.h:
const U32 pic_zilog_inside_xs=640;
const U32 pic_zilog_inside_ys=480;
const U32 pic_zilog_inside_bs=1;
const U32 pic_zilog_inside[]= // hard coded image
{
0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,
0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0x80000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,
0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000001,0x80000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,
...
0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000001,0x80000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,
0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000000,0x00000001,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,
0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,0xFFFFFFFF,
};
The function pic_copy just copies hard-coded image into VRAM.
The function VGA_screen() creates the VGA signal in endless loop so other tasks must be encoded into ISRs or hard coded into pause code or between individual frames (however this is really demanding on mine setup as I got small MCU clock so there is not much room for other stuff to do). The VRAM is encoded in 16 colors (4 bits per pixel)
8 4 2 1
Brightness B G R
The brightness should just adds some voltage to R,G,B with few resistors and diodes but newer implemented it on HW side instead I have this circuit (8 colors only):
The diodes must be fast with the same barrier voltage and capacitors are 1nF. Its to avoid glitching of the image due to used interface data bus timing. Also the diodes are needed for the brightness if added in future for more info see the R2R current problem in here:
Generating square wave in AVR Assembly without PWM
[Edit1] I made huge changes in code:
//------------------------------------------------------------------------------------------------
//--- VGA EBI SDRAMC DMACA ver: 3.0 --------------------------------------------------------------
//------------------------------------------------------------------------------------------------
/*
VGA <- AT32UC3A3256
R PX10 (EBI_D0)
G PX09 (EBI_D1)
B PX08 (EBI_D2)
Bright PX07 (EBI_D3)*
/HS PX58
/VS PX59
Button PB10 (Bootloader)
debug PX54 (timing of TC00)
*/
//------------------------------------------------------------------------------------------------
//#define _Debug AVR32_PIN_PX54
#define _Button AVR32_PIN_PB10
#define _VGA_HS (1<<(AVR32_PIN_PX58&31))
#define _VGA_VS (1<<(AVR32_PIN_PX59&31))
#define _VGA_mask (_VGA_HS|_VGA_VS)
volatile avr32_gpio_port_t *port_VGA=&GPIO.port[AVR32_PIN_PX58>>5];
volatile U8 *SDRAM=(U8*)AVR32_EBI_CS0_ADDRESS;
//------------------------------------------------------------------------------------------------
//--- VGA 640x480x4 60Hz -------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
#define VRAM_xs 256
#define VRAM_ys 192
#define VRAM_bs 8
#define VRAM_ls ((VRAM_xs*VRAM_bs)>>3)
volatile static U8 VRAM[VRAM_ls*VRAM_ys];
/*------------------------------------------------------------------------------------------------
|------------------------|
| V sync |
| |----------------------|
| | V back |
| | |------------------| |
|H|H| |H|
|s|b| Video 640x480 |f|
|y|a| 525 lines |r|
|n|c| 60 Hz |o|
|c|k| |n|
| | |------------------|t|
| | V front |
|------------------------|
//----------------------------------------------------------------------------------------------*/
// VGA 640x480 60Hz H timing [pixels] dot clock = 25.175MHz
#define VGA_H_front 16
#define VGA_H_sync 96
#define VGA_H_back 48
#define VGA_H_video 640
// VGA 640x480 60Hz H timing [us] Ht = H/25.175, Hf = Vf*(VGA_V_video+VGA_V_front+VGA_V_sync+VGA_V_back)
#define VGA_Ht_front 1
#define VGA_Ht_sync 2
#define VGA_Ht_back 1
#define VGA_Hf 31500
// VGA 640x480 60Hz V timing [lines]
#define VGA_V_video 480
#define VGA_V_front 10
#define VGA_V_sync 2
#define VGA_V_back 33
#define VGA_Vf 60
//------------------------------------------------------------------------------------------------
void VGA_init();
void VGA_screen();
//------------------------------------------------------------------------------------------------
//------------------------------------------------------------------------------------------------
__attribute__((__interrupt__)) static void ISR_TC00_VGA() // TC0 chn:0 VGA horizontal frequency
{ // 8us every 31.75us -> 25% of CPU power
tc_read_sr(&AVR32_TC0,0); // more centered image requires +1 us to VGA_Ht_back -> 28% CPU power
#define y0 (VGA_V_video)
#define y1 (y0+VGA_V_front)
#define y2 (y1+VGA_V_sync)
#define y3 (y2+VGA_V_back)
#define yscr0 ((VGA_V_video>>1)-VRAM_ys)
#define yscr1 (yscr0+(VRAM_ys<<1))
static volatile U8 *p;
static volatile U32 y=y3;
#ifdef _Debug
gpio_set_gpio_pin(_Debug);
#endif
// init state
if (y>=y3){ y=0; p=VRAM; port_VGA->ovrs=_VGA_mask; }
// VS sync
if (y==y1) port_VGA->ovrc=_VGA_VS; // VS = L
if (y==y2) port_VGA->ovrs=_VGA_VS; // VS = H
// HS sync
wait_us(VGA_Ht_front); // front
port_VGA->ovrc=_VGA_HS; // HS = L
wait_us(VGA_Ht_sync); // sync
port_VGA->ovrs=_VGA_HS; // HS = H
wait_us(VGA_Ht_back); // back
// 8bit pixelformat DMACA, scan doubler + y offset
if ((y>=yscr0)&&(y<yscr1))
{
// Enable the DMACA
AVR32_DMACA.dmacfgreg = (1 << AVR32_DMACA_DMACFGREG_DMA_EN_OFFSET);
// Src Address: the source_data address
AVR32_DMACA.sar2 = (uint32_t)p;
// Dst Address: the dest_data address
AVR32_DMACA.dar2 = (uint32_t)SDRAM;
// Linked list ptrs: not used.
AVR32_DMACA.llp2 = 0x00000000;
// Channel 2 Ctrl register low
AVR32_DMACA.ctl2l =
(0 << AVR32_DMACA_CTL2L_INT_EN_OFFSET) | // Enable interrupts
(0 << AVR32_DMACA_CTL2L_DST_TR_WIDTH_OFFSET) | // Dst transfer width: 8bit (1,2 znasobi dotclock na 2x)
(0 << AVR32_DMACA_CTL2L_SRC_TR_WIDTH_OFFSET) | // Src transfer width: 8bit
(0 << AVR32_DMACA_CTL2L_DINC_OFFSET) | // Dst address increment: increment
(0 << AVR32_DMACA_CTL2L_SINC_OFFSET) | // Src address increment: increment
(0 << AVR32_DMACA_CTL2L_DST_MSIZE_OFFSET) | // Dst burst transaction len: 1 data items (each of size DST_TR_WIDTH)
(0 << AVR32_DMACA_CTL2L_SRC_MSIZE_OFFSET) | // Src burst transaction len: 1 data items (each of size DST_TR_WIDTH)
(0 << AVR32_DMACA_CTL2L_TT_FC_OFFSET) | // transfer type:M2M, flow controller: DMACA
(1 << AVR32_DMACA_CTL2L_DMS_OFFSET) | // Destination master: HSB master 2
(0 << AVR32_DMACA_CTL2L_SMS_OFFSET) | // Source master: HSB master 1
(0 << AVR32_DMACA_CTL2L_LLP_D_EN_OFFSET) | // Not used
(0 << AVR32_DMACA_CTL2L_LLP_S_EN_OFFSET); // Not used
// Channel 2 Ctrl register high
AVR32_DMACA.ctl2h =
((VRAM_ls) << AVR32_DMACA_CTL2H_BLOCK_TS_OFFSET) | // Block transfer size
(0 << AVR32_DMACA_CTL2H_DONE_OFFSET); // Not done
// Channel 2 Config register low
AVR32_DMACA.cfg2l =
(0 << AVR32_DMACA_CFG2L_HS_SEL_DST_OFFSET) | // Destination handshaking: ignored because the dst is memory
(0 << AVR32_DMACA_CFG2L_HS_SEL_SRC_OFFSET); // Source handshaking: ignored because the src is memory.
// Channel 2 Config register high
AVR32_DMACA.cfg2h =
(0 << AVR32_DMACA_CFG2H_DEST_PER_OFFSET) | // Dest hw handshaking itf: ignored because the dst is memory.
(0 << AVR32_DMACA_CFG2H_SRC_PER_OFFSET); // Source hw handshaking itf: ignored because the src is memory.
// Enable Channel 2 : start the process.
AVR32_DMACA.chenreg = ((4 << AVR32_DMACA_CHENREG_CH_EN_OFFSET) | (4 << AVR32_DMACA_CHENREG_CH_EN_WE_OFFSET));
// DMACA is messing up first BYTE so send it by SW before DMA
*SDRAM=*p;
// scan doubler increment only every second scanline
if ((y&1)==1) p+=VRAM_ls;
}
*SDRAM=0; y++;
#ifdef _Debug
gpio_clr_gpio_pin(_Debug);
#endif
#undef y0
#undef y1
#undef y2
#undef y3
}
//------------------------------------------------------------------------------------------------
void VGA_init()
{
system_init();
Disable_global_interrupt();
gpio_configure_pin(_Button,GPIO_DIR_INPUT);
#ifdef _Debug
gpio_configure_pin(_Debug,GPIO_DIR_OUTPUT);
#endif
gpio_configure_pins(port_VGA,_VGA_mask,GPIO_DIR_OUTPUT|GPIO_INIT_HIGH);
static const gpio_map_t EBI_GPIO_MAP[] =
{
{ AVR32_EBI_DATA_0_PIN, AVR32_EBI_DATA_0_FUNCTION},
{ AVR32_EBI_DATA_1_PIN, AVR32_EBI_DATA_1_FUNCTION},
{ AVR32_EBI_DATA_2_PIN, AVR32_EBI_DATA_2_FUNCTION},
{ AVR32_EBI_DATA_3_PIN, AVR32_EBI_DATA_3_FUNCTION},
};
gpio_enable_module(EBI_GPIO_MAP, sizeof(EBI_GPIO_MAP) / sizeof(EBI_GPIO_MAP[0]));
AVR32_SDRAMC.mr=0; // normal mode
AVR32_SDRAMC.tr=0; // no refresh (T=0)
AVR32_SDRAMC.cr=
(AVR32_SDRAMC_CR_NC_11_COLUMN_BITS <<AVR32_SDRAMC_CR_NC_OFFSET)
|(AVR32_SDRAMC_CR_NR_13_ROW_BITS <<AVR32_SDRAMC_CR_NR_OFFSET)
|(AVR32_SDRAMC_CR_NB_TWO_BANKS <<AVR32_SDRAMC_CR_NB_OFFSET)
|(AVR32_SDRAMC_CAS_ONE_CYCLE <<AVR32_SDRAMC_CR_CAS_OFFSET)
|(AVR32_SDRAMC_DBW_16_BITS <<AVR32_SDRAMC_CR_DBW_OFFSET)
|(0 <<AVR32_SDRAMC_TWR_OFFSET)
|(0 <<AVR32_SDRAMC_TRC_OFFSET)
|(0 <<AVR32_SDRAMC_TRP_OFFSET)
|(0 <<AVR32_SDRAMC_TRCD_OFFSET)
|(0 <<AVR32_SDRAMC_TRAS_OFFSET)
|(0 <<AVR32_SDRAMC_TXSR_OFFSET);
AVR32_SDRAMC.hsr=AVR32_SDRAMC_HSR_DA_MASK;
AVR32_SDRAMC.mdr=AVR32_SDRAMC_MDR_MD_SDRAM;
// map SDRAM CS -> memory space
AVR32_HMATRIX.sfr[AVR32_EBI_HMATRIX_NR]|=1<<AVR32_EBI_SDRAM_CS;
AVR32_HMATRIX.sfr[AVR32_EBI_HMATRIX_NR];
for (U32 a=0;a<VRAM_ls*VRAM_ys;a++) VRAM[a]=0;
timer_init(&AVR32_TC0,0,VGA_Hf,ISR_TC00_VGA,0);
Enable_global_interrupt();
}
//------------------------------------------------------------------------------------------------
Now its enough to call VGA_init(); and the stuff runs in background using Timer and DMA between internal RAM and EBI SDRAM interface. It uses only 25% of CPU power in current configuration. However half of VRAM is wasted as only 4 bits are used so high nibel might be used for back buffering to compensate. I also downclock the stuf to 66MHz as I do not have enough RAM for higher resolutions.

How to convert arduino's digital output in terms of frequency

I am using a analog-output sound sensor module where the output of the sensor module is connected to the arduino and can see arduino is doing Ato D conversion and displaying integers from range 0 to 1023.
But I need to calculate the frequency of the sound getting measure from the sensor.
so could you help me, hwo to calculate the frequecy from this Ato D converted values from arduino.
You don't really need to to ADC conversions do you? All you need to do is detect a rising edge on the input and then count those. Since your sensor will output low-high-low sequences, and since the Arduino will register HIGH as over a certain voltage, that should be adequate.
This code will measure up to around 200 kHz, from an input connected to digital pin 8 on the board:
// Input: Pin D8
volatile boolean first;
volatile boolean triggered;
volatile unsigned long overflowCount;
volatile unsigned long startTime;
volatile unsigned long finishTime;
// timer overflows (every 65536 counts)
ISR (TIMER1_OVF_vect)
{
overflowCount++;
} // end of TIMER1_OVF_vect
ISR (TIMER1_CAPT_vect)
{
// grab counter value before it changes any more
unsigned int timer1CounterValue;
timer1CounterValue = ICR1; // see datasheet, page 117 (accessing 16-bit registers)
unsigned long overflowCopy = overflowCount;
// if just missed an overflow
if ((TIFR1 & bit (TOV1)) && timer1CounterValue < 0x7FFF)
overflowCopy++;
// wait until we noticed last one
if (triggered)
return;
if (first)
{
startTime = (overflowCopy << 16) + timer1CounterValue;
first = false;
return;
}
finishTime = (overflowCopy << 16) + timer1CounterValue;
triggered = true;
TIMSK1 = 0; // no more interrupts for now
} // end of TIMER1_CAPT_vect
void prepareForInterrupts ()
{
noInterrupts (); // protected code
first = true;
triggered = false; // re-arm for next time
// reset Timer 1
TCCR1A = 0;
TCCR1B = 0;
TIFR1 = bit (ICF1) | bit (TOV1); // clear flags so we don't get a bogus interrupt
TCNT1 = 0; // Counter to zero
overflowCount = 0; // Therefore no overflows yet
// Timer 1 - counts clock pulses
TIMSK1 = bit (TOIE1) | bit (ICIE1); // interrupt on Timer 1 overflow and input capture
// start Timer 1, no prescaler
TCCR1B = bit (CS10) | bit (ICES1); // plus Input Capture Edge Select (rising on D8)
interrupts ();
} // end of prepareForInterrupts
void setup ()
{
Serial.begin(115200);
Serial.println("Frequency Counter");
// set up for interrupts
prepareForInterrupts ();
} // end of setup
void loop ()
{
// wait till we have a reading
if (!triggered)
return;
// period is elapsed time
unsigned long elapsedTime = finishTime - startTime;
// frequency is inverse of period, adjusted for clock period
float freq = F_CPU / float (elapsedTime); // each tick is 62.5 ns at 16 MHz
Serial.print ("Took: ");
Serial.print (elapsedTime);
Serial.print (" counts. ");
Serial.print ("Frequency: ");
Serial.print (freq);
Serial.println (" Hz. ");
// so we can read it
delay (500);
prepareForInterrupts ();
} // end of loop
More discussion and information at Timers and counters.
As I suggested you in the other thread, the best is to
filter
amplify
apply a threshold
measure the time between edges
Steps 1, 2, 3 can be performed in software but it is MUCH better to perform them in hardware. The fourth step is what Nick Gammon solution is about... But you have to first make steps 1,2,3 in HW otherwise you will receive a lot of "noisy" readings

CUDA Programming: Compilation Error

I am making a CUDA program that implements the data parallel prefix sum calculation operating upon N numbers. My code is also supposed to generate the numbers on the host using a random number generator. However, I seem to always run into a "unrecognized token" and "expected a declaration" error on the ending bracket of int main when attempting to compile. I am running the code on Linux.
#include <stdio.h>
#include <cuda.h>
#include <stdlib.h>
#include <math.h>
__global__ void gpu_cal(int *a,int i, int n) {
int tid = blockIdx.x * blockDim.x + threadIdx.x;
if(tid>=i && tid < n) {
a[tid] = a[tid]+a[tid-i];
}
}
int main(void)
{
int key;
int *dev_a;
int N=10;//size of 1D array
int B=1;//blocks in the grid
int T=10;//threads in a block
do{
printf ("Some limitations:\n");
printf (" Maximum number of threads per block = 1024\n");
printf (" Maximum sizes of x-dimension of thread block = 1024\n");
printf (" Maximum size of each dimension of grid of thread blocks = 65535\n");
printf (" N<=B*T\n");
do{
printf("Enter size of array in one dimension, currently %d\n",N);
scanf("%d",&N);
printf("Enter size of blocks in the grid, currently %d\n",B);
scanf("%d",&B);
printf("Enter size of threads in a block, currently %d\n",T);
scanf("%d",&T);
if(N>B*T)
printf("N>B*T, this will result in an incorrect result generated by GPU, please try again\n");
if(T>1024)
printf("T>1024, this will result in an incorrect result generated by GPU, please try again\n");
}while((N>B*T)||(T>1024));
cudaEvent_t start, stop; // using cuda events to measure time
float elapsed_time_ms1, elapsed_time_ms3;
int a[N],gpu_result[N];//for result generated by GPU
int cpu_result[N];//CPU result
cudaMalloc((void**)&dev_a,N * sizeof(int));//allocate memory on GPU
int i,j;
srand(1); //initialize random number generator
for (i=0; i < N; i++) // load array with some numbers
a[i] = (int)rand() ;
cudaMemcpy(dev_a, a , N*sizeof(int),cudaMemcpyHostToDevice);//load data from host to device
cudaEventCreate(&start); // instrument code to measure start time
cudaEventCreate(&stop);
cudaEventRecord(start, 0);
//GPU computation
for(j=0;j<log(N)/log(2);j++){
gpu_cal<<<B,T>>>(dev_a,pow(2,j),N);
cudaThreadSynchronize();
}
cudaMemcpy(gpu_result,dev_a,N*sizeof(int),cudaMemcpyDeviceToHost);
cudaEventRecord(stop, 0); // instrument code to measue end time
cudaEventSynchronize(stop);
cudaEventElapsedTime(&elapsed_time_ms1, start, stop );
printf("\n\n\nTime to calculate results on GPU: %f ms.\n", elapsed_time_ms1); // print out execution time
//CPU computation
cudaEventRecord(start, 0);
for(i=0;i<N;i++)
{
cpu_result[i]=0;
for(j=0;j<=i;j++)
{
cpu_result[i]=cpu_result[i]+a[j];
}
}
cudaEventRecord(stop, 0); // instrument code to measue end time
cudaEventSynchronize(stop);
cudaEventElapsedTime(&elapsed_time_ms3, start, stop );
printf("Time to calculate results on CPU: %f ms.\n\n", elapsed_time_ms3); // print out execution time
//Error check
for(i=0;i < N;i++) {
if (gpu_result[i] != cpu_result[i] ) {
printf("ERROR!!! CPU and GPU create different answers\n");
break;
}
}
//Calculate speedup
printf("Speedup on GPU compared to CPU= %f\n", (float) elapsed_time_ms3 / (float) elapsed_time_ms1);
printf("\nN=%d",N);
printf("\nB=%d",B);
printf("\nT=%d",T);
printf("\n\n\nEnter '1' to repeat, or other integer to terminate\n");
scanf("%d",&key);
}while(key == 1);
cudaFree(dev_a);//deallocation
return 0;
}​
The very last } in your code is a Unicode character. If you delete this entire line, and retype the }, the error will be gone.
There are two compile errors in your code.
First, Last ending bracket is a unicode character, so you should resave your code as unicode or delete and rewrite the last ending bracket.
Second, int type variable N which used at this line - int a[N],gpu_result[N];//for result generated by GPU
was declared int type, but it's not allowed in c or c++ compiler, so you should change the N declaration as const int N.

Pulse width modulation (PWM) on AVR Studio

I'm trying to use PWM for an LED on an ATmega8, any pin of port B. Setting up timers has been a annoying, and I don't know what to do with my OCR1A. Here's my code, and I'd love some feedback.
I'm just trying to figure out how use PWM. I know the concept, and OCR1A is supposed to be the fraction of the whole counter time I want the pulse on.
#define F_CPU 1000000 // 1 MHz
#include <avr/io.h>
#include <avr/delay.h>
#include <avr/interrupt.h>
int main(void){
TCCR1A |= (1 << CS10) | (1 << CS12) | (1 << CS11);
OCR1A = 0x0000;
TCCR1A |= ( 0 << WGM11 ) | ( 1 << WGM10 ) | (WGM12 << 1) | (WGM13 << 0);
TCCR1A |= ( 1 << COM1A0 ) | ( 0 << COM1A1 );
TIMSK |= (1 << TOIE1); // Enable timer interrupt
DDRB = 0xFF;
sei(); // Enable global interrupts
PORTB = 0b00000000;
while(1)
{
OCR1A = 0x00FF; //I'm trying to get the timer to alternate being on for 100% of the time,
_delay_ms(200);
OCR1A = 0x0066; // Then 50%
_delay_ms(200);
OCR1A = 0x0000; // Then 0%
_delay_ms(200);
}
}
ISR (TIMER1_COMA_vect) // timer0 overflow interrupt
{
PORTB =~ PORTB;
}
No, this is not the way how you should do a PWM. For example, how do you set a PWM rate of, for example, 42% with it? Also, the code size is big, it can be done in a much more efficient way. Also, you waste a 16 bit timer to do 8 bit operations. You have 2x 8 bit timers (Timer/Counter 0 and 2), and one 16 bit timer, Timer/Counter 1.
It's also a bad idea to set unused portpins to output. All portpins which are not connected to anything, should be left as inputs.
The ATmega8 has a built-in PWM generator on timers 1 and 2, there is no need in simulating it through software. You don't even have to set your ports manually (you only have to set the corresponding portpin to output)
You don't even need any interrupt.
#define fillrate OCR2A
//...
// main()
PORTB=0x00;
DDRB=0x08; //We use PORTB.3 as output, for OC2A, see the atmega8 reference manual
// Mode: Phase correct PWM top=0xFF
// OC2A output: Non-Inverted PWM
TCCR2A=0x81;
// Set the speed here, it will depend on your clock rate.
TCCR2B=0x02;
// for example, this will alternate between 75% and 42% PWM
while(1)
{
fillrate = 191; // ca. 75% PWM
delay_ms(2000);
fillrate = 107; // ca. 42% PWM
delay_ms(2000);
}
Note that you can use another LED with another PWM, by using the same timer and setting OCR2B instead of OCR2A. Don't forget to set TCCR2A to enable OCR2B as output for your PWM, as in this example only OCR2A is allowed.
You need to initialize your OCR1A with these two lines:
TCCR1A = (1 << WGM10) | (1 << COM1A1);
TCCR1B = (1 << CS10) | (1 << WGM12);
And then use this:
OCR1A = in
And know that the range is 0-255. Count your percentages, and there you have it!
#define F_CPU 1000000 // 1 MHz
#include <avr/io.h>
#include <avr/delay.h>
#include <avr/interrupt.h>
int main(void){
TCCR1A = (1 << WGM10) | (1 << COM1A1);
TCCR1B = (1 << CS10) | (1 << WGM12);
DDRB = 0xFF;
sei(); // Enable global interrupts
PORTB = 0b00000000;
while(1)
{
OCR1A = 255;
_delay_ms(200);
OCR1A = 125;
_delay_ms(200);
OCR1A = 0;
_delay_ms(200);
}
}

Resources