Skip to content
Snippets Groups Projects
Commit e94ec788 authored by Sam Calisch's avatar Sam Calisch
Browse files

working on radio link for stage, moved code from step project

parent 0c260430
No related branches found
No related tags found
No related merge requests found
Pipeline #
#!/usr/bin/env python
import numpy as np
from math import *
import serial, time
import struct
import sys
import socket
import matplotlib.pyplot as plt
import matplotlib.animation as animation
import bitstring
n_samples = 20
def read_as5013_12bit(bytes):
return (bitstring.Bits(bytes=bytes, length=16)<<4).unpack('uint:16')[0]
#signed 12 bit val comes in two bytes
#return struct.unpack("<h",bytearray([ (high<<4) , low<<4 ]))[0]
def read(ser=None):
if ser is None:
print "No serial connection!"
else:
c = ser.read(n_samples)
data = [read_as5013_12bit(c[x:x+2]) for x in xrange(0,n_samples,2)]
return data
def main():
try:
ser = serial.Serial(port='/dev/tty.usbserial-FT9L3KWR',baudrate=1000000,timeout=1.)
ser.isOpen()
print "Established serial connection."
except(OSError):
#no serial port
print "Couldn't find the serial port, entering debug mode."
ser = None
ser.flush()
while True:
#connection, address = serversocket.accept()
try:
data = np.asarray(read(ser=ser))
print data[1::2] - data[::2]
except(KeyboardInterrupt):
break
#if data:
# clientsocket.send(data)
print "quitting"
ser.close()
if __name__ == '__main__':
main()
//read raw values from as5013 hall effect array ic
//read raw values from as5013 hall effect array ic and pass to uarte
//sec, 2017
#include "radio.h"
//as5013 registers
#define ctrl_reg 0x0F
#define y_res_reg 0x11
#define T_ctrl_reg 0x2D
#define c_raw_values_start 0x16 //starting address for raw sensor values
#define n_tx_bytes 1 //only need transmit the start read address
......@@ -11,27 +13,39 @@
#define scl_pin 0 //XL1
#define sda_pin 1 //XL2
#define rst_pin 3 //A1
static uint8_t txdata[n_tx_bytes] = {0};
static uint8_t rxdata[n_rx_bytes] = {0};
//raw sensor values
volatile int16_t c1,c2,c3,c4,c5;
//uarte
const uint8_t pin_rx = 8;
const uint8_t pin_tx = 6;
uint16_t last_tx_time = 0;
uint16_t tx_period = 100; //ms
void twi_tx(){
// triggering the STARTTX task
NRF_TWIM0->TASKS_STARTTX = 1;
while( !(NRF_TWIM0->EVENTS_STOPPED) ){}
}
void twi_rx(){
// triggering the STARTRX task
NRF_TWIM0->TASKS_STARTRX = 1;
while( !(NRF_TWIM0->EVENTS_STOPPED) ){}
//
//UARTE
//
void uarte_setup(){
//uart with dma
NRF_UARTE0->PSEL.TXD = (pin_tx << UARTE_PSEL_TXD_PIN_Pos) & UARTE_PSEL_TXD_PIN_Msk;
NRF_UARTE0->PSEL.RXD = (pin_rx << UARTE_PSEL_RXD_PIN_Pos) & UARTE_PSEL_RXD_PIN_Msk;
NRF_UARTE0->CONFIG = ((UART_CONFIG_PARITY_Excluded << UARTE_CONFIG_PARITY_Pos) & UARTE_CONFIG_PARITY_Msk)
| ((UARTE_CONFIG_HWFC_Disabled << UARTE_CONFIG_HWFC_Pos) & UARTE_CONFIG_HWFC_Msk);
NRF_UARTE0->BAUDRATE = UART_BAUDRATE_BAUDRATE_Baud1M;
NRF_UARTE0->ENABLE = (UARTE_ENABLE_ENABLE_Enabled << UARTE_ENABLE_ENABLE_Pos) & UARTE_ENABLE_ENABLE_Msk;
NRF_UARTE0->TXD.MAXCNT = n_rx_bytes;
}
void setup() {
Serial.begin(115200);
//
//TWI
//
void twi_set_cnts(uint8_t n_tx, uint8_t n_rx){
NRF_TWIM0->TXD.MAXCNT = (n_tx << TWIM_TXD_MAXCNT_MAXCNT_Pos) & TWIM_TXD_MAXCNT_MAXCNT_Msk;
NRF_TWIM0->RXD.MAXCNT = (n_rx << TWIM_RXD_MAXCNT_MAXCNT_Pos) & TWIM_RXD_MAXCNT_MAXCNT_Msk;
}
void twi_setup(){
//Need to switch to internal LFCLK to disconnect from XL1 and XL2
NRF_CLOCK->LFCLKSRC = 0; //disconnect XL1 AND XL2 FROM LFCLK?
NRF_CLOCK->EVENTS_LFCLKSTARTED = 0;
......@@ -42,12 +56,6 @@ void setup() {
NRF_GPIO->PIN_CNF[scl_pin] = (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos) & GPIO_PIN_CNF_DRIVE_Msk;
NRF_GPIO->PIN_CNF[sda_pin] = (GPIO_PIN_CNF_DRIVE_S0D1 << GPIO_PIN_CNF_DRIVE_Pos) & GPIO_PIN_CNF_DRIVE_Msk;
NRF_GPIO->DIRCLR = (1<<scl_pin)|(1<<sda_pin); //set SDA/SCL as inputs (likely not necessary)
NRF_GPIO->DIRSET = (1<<rst_pin); //set AS5013 nRESET pin as output
NRF_GPIO->OUTCLR = (1<<rst_pin); //hardware reset
delay(1);
NRF_GPIO->OUTSET = (1<<rst_pin); //turn on as5013
delay(1);
NRF_TWIM0->PSEL.SCL = ((scl_pin << TWIM_PSEL_SCL_PIN_Pos) & TWIM_PSEL_SCL_PIN_Msk)
| ((TWIM_PSEL_SCL_CONNECT_Connected << TWIM_PSEL_SCL_CONNECT_Pos) & TWIM_PSEL_SCL_CONNECT_Msk);
......@@ -57,37 +65,85 @@ void setup() {
NRF_TWIM0->ADDRESS = (0x41 << TWI_ADDRESS_ADDRESS_Pos) & TWI_ADDRESS_ADDRESS_Msk;
NRF_TWIM0->TXD.PTR = (uint32_t)(&txdata);
NRF_TWIM0->RXD.PTR = (uint32_t)(&rxdata);
NRF_TWIM0->TXD.MAXCNT = (n_tx_bytes << TWIM_TXD_MAXCNT_MAXCNT_Pos) & TWIM_TXD_MAXCNT_MAXCNT_Msk;
NRF_TWIM0->RXD.MAXCNT = (n_rx_bytes << TWIM_RXD_MAXCNT_MAXCNT_Pos) & TWIM_RXD_MAXCNT_MAXCNT_Msk;
twi_set_cnts(n_tx_bytes, n_rx_bytes);
//set up short between LASTTX and STOP and between LASTRX and STOP
NRF_TWIM0->SHORTS = ((TWIM_SHORTS_LASTTX_STOP_Enabled << TWIM_SHORTS_LASTTX_STOP_Pos) & TWIM_SHORTS_LASTTX_STOP_Msk)
| ((TWIM_SHORTS_LASTRX_STOP_Enabled << TWIM_SHORTS_LASTRX_STOP_Pos) & TWIM_SHORTS_LASTRX_STOP_Msk);
//NRF_TWIM0->ENABLE = (TWI_ENABLE_ENABLE_Enabled << TWI_ENABLE_ENABLE_Pos) & TWI_ENABLE_ENABLE_Msk;
//There's a typo in nrf52_bitfields, so we set this manually.
NRF_TWIM0->ENABLE = (6 << TWI_ENABLE_ENABLE_Pos) & TWI_ENABLE_ENABLE_Msk;
}
void twi_tx(){
// clear the stopped event
NRF_TWIM0->EVENTS_STOPPED = 0;
// triggering the STARTTX task
NRF_TWIM0->TASKS_STARTTX = 1;
while( !(NRF_TWIM0->EVENTS_STOPPED) ){}
}
void twi_rx(){
// clear the stopped event
NRF_TWIM0->EVENTS_STOPPED = 0;
// trigger the STARTRX task
NRF_TWIM0->TASKS_STARTRX = 1;
while( !(NRF_TWIM0->EVENTS_STOPPED) ){}
}
//
//AS5013
//
void as5013_setup(){
NRF_GPIO->DIRSET = (1<<rst_pin); //set AS5013 nRESET pin as output
NRF_GPIO->OUTCLR = (1<<rst_pin); //hardware reset
delayMicroseconds(10);
NRF_GPIO->OUTSET = (1<<rst_pin); //turn on as5013
delayMicroseconds(1000);
//Loop check ctrl_reg until the value F0h or F1h is present
delay(1); //in practice even no delay is fine.
//config sensor
//todo: experiment with setting values
}
void as5013_read(){
//read raw values
twi_set_cnts(n_tx_bytes, n_rx_bytes);
txdata[0] = c_raw_values_start; //set up to read from this address
twi_tx();
twi_rx();
//assume idle mode, so we must read from Y_res_int register at end to trigger new conversion
twi_set_cnts(1, 1);
txdata[0] = y_res_reg;
twi_tx();
twi_rx();
}
//
//main
//
void setup() {
Serial.begin(115200);
//uarte_setup();
twi_setup();
as5013_setup();
radio_setup();
while(1){
//Serial.println("start txing");
txdata[0] = c_raw_values_start; //set up to read from address
twi_tx();
//Serial.println("done txing");
//Serial.println("start rxing");
twi_rx();
//Serial.println("done rxing");
c1 = (((int16_t)rxdata[2])<<8 + (int16_t)rxdata[3]) - (((int16_t)rxdata[0])<<8 + (int16_t)rxdata[1]);
c2 = (((int16_t)rxdata[6])<<8 + (int16_t)rxdata[7]) - (((int16_t)rxdata[4])<<8 + (int16_t)rxdata[5]);
c3 = (((int16_t)rxdata[10])<<8 + (int16_t)rxdata[11]) - (((int16_t)rxdata[8])<<8 + (int16_t)rxdata[9]);
c4 = (((int16_t)rxdata[14])<<8 + (int16_t)rxdata[15]) - (((int16_t)rxdata[12])<<8 + (int16_t)rxdata[13]);
c5 = (((int16_t)rxdata[18])<<8 + (int16_t)rxdata[19]) - (((int16_t)rxdata[16])<<8 + (int16_t)rxdata[17]);
Serial.println("Raw sensor values");
Serial.println(c1);
Serial.println(c2);
Serial.println(c3);
Serial.println(c4);
Serial.println(c5);
if (millis() - last_tx_time > tx_period){
as5013_read();
radio_buffer[0] = 1; //send a move command
radio_buffer[1] = 10; //move 10 steps forward
radio_send(); //send command
int result = radio_recv(); //wait for response
//getting false positives...
Serial.print("buffer: ");
Serial.println(radio_buffer[1]);
Serial.print("result: ");
Serial.println(result);
//NRF_UARTE0->TXD.PTR = (uint32_t)(&rxdata); //reset pointer to start of buffer
//NRF_UARTE0->TASKS_STARTTX = 1; //trigger start task
last_tx_time = millis();
}
}
delay(100);
}
......
#define PACKET_BASE_ADDRESS_LENGTH (2UL) //Packet base address length field size in bytes
#define PACKET_LENGTH 4
static int16_t radio_buffer[PACKET_LENGTH] = {0};
//
//RADIO
//
void radio_setup(){
NRF_RADIO->POWER = RADIO_POWER_POWER_Disabled; //turn off radio to reset registers
delay(10);
NRF_RADIO->POWER = RADIO_POWER_POWER_Enabled; //turn on radio
delay(10);
NRF_RADIO->TXPOWER = (RADIO_TXPOWER_TXPOWER_Pos3dBm << RADIO_TXPOWER_TXPOWER_Pos);
NRF_RADIO->FREQUENCY = 7UL; // Frequency bin 7, 2407MHz
NRF_RADIO->MODE = (RADIO_MODE_MODE_Nrf_1Mbit << RADIO_MODE_MODE_Pos);
NRF_RADIO->PREFIX0 = ((uint32_t)0xC0 << 0); // Prefix byte of address 0
NRF_RADIO->BASE0 = 0x01234567UL; // Base address for prefix 0
NRF_RADIO->TXADDRESS = 0x00UL; // Set device address 0 to use when transmitting
NRF_RADIO->RXADDRESSES = 0x01UL; // Enable device address 0 to use to select which addresses to receive
// Packet configuration
NRF_RADIO->PCNF0 = (0 << RADIO_PCNF0_S1LEN_Pos) | (0 << RADIO_PCNF0_S0LEN_Pos) | (0 << RADIO_PCNF0_LFLEN_Pos);
NRF_RADIO->PCNF1 = (RADIO_PCNF1_WHITEEN_Enabled << RADIO_PCNF1_WHITEEN_Pos) |
((PACKET_LENGTH) << RADIO_PCNF1_STATLEN_Pos) |
(RADIO_PCNF1_ENDIAN_Big << RADIO_PCNF1_ENDIAN_Pos) |
(2 << RADIO_PCNF1_BALEN_Pos);
NRF_RADIO->CRCCNF = (RADIO_CRCCNF_LEN_Three << RADIO_CRCCNF_LEN_Pos); // Number of checksum bits
NRF_RADIO->CRCINIT = 0xFFFFUL; // Initial value
NRF_RADIO->CRCPOLY = 0x18D; //x8 + x7 + x3 + x2 + 1 = 110001101
NRF_RADIO->MODECNF0 |= RADIO_MODECNF0_RU_Fast << RADIO_MODECNF0_RU_Pos; //turn on fast ramp up
NRF_RADIO->SHORTS = 0; //turn off all shortcuts, for debug
NRF_RADIO->PACKETPTR = (uint32_t)&radio_buffer; //set pointer to packet buffer
//start HFCLK
NRF_CLOCK->TASKS_HFCLKSTART = 1;
while(!(NRF_CLOCK->HFCLKSTAT & CLOCK_HFCLKSTAT_STATE_Msk)); //wait for hfclk to start
delay(10);
}
void radio_wait_for_end(){ while(!(NRF_RADIO->EVENTS_END)); NRF_RADIO->EVENTS_END = 0;} //clear end event
void radio_wait_for_ready(){ while(!(NRF_RADIO->EVENTS_READY)); NRF_RADIO->EVENTS_READY = 0;} //clear ready event
void radio_disable(){
NRF_RADIO->EVENTS_DISABLED = 0; //clear disabled event
NRF_RADIO->TASKS_DISABLE = 1;
while(!(NRF_RADIO->EVENTS_DISABLED));
}
void radio_send(){
NRF_RADIO->EVENTS_READY = 0; //clear ready event
NRF_RADIO->TASKS_TXEN=1; //trigger tx enable task
delayMicroseconds(20);
//radio_wait_for_ready(); //only generated when actually switching to tx mode
NRF_RADIO->TASKS_START=1; //start
radio_wait_for_end();
//add wait for ack?
}
int radio_recv(){
//return 0 if success
NRF_RADIO->EVENTS_CRCOK = 0;
NRF_RADIO->EVENTS_CRCERROR = 0;
NRF_RADIO->EVENTS_DEVMATCH = 0;
while(true){
NRF_RADIO->EVENTS_READY = 0; //clear ready event
NRF_RADIO->TASKS_RXEN=1; //trigger rx enable task
delayMicroseconds(20);
//radio_wait_for_ready(); //only generated when actually switching to rx mode
NRF_RADIO->TASKS_START=1;
radio_wait_for_end();
Serial.println("got packet");
Serial.println(NRF_RADIO->EVENTS_CRCOK);
if ((NRF_RADIO->EVENTS_CRCOK == 1) && (NRF_RADIO->EVENTS_DEVMATCH == 1)){ break;}
delay(10);
}
return 0;
}
#include "radio.h"
uint16_t pwms[1] = {0};
const uint8_t pin_mode1 = 3; //A1
const uint8_t pin_mode0 = 0; //XL1
const uint8_t pin_step = 1; //XL2
const uint8_t pin_direction = 2; //A0
const uint8_t pin_nrst = 27; //p27
const uint8_t pin_ref = 26; //p26
int i=0; //counter
void stepper_setup(){
NRF_GPIO->DIRSET = (1 << pin_nrst); //set nrst/nslp pins as output
NRF_GPIO->OUTCLR = (1 << pin_nrst); //set nrst/nslp low to disable drv8825
NRF_GPIO->OUT = (0<<pin_nrst);
NRF_GPIO->DIRSET = (1 << pin_mode1) | (1 << pin_mode0); //set mode pins as output
NRF_GPIO->OUTCLR = (1 << pin_mode1) | (1 << pin_mode0); //set to full step mode
NRF_GPIO->DIRSET = (1 << pin_step) | (1 << pin_direction); //set step/dir pins as output
//Use PWM module to generate aref/bref
NRF_GPIO->DIRSET = (1<<pin_ref); //set ref pin as output
NRF_GPIO->OUTCLR = (1<<pin_ref); //set ref pin low
NRF_PWM0->PSEL.OUT[0] = (pin_ref << PWM_PSEL_OUT_PIN_Pos) | (PWM_PSEL_OUT_CONNECT_Connected << PWM_PSEL_OUT_CONNECT_Pos); //set aref pin to pwm out[0]
NRF_PWM0->ENABLE = (PWM_ENABLE_ENABLE_Enabled << PWM_ENABLE_ENABLE_Pos);
NRF_PWM0->MODE = (PWM_MODE_UPDOWN_Up << PWM_MODE_UPDOWN_Pos);
NRF_PWM0->PRESCALER = (PWM_PRESCALER_PRESCALER_DIV_1 << PWM_PRESCALER_PRESCALER_Pos); //16MHz tick
NRF_PWM0->COUNTERTOP = (1600 << PWM_COUNTERTOP_COUNTERTOP_Pos); //1 kHz pwm freq.
NRF_PWM0->LOOP = (PWM_LOOP_CNT_Disabled << PWM_LOOP_CNT_Pos);
NRF_PWM0->DECODER = (PWM_DECODER_LOAD_Common << PWM_DECODER_LOAD_Pos) | (PWM_DECODER_MODE_RefreshCount << PWM_DECODER_MODE_Pos);
pwms[0] = 1500; //50% duty cycle to test
NRF_PWM0->SEQ[0].PTR = ((uint32_t)(pwms) << PWM_SEQ_PTR_PTR_Pos);
NRF_PWM0->SEQ[0].CNT = (1 << PWM_SEQ_CNT_CNT_Pos);
NRF_PWM0->SEQ[0].REFRESH = 0;
NRF_PWM0->SEQ[0].ENDDELAY = 0;
NRF_PWM0->TASKS_SEQSTART[0] = 1;
delay(1); //give aref filter time to settle.
}
void parse_command(){
//interpret command from radio for stepper actions
//TODO: add commands for enable/disable driver, setting current limit, setting microstepping
if( radio_buffer[0] == 1 ){
//move by commanded number of steps
if (radio_buffer[1] > 0){
NRF_GPIO->OUTSET = (1<<pin_direction); //set direction forwards
} else {
NRF_GPIO->OUTCLR = (1<<pin_direction); //set direction backwards
}
for(i=0; i<radio_buffer[1]; i++){
NRF_GPIO->OUTSET = (1<<pin_step);
delay(10);
NRF_GPIO->OUTCLR = (1<<pin_step);
delay(1);
}
//reset radio buffer
for(i=0; i<PACKET_LENGTH; i++){
radio_buffer[i] = 0;
}
} else{
//unrecognized command, set radio buffer to all -1
for(int i=0; i<PACKET_LENGTH; i++){
radio_buffer[i] = -1;
}
}
}
void setup() {
Serial.begin(115200);
//Switch to internal LFCLK to disconnect from XL1 and XL2
NRF_CLOCK->LFCLKSRC = 0; //disconnect XL1 AND XL2 FROM LFCLK?
NRF_CLOCK->EVENTS_LFCLKSTARTED = 0;
NRF_CLOCK->TASKS_LFCLKSTART = 1;
while (NRF_CLOCK->EVENTS_LFCLKSTARTED == 0) {}
stepper_setup();
radio_setup();
NRF_GPIO->OUTSET = (1<<pin_nrst); //set nrst/nslp high to enable drv8825
//debug transmit loop
while(true){
radio_send();
delay(10);
}
while (true) {
int result = radio_recv(); //wait until recieve
if (result==0){
//no crc error
parse_command();
} else{
//incoming crc error, set radio buffer to all -2
for(int i=0; i<PACKET_LENGTH; i++){
radio_buffer[i] = -2;
}
}
radio_send(); //send back radio buffer when done
}
}
void loop() {}
// draft for using timer for pwm
//NRF_TIMER1->MODE = (TIMER_MODE_MODE_Timer << TIMER_MODE_MODE_Pos) & TIMER_MODE_MODE_Msk;
//NRF_TIMER1->BITMODE = (TIMER_BITMODE_BITMODE_16Bit << TIMER_BITMODE_BITMODE_Pos) & TIMER_BITMODE_BITMODE_Msk;
//NRF_TIMER1->PRESCALER = (7 << TIMER_PRESCALER_PRESCALER_Pos) & TIMER_PRESCALER_PRESCALER_Msk;
//NRF_TIMER1->SHORTS = ((TIMER_SHORTS_COMPARE0_CLEAR_Enabled << TIMER_SHORTS_COMPARE0_CLEAR_Pos) & TIMER_SHORTS_COMPARE0_CLEAR_Msk);
//NRF_TIMER1->CC[0] = (1 << 15); //50% duty cycle to test
//enable PPI channel 0 for compare task setting pin high
//NRF_PPI->CHEN = (PPI_CHEN_CH0_Enabled << PPI_CHEN_CH0_Pos) & PPI_CHEN_CH0_Msk;
//NRF_PPI->CH[0].EEP = (uint32_t)&NRF_TIMER1->EVENTS_COMPARE[0];
//NRF_PPI->CH[0].TEP = (uint32_t)&NRF_GPIOTE->TASKS_OUT[0];
//enable PPI channel 1 for compare overflow setting pin low
//NRF_PPI->CHEN = (PPI_CHEN_CH1_Enabled << PPI_CHEN_CH1_Pos) & PPI_CHEN_CH1_Msk;
//NRF_PPI->CH[0].EEP = (uint32_t)&NRF_TIMER1->EVENTS_;
//NRF_PPI->CH[0].TEP = (uint32_t)&NRF_GPIOTE->TASKS_OUT[1];
//NRF_TIMER1->TASKS_START = 1; //start timer
#define PACKET_BASE_ADDRESS_LENGTH (2UL) //Packet base address length field size in bytes
#define PACKET_LENGTH 4
static int16_t radio_buffer[PACKET_LENGTH] = {0};
//
//RADIO
//
void radio_setup(){
NRF_RADIO->POWER = RADIO_POWER_POWER_Disabled; //turn off radio to reset registers
delay(10);
NRF_RADIO->POWER = RADIO_POWER_POWER_Enabled; //turn on radio
delay(10);
NRF_RADIO->TXPOWER = (RADIO_TXPOWER_TXPOWER_Pos3dBm << RADIO_TXPOWER_TXPOWER_Pos);
NRF_RADIO->FREQUENCY = 7UL; // Frequency bin 7, 2407MHz
NRF_RADIO->MODE = (RADIO_MODE_MODE_Nrf_1Mbit << RADIO_MODE_MODE_Pos);
NRF_RADIO->PREFIX0 = ((uint32_t)0xC0 << 0); // Prefix byte of address 0
NRF_RADIO->BASE0 = 0x01234567UL; // Base address for prefix 0
NRF_RADIO->TXADDRESS = 0x00UL; // Set device address 0 to use when transmitting
NRF_RADIO->RXADDRESSES = 0x01UL; // Enable device address 0 to use to select which addresses to receive
// Packet configuration
NRF_RADIO->PCNF0 = (0 << RADIO_PCNF0_S1LEN_Pos) | (0 << RADIO_PCNF0_S0LEN_Pos) | (0 << RADIO_PCNF0_LFLEN_Pos);
NRF_RADIO->PCNF1 = (RADIO_PCNF1_WHITEEN_Enabled << RADIO_PCNF1_WHITEEN_Pos) |
((PACKET_LENGTH) << RADIO_PCNF1_STATLEN_Pos) |
(RADIO_PCNF1_ENDIAN_Big << RADIO_PCNF1_ENDIAN_Pos) |
(2 << RADIO_PCNF1_BALEN_Pos);
NRF_RADIO->CRCCNF = (RADIO_CRCCNF_LEN_Three << RADIO_CRCCNF_LEN_Pos); // Number of checksum bits
NRF_RADIO->CRCPOLY = 0x18D; //x8 + x7 + x3 + x2 + 1 = 110001101
NRF_RADIO->MODECNF0 |= RADIO_MODECNF0_RU_Fast << RADIO_MODECNF0_RU_Pos; //turn on fast ramp up
NRF_RADIO->SHORTS = 0; //turn off all shortcuts, for debug
NRF_RADIO->PACKETPTR = (uint32_t)&radio_buffer; //set pointer to packet buffer
//start HFCLK
NRF_CLOCK->TASKS_HFCLKSTART = 1;
while(!(NRF_CLOCK->HFCLKSTAT & CLOCK_HFCLKSTAT_STATE_Msk)); //wait for hfclk to start
delay(10);
}
void radio_wait_for_end(){ while(!(NRF_RADIO->EVENTS_END)); NRF_RADIO->EVENTS_END = 0;} //clear end event
void radio_wait_for_ready(){ while(!(NRF_RADIO->EVENTS_READY)); NRF_RADIO->EVENTS_READY = 0;} //clear ready event
void radio_disable(){
NRF_RADIO->EVENTS_DISABLED = 0; //clear disabled event
NRF_RADIO->TASKS_DISABLE = 1;
while(!(NRF_RADIO->EVENTS_DISABLED));
}
void radio_send(){
NRF_RADIO->EVENTS_READY = 0; //clear ready event
NRF_RADIO->TASKS_TXEN=1; //trigger tx enable task
delayMicroseconds(15);
//radio_wait_for_ready(); //only generated when actually switching to tx mode
NRF_RADIO->TASKS_START=1; //start
radio_wait_for_end();
//add wait for ack?
}
int radio_recv(){
//return 0 if success
NRF_RADIO->EVENTS_CRCOK = 0;
NRF_RADIO->EVENTS_CRCERROR = 0;
while(true){
NRF_RADIO->EVENTS_READY = 0; //clear ready event
NRF_RADIO->TASKS_RXEN=1; //trigger rx enable task
delayMicroseconds(15);
//radio_wait_for_ready(); //only generated when actually switching to rx mode
NRF_RADIO->TASKS_START=1;
radio_wait_for_end();
if (NRF_RADIO->EVENTS_CRCOK == 1){ break;}
}
return 0;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment