added angle sensor reading

This commit is contained in:
Nicolas Trimborn 2021-08-20 17:20:29 +02:00
parent 0bd8db92ac
commit ed161629eb
28 changed files with 24445 additions and 16 deletions

View File

@ -46,6 +46,7 @@
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/custom_logic.rst"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/evsys.rst"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/ext_irq.rst"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/i2c_master_sync.rst"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/pwm.rst"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/spi_master_async.rst"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="hal/documentation/spi_master_sync.rst"/>
@ -58,6 +59,7 @@
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_evsys.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_ext_irq.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_gpio.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_i2c_m_sync.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_init.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_io.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hal/include/hal_sleep.h"/>
@ -91,6 +93,7 @@
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_delay.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_evsys.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_gpio.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_i2c_m_sync.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_init.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_io.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hal/src/hal_sleep.c"/>
@ -146,6 +149,9 @@
<file category="header" condition="ARMCC, GCC, IAR" name="hri/hri_trng_e51.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hri/hri_usb_e51.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hri/hri_wdt_e51.h"/>
<file category="source" condition="ARMCC, GCC, IAR" name="bosch_sensor/bno055.c"/>
<file category="header" condition="ARMCC, GCC, IAR" name="bosch_sensor/bno055.h"/>
<file category="doc" condition="ARMCC, GCC, IAR" name="documentation/bosch_sensor_bno055.rst"/>
<file category="source" condition="ARMCC, GCC, IAR" name="main.c"/>
<file category="source" condition="ARMCC, GCC, IAR" name="driver_init.c"/>
<file category="header" condition="ARMCC, GCC, IAR" name="driver_init.h"/>
@ -202,6 +208,8 @@
<file category="header" condition="ARMCC, GCC, IAR" name="hpl/tc/tc_lite.h"/>
<file category="source" condition="ARMCC, GCC, IAR" name="hpl/tcc/hpl_tcc.c"/>
<file category="header" condition="ARMCC, GCC, IAR" name="hpl/tcc/hpl_tcc.h"/>
<file category="source" condition="ARMCC, GCC, IAR" name="bosch_sensor_main.c"/>
<file category="header" condition="ARMCC, GCC, IAR" name="bosch_sensor_main.h"/>
<file category="header" condition="ARMCC, GCC, IAR" name="atmel_start.h"/>
<file category="source" condition="ARMCC, GCC, IAR" name="atmel_start.c"/>
<file attr="config" category="header" condition="ARMCC, GCC, IAR" name="config/hpl_adc_config.h"/>
@ -219,6 +227,7 @@
<file attr="config" category="header" condition="ARMCC, GCC, IAR" name="config/hpl_tc_config.h"/>
<file attr="config" category="header" condition="ARMCC, GCC, IAR" name="config/hpl_tcc_config.h"/>
<file attr="config" category="header" condition="ARMCC, GCC, IAR" name="config/peripheral_clk_config.h"/>
<file attr="config" category="header" condition="ARMCC, GCC, IAR" name="config/bno055_config.h"/>
<file category="include" condition="ARMCC, GCC, IAR" name=""/>
<file category="include" condition="ARMCC, GCC, IAR" name="config"/>
<file category="include" condition="ARMCC, GCC, IAR" name="examples"/>
@ -243,6 +252,9 @@
<file category="include" condition="ARMCC, GCC, IAR" name="hpl/tcc"/>
<file category="include" condition="ARMCC, GCC, IAR" name="hri"/>
<file category="include" condition="ARMCC, GCC, IAR" name=""/>
<file category="include" condition="ARMCC, GCC, IAR" name="bosch_sensor"/>
<file category="include" condition="ARMCC, GCC, IAR" name="config"/>
<file category="include" condition="ARMCC, GCC, IAR" name=""/>
</files>
</component>
</components>

View File

@ -18,7 +18,17 @@ board:
device: SAME51J19A-MF
details: null
application: null
middlewares: {}
middlewares:
ORIENTATION_SENSOR_0:
user_label: ORIENTATION_SENSOR_0
configuration:
bno055_i2c_address: '0x29'
definition: Atmel:Bosch_Sensor:0.0.1::Bosch_BNO055_Driver
functionality: Orientation_Sensor
api: Bosch:BNO055:Driver
dependencies:
Communication IO: COMMUNICATION_IO
BNO055 nRESET: BNO055_NRESET
drivers:
ADC_0:
user_label: ADC_0
@ -1739,6 +1749,46 @@ drivers:
variant: null
clocks:
domain_group: null
COMMUNICATION_IO:
user_label: COMMUNICATION_IO
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::SERCOM0::driver_config_definition::I2C.Master.Standard~2FFast-mode::HAL:Driver:I2C.Master.Sync
functionality: I2C
api: HAL:Driver:I2C_Master_Sync
configuration:
i2c_master_advanced: false
i2c_master_arch_dbgstop: Keep running
i2c_master_arch_inactout: Disabled
i2c_master_arch_lowtout: false
i2c_master_arch_mexttoen: false
i2c_master_arch_runstdby: false
i2c_master_arch_sdahold: 300-600ns hold time
i2c_master_arch_sexttoen: false
i2c_master_arch_trise: 215
i2c_master_baud_rate: 400000
optional_signals: []
variant:
specification: SDA=0, SCL=1
required_signals:
- name: SERCOM0/PAD/0
pad: PA08
label: SDA
- name: SERCOM0/PAD/1
pad: PA09
label: SCL
clocks:
domain_group:
nodes:
- name: Core
input: Generic clock generator 0
external: false
external_frequency: 0
- name: Slow
input: Generic clock generator 3
external: false
external_frequency: 0
configuration:
core_gclk_selection: Generic clock generator 0
slow_gclk_selection: Generic clock generator 3
SPI_1_MSIF:
user_label: SPI_1_MSIF
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::SERCOM1::driver_config_definition::SPI.Slave::HAL:Driver:SPI.Slave.Sync
@ -1847,7 +1897,7 @@ drivers:
spi_master_arch_dord: MSB first
spi_master_arch_ibon: In data stream
spi_master_arch_runstdby: false
spi_master_baud_rate: 50000
spi_master_baud_rate: 8000000
spi_master_character_size: 8 bits
spi_master_dummybyte: 511
spi_master_rx_enable: true
@ -2322,6 +2372,25 @@ pads:
mode: Digital input
user_label: ECAT_SYNC
configuration: null
PA08:
name: PA08
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::pad::PA08
mode: I2C
user_label: PA08
configuration: null
PA09:
name: PA09
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::pad::PA09
mode: I2C
user_label: PA09
configuration: null
BNO055_NRESET:
name: PB10
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::pad::PB10
mode: Digital output
user_label: BNO055_NRESET
configuration:
pad_initial_level: High
M1_PWMA:
name: PB12
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::pad::PB12
@ -2475,9 +2544,10 @@ pads:
SPI3_SS:
name: PB00
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::pad::PB00
mode: Peripheral IO
mode: Digital output
user_label: SPI3_SS
configuration: null
configuration:
pad_initial_level: High
SPI3_MISO:
name: PB01
definition: Atmel:SAME51_Drivers:0.0.1::SAME51J19A-MF::pad::PB01

View File

@ -0,0 +1,201 @@
/*
* AS5048.c
*
* Created: 27/07/2021 16:13:20
* Author: Nick-XMG
*/
#include "AS5048.h"
#define AS5048A_CMD_NOP (0x0000)
#define AS5048A_READ (0x4000)
#define AS5048A_CLEAR_ERROR_FLAG (0x0001)
#define AS5048A_PROGRAMMING_CONTROL (0x0003)
#define AS5048A_OTP_REGISTER_ZERO_POS_HIGH (0x0016)
#define AS5048A_OTP_REGISTER_ZERO_POS_LOW (0x0017)
#define AS5048A_DIAG_AGC (0x3FFD)
#define AS5048A_MAGNITUDE (0x3FFE)
#define AS5048A_ANGLE (0x3FFF)
#define AS5048A_ANGLEUNC (0x3FFE)
#define AS5048A_MAX_VALUE (8191.0f)
static bool debugPrint = false;
struct SPI_AS5048 AS_1 = {
.SPI_descr = NULL,
.io_descr = NULL,
.flags = 0,
.state = 0,
.SS_pin = SPI3_SS,
.tx_buffer = NULL,
.rx_buffer = NULL,
};
void as5048a_State_Machine(struct SPI_AS5048 *Sn)
{
volatile uint16_t angle;
switch(Sn->state) {
case 0: // Default un-initialized State
break;
case 1: // State After angleSensor_init. Configure Sensor
Sn->state++;
break;
case 2: // Synchronous blocking read
as5048a_getRotationInDegrees(Sn);
break;
case 3: // Continuously Read Angle (DMA)
break;
case 4: // Error State
break;
}
}
void as5048a_init(struct spi_m_sync_descriptor *spi, struct SPI_AS5048 *Sn)
{
Sn->SPI_descr = spi;
spi_m_sync_disable(&SPI_3);
// Set Mode 1 : CPOL = 0; CPHA = 1;
hri_sercomspi_write_CTRLA_CPOL_bit((SercomSpi *)(SPI_3.dev.prvt), false);
hri_sercomspi_write_CTRLA_CPHA_bit((SercomSpi *)(SPI_3.dev.prvt), true);
//Get IO descriptor
spi_m_sync_get_io_descriptor(Sn->SPI_descr, &Sn->io_descr);
spi_m_sync_enable(&SPI_3);
gpio_set_pin_level(Sn->SS_pin, true);
if(Sn->io_descr == NULL || Sn->SPI_descr == NULL) {
Sn->state = 4;
} else {
Sn->state = 1;
}
}
uint16_t as5048a_read(struct SPI_AS5048 *Sn, uint16_t address)
{
uint8_t in_buf[2], out_buf[2];
uint16_t returnedVal;
volatile uint16_t command = 0b0100000000000000; // PAR=0 R/W=R
command = command | address;
//Add a parity bit on the the MSB
command |= ((uint16_t)as5048a_CalcEvenParity(command)<<15);
//Split the command into two bytes
out_buf[1] = command & 0xFF;
out_buf[0] = ( command >> 8 ) & 0xFF;
/* Send Command */
gpio_set_pin_level(Sn->SS_pin, false);
as5048a_transfer16(Sn, command);
gpio_set_pin_level(Sn->SS_pin, true);
/* Send again to Get Response */
gpio_set_pin_level(Sn->SS_pin, false);
returnedVal = as5048a_transfer16(Sn, command);
gpio_set_pin_level(Sn->SS_pin, true);
// printf("In_buff= ");
// /* Print Received data by SPI Master from SPI Slave on Console */
// for (int i = 0; i < 2; i++) {
// printf("%u", in_buf[i]);
// }
// printf("\n\r"); //if(debugPrint) {
//printf("Returned val = %u \n\r", returnedVal);
//}
if (returnedVal & 0x4000) {
Sn->flags = 1;
} else {
Sn->flags = 0;
}
//Return the data, stripping the parity and error bits
//return (( ( in_buf[1] & 0xFF ) << 8 ) | ( in_buf[0] & 0xFF )) & ~0xC000;
return returnedVal & ~0xC000;
}
/*
* getRawRotation
*
* Read Raw Angle Register Value
*/
uint16_t as5048a_getRawRotation(struct SPI_AS5048 *Sn)
{
volatile uint16_t rawAngle = as5048a_read(Sn, AS5048A_ANGLE);
return rawAngle;
}
int16_t as5048a_getRotation(struct SPI_AS5048 *Sn)
{
uint16_t data;
int16_t rotation;
data = as5048a_getRawRotation(Sn);
rotation = (int16_t)(data); //- static_cast<int16_t>(this->position);
if (rotation > AS5048A_MAX_VALUE) {
rotation = -((0x3FFF) - rotation); //more than -180
}
return rotation;
}
/*
* getRotationDecInt
*
* Read angle register and return angle in Degrees
*/
uint16_t as5048a_getRotationDecInt(struct SPI_AS5048 *Sn)
{
int16_t rawAngle = as5048a_getRotation(Sn);
float angleDegrees = 360.0 * (rawAngle + AS5048A_MAX_VALUE) / (AS5048A_MAX_VALUE * 2.0);
//float32_t angleDegrees = 360.0 * (rawAngle + AS5048A_MAX_VALUE) * 0.000061042607;
return (uint16_t)(angleDegrees * 10 + .5);
}
/*
* getRotationInDegrees
*
* Read angle register and return angle in Degrees
*/
float as5048a_getRotationInDegrees(struct SPI_AS5048 *Sn)
{
int16_t rawAngle = as5048a_getRotation(Sn);
float angleDegrees = 360.0 * (rawAngle + AS5048A_MAX_VALUE) / (AS5048A_MAX_VALUE * 2.0);
//float angleDegrees = (360.0 * (rawAngle + AS5048A_MAX_VALUE)) * 0.000061042607;
return angleDegrees;
}
uint16_t as5048a_transfer16(struct SPI_AS5048 *Sn, uint16_t value)
{
uint8_t in_buf[2], out_buf[2];
uint16_t wordRead;
out_buf[1] = value & 0xFF;
out_buf[0] = ( value >> 8 ) & 0xFF;
struct spi_xfer xfer;
xfer.rxbuf = in_buf;
xfer.txbuf = (uint8_t *)out_buf;
xfer.size = 2;
spi_m_sync_transfer(Sn->SPI_descr, &xfer);
wordRead = (uint16_t)((in_buf[0] << 8) | in_buf[1]);
return wordRead;
}
uint8_t as5048a_CalcEvenParity(uint16_t value) {
uint8_t cnt = 0;
uint8_t i;
for (i = 0; i < 16; i++) {
if (value & 0x1) {
cnt++;
}
value >>= 1;
}
return cnt & 0x1;
}

View File

@ -0,0 +1,40 @@
/*
* AS5048.h
*
* Created: 27/07/2021 16:12:53
* Author: Nick-XMG
*/
#ifndef AS5048_H_
#define AS5048_H_
#include <atmel_start.h>
#include "arm_math.h"
struct SPI_AS5048 {
struct spi_m_sync_descriptor *SPI_descr;
struct io_descriptor *io_descr;
uint8_t state;
uint8_t flags;
uint32_t SS_pin;
uint8_t *tx_buffer;
uint8_t *rx_buffer;
};
struct SPI_AS5048 AS_1;
void as5048a_init(struct spi_m_sync_descriptor *spi, struct SPI_AS5048 *Sn);
void as5048a_State_Machine(struct SPI_AS5048 *Sn);
//
///* Sensor Specific Read Functions */
uint16_t as5048a_read(struct SPI_AS5048 *Sn, uint16_t address);
uint16_t as5048a_getRawRotation(struct SPI_AS5048 *Sn);
int16_t as5048a_getRotation(struct SPI_AS5048 *Sn);
float as5048a_getRotationInDegrees(struct SPI_AS5048 *Sn);
uint16_t as5048a_getRotationDecInt(struct SPI_AS5048 *Sn);
//
///* Support Functions */
uint16_t as5048a_transfer16(struct SPI_AS5048 *Sn, uint16_t value);
uint8_t as5048a_CalcEvenParity(uint16_t value);
#endif /* AS5048_H_ */

View File

@ -0,0 +1,167 @@
/*
* AS5048A_dma.c
*
* Created: 18/07/2021 14:38:25
* Author: Nick-XMG
*/
#include "AS5048A_dma.h"
#include "atmel_start_pins.h"
static uint8_t AS5048A_rx_buffer[2] = {0};
static uint8_t AS5048A_tx_buffer[2] = {0};
void spi_master_tx_complete_cb(struct _dma_resource *const resource)
{
//DMAC->Channel[CONF_SERCOM_6_TRANSMIT_DMA_CHANNEL].CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE;
delay_us(10);
gpio_set_pin_level(SPI_SS, true);
}
void spi_master_rx_complete_cb(struct _dma_resource *const resource)
{
//DMAC->Channel[CONF_SERCOM_6_RECEIVE_DMA_CHANNEL].CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE;
gpio_set_pin_level(SPI_SS, true);
}
void as5048a_init(void)
{
spi_m_dma_enable(&SPI_0);
/* tx_descriptor */
DmacDescriptor tx_descriptor;
tx_descriptor.DSTADDR.reg = (uint32_t)&AS5048A_SPI->SPI.DATA.reg; // destination address is SPI DATA register
tx_descriptor.SRCADDR.reg = (uint32_t)(AS5048A_tx_buffer + sizeof AS5048A_tx_buffer); // source address is the DMA buffer
tx_descriptor.DESCADDR.reg = 0; // only one transfer descriptor
tx_descriptor.BTCTRL.bit.BEATSIZE = DMAC_BTCTRL_BEATSIZE_BYTE_Val; // beat size is one byte
tx_descriptor.BTCTRL.bit.DSTINC = 0; // destination address increment disabled
tx_descriptor.BTCTRL.bit.SRCINC = 1; // source address increment enabled
tx_descriptor.BTCTRL.bit.STEPSEL = DMAC_BTCTRL_STEPSEL_SRC_Val; // flexible source address increment size
tx_descriptor.BTCTRL.bit.STEPSIZE = DMAC_BTCTRL_STEPSIZE_X1_Val; // source address increment is one byte
tx_descriptor.BTCTRL.bit.BLOCKACT = DMAC_BTCTRL_BLOCKACT_NOACT_Val; // request interrupt at end of block transfer
tx_descriptor.BTCNT.reg = sizeof AS5048A_tx_buffer; // beat count
tx_descriptor.BTCTRL.bit.VALID = 1;
//DMA_add_channel(0x0D, tx_descriptor, 1);
/* Register Callback */
spi_m_dma_register_callback(&SPI_0, SPI_M_DMA_CB_TX_DONE, spi_master_tx_complete_cb);
//struct _dma_resource *resource_tx;
//_dma_get_channel_resource(&resource_tx, CONF_SERCOM_6_TRANSMIT_DMA_CHANNEL);
//resource_tx->dma_cb.transfer_done = DMAC_Handler_tx_cb;
/* rx_descriptor */
DmacDescriptor rx_descriptor;
rx_descriptor.DSTADDR.reg = (uint32_t)(AS5048A_rx_buffer + sizeof AS5048A_rx_buffer); // destination address is SPI DATA register
rx_descriptor.SRCADDR.reg = (uint32_t)&AS5048A_SPI->SPI.DATA.reg; // source address is the DMA buffer
rx_descriptor.DESCADDR.reg = 0; // only one transfer descriptor
rx_descriptor.BTCTRL.bit.BEATSIZE = DMAC_BTCTRL_BEATSIZE_BYTE_Val; // beat size is one byte
rx_descriptor.BTCTRL.bit.DSTINC = 0; // destination address increment disabled
rx_descriptor.BTCTRL.bit.SRCINC = 1; // source address increment enabled
rx_descriptor.BTCTRL.bit.STEPSEL = DMAC_BTCTRL_STEPSEL_SRC_Val; // flexible source address increment size
rx_descriptor.BTCTRL.bit.STEPSIZE = DMAC_BTCTRL_STEPSIZE_X1_Val; // source address increment is one byte
rx_descriptor.BTCTRL.bit.BLOCKACT = DMAC_BTCTRL_BLOCKACT_NOACT_Val; // request interrupt at end of block transfer
rx_descriptor.BTCNT.reg = sizeof AS5048A_rx_buffer; // beat count
rx_descriptor.BTCTRL.bit.VALID = 1;
//DMA_add_channel(0x0C, rx_descriptor, 0);
/* Register Callback */
spi_m_dma_register_callback(&SPI_0, SPI_M_DMA_CB_RX_DONE, spi_master_rx_complete_cb);
//struct _dma_resource *resource_rx;
//_dma_get_channel_resource(&resource_tx, CONF_SERCOM_6_RECEIVE_DMA_CHANNEL);
//resource_tx->dma_cb.transfer_done = DMAC_Handler_rx_cb;
//DMA_enable();
}
uint16_t as5048a_read(uint16_t registerAddress)
{
uint8_t in_buf[2], out_buf[2];
volatile uint16_t command = 0b0100000000000000; // PAR=0 R/W=R
command = command | registerAddress;
//Add a parity bit on the the MSB
command |= ((uint16_t)spiCalcEvenParity(command)<<15);
//Split the command into two bytes
AS5048A_tx_buffer[1] = command & 0xFF;
AS5048A_tx_buffer[0] = ( command >> 8 ) & 0xFF;
gpio_set_pin_level(SPI_SS, false);
spi_m_dma_transfer(&SPI_0, AS5048A_tx_buffer, AS5048A_rx_buffer, sizeof AS5048A_tx_buffer );
//gpio_set_pin_level(SPI_SS, false);
//_dma_enable_transaction(0,false);
//_dma_enable_transaction(1,false);
if (AS5048A_rx_buffer[1] & 0x40) {
int i = 0;
//as5048a.errorFlag = 1;
} else {
//as5048a.errorFlag = 0;
}
return (( ( AS5048A_rx_buffer[1] & 0xFF ) << 8 ) | ( AS5048A_rx_buffer[0] & 0xFF )) & ~0xC000;
}
void as5048a_write(void)
{
}
uint8_t calcEvenParity(uint16_t value)
{
uint8_t cnt = 0;
uint8_t i;
for (i = 0; i < 16; i++)
{
if (value & 0x1)
{
cnt++;
}
value >>= 1;
}
return cnt & 0x1;
}
void DMA_add_channel(const int trigger_source, DmacDescriptor descriptor, const uint8_t channel)
{
/* disable DMA if enabled */
if (DMAC->CTRL.bit.DMAENABLE)
DMAC->CTRL.bit.DMAENABLE = 0;
while (DMAC->CTRL.bit.DMAENABLE);
_dma_set_descriptor(channel, descriptor);
/* add transfer descriptor to transfer descriptor section (before enabling channel!) */
//memcpy(descriptor_section + channel * sizeof(DmacDescriptor) , descriptor, sizeof(DmacDescriptor));
/* configure and enable first least significant free channel */
// use first free channel
DMAC->Channel[channel].CHPRILVL.bit.PRILVL = 0x00; // channel priority level 0
DMAC->Channel[channel].CHCTRLA.bit.TRIGACT = 0x02; // one trigger each beat transfer
DMAC->Channel[channel].CHCTRLA.bit.TRIGSRC = trigger_source; // select trigger source
DMAC->Channel[channel].CHCTRLA.reg |= DMAC_CHCTRLA_ENABLE; // enable channel
/* enable DMA block transfer complete interrupt */
DMAC->Channel[channel].CHINTENSET.bit.TCMPL = 1; // enable DMA block transfer complete interrupt
NVIC_EnableIRQ(DMAC_1_IRQn);
}
void DMA_enable(void)
{
/* enable DMA controller */
DMAC->CTRL.bit.DMAENABLE = 1;
}

View File

@ -0,0 +1,43 @@
/*
* AS5048A_dma.h
*
* Created: 18/07/2021 14:38:15
* Author: Nick-XMG
*/
#ifndef AS5048A_DMA_H_
#define AS5048A_DMA_H_
#include <atmel_start.h>
#include <hpl_dma.h>
/* AS5048 Registers */
#define AS5048A_CMD_NOP 0x0000
#define AS5048A_READ 0x4000
#define AS5048A_CLEAR_ERROR_FLAG 0x0001
#define AS5048A_PROGRAMMING_CONTROL 0x0003
#define AS5048A_OTP_REGISTER_ZERO_POS_HIGH 0x0016
#define AS5048A_OTP_REGISTER_ZERO_POS_LOW 0x0017
#define AS5048A_DIAG_AGC 0x3FFD
#define AS5048A_MAGNITUDE 0x3FFE
#define AS5048A_ANGLE 0x3FFF
/* AS5048 parameters */
#define AS5048A_MAX_VALUE 8191.0f
/* DMA channel for SPI Master TX and RX */
#define CONF_SERCOM_6_TRANSMIT_DMA_CHANNEL 0
#define CONF_SERCOM_6_RECEIVE_DMA_CHANNEL 1
#define AS5048A_SPI SERCOM4
void as5048a_init(void);
uint16_t as5048a_read(uint16_t registerAddress);
void as5048a_write(void);
uint8_t calcEvenParity(uint16_t value);
void DMA_add_channel(const int trigger_source, DmacDescriptor descriptor, const uint8_t channel);
void DMA_enable(void);
#endif /* AS5048A_DMA_H_ */

View File

@ -0,0 +1,9 @@
/*
* BNO055_imu.c
*
* Created: 8/20/2021 10:52:36 AM
* Author: ge37vez
*/
#include "BNO055_imu.h"

View File

@ -0,0 +1,16 @@
/*
* BNO055_imu.h
*
* Created: 8/20/2021 10:51:57 AM
* Author: ge37vez
*/
#ifndef BNO055_IMU_H_
#define BNO055_IMU_H_
#include "bosch_sensor_main.h"
#endif /* BNO055_IMU_H_ */

View File

@ -0,0 +1,22 @@
/* Auto-generated config file bno055_config.h */
#ifndef BNO055_CONFIG_H
#define BNO055_CONFIG_H
// <<< Use Configuration Wizard in Context Menu >>>
// <h> Basic Configuration
// <o> I2C Address Selection
// <i> Select which I2C address will be used
// <0x28=> 0x28
// <0x29=> 0x29
// <id> bno055_i2c_address
#ifndef CONF_BNO055_I2C_ADDR
#define CONF_BNO055_I2C_ADDR 0x29
#endif
// </h>
// <<< end of configuration section >>>
#endif // BNO055_CONFIG_H

View File

@ -4,6 +4,141 @@
// <<< Use Configuration Wizard in Context Menu >>>
#include <peripheral_clk_config.h>
#ifndef SERCOM_I2CM_CTRLA_MODE_I2C_MASTER
#define SERCOM_I2CM_CTRLA_MODE_I2C_MASTER (5 << 2)
#endif
#ifndef CONF_SERCOM_0_I2CM_ENABLE
#define CONF_SERCOM_0_I2CM_ENABLE 1
#endif
// <h> Basic
// <o> I2C Bus clock speed (Hz) <1-400000>
// <i> I2C Bus clock (SCL) speed measured in Hz
// <id> i2c_master_baud_rate
#ifndef CONF_SERCOM_0_I2CM_BAUD
#define CONF_SERCOM_0_I2CM_BAUD 400000
#endif
// </h>
// <e> Advanced
// <id> i2c_master_advanced
#ifndef CONF_SERCOM_0_I2CM_ADVANCED_CONFIG
#define CONF_SERCOM_0_I2CM_ADVANCED_CONFIG 0
#endif
// <o> TRise (ns) <0-300>
// <i> Determined by the bus impedance, check electric characteristics in the datasheet
// <i> Standard Fast Mode: typical 215ns, max 300ns
// <i> Fast Mode +: typical 60ns, max 100ns
// <i> High Speed Mode: typical 20ns, max 40ns
// <id> i2c_master_arch_trise
#ifndef CONF_SERCOM_0_I2CM_TRISE
#define CONF_SERCOM_0_I2CM_TRISE 215
#endif
// <q> Master SCL Low Extended Time-Out (MEXTTOEN)
// <i> This enables the master SCL low extend time-out
// <id> i2c_master_arch_mexttoen
#ifndef CONF_SERCOM_0_I2CM_MEXTTOEN
#define CONF_SERCOM_0_I2CM_MEXTTOEN 0
#endif
// <q> Slave SCL Low Extend Time-Out (SEXTTOEN)
// <i> Enables the slave SCL low extend time-out. If SCL is cumulatively held low for greater than 25ms from the initial START to a STOP, the slave will release its clock hold if enabled and reset the internal state machine
// <id> i2c_master_arch_sexttoen
#ifndef CONF_SERCOM_0_I2CM_SEXTTOEN
#define CONF_SERCOM_0_I2CM_SEXTTOEN 0
#endif
// <q> SCL Low Time-Out (LOWTOUT)
// <i> Enables SCL low time-out. If SCL is held low for 25ms-35ms, the master will release it's clock hold
// <id> i2c_master_arch_lowtout
#ifndef CONF_SERCOM_0_I2CM_LOWTOUT
#define CONF_SERCOM_0_I2CM_LOWTOUT 0
#endif
// <o> Inactive Time-Out (INACTOUT)
// <0x0=>Disabled
// <0x1=>5-6 SCL cycle time-out(50-60us)
// <0x2=>10-11 SCL cycle time-out(100-110us)
// <0x3=>20-21 SCL cycle time-out(200-210us)
// <i> Defines if inactivity time-out should be enabled, and how long the time-out should be
// <id> i2c_master_arch_inactout
#ifndef CONF_SERCOM_0_I2CM_INACTOUT
#define CONF_SERCOM_0_I2CM_INACTOUT 0x0
#endif
// <o> SDA Hold Time (SDAHOLD)
// <0=>Disabled
// <1=>50-100ns hold time
// <2=>300-600ns hold time
// <3=>400-800ns hold time
// <i> Defines the SDA hold time with respect to the negative edge of SCL
// <id> i2c_master_arch_sdahold
#ifndef CONF_SERCOM_0_I2CM_SDAHOLD
#define CONF_SERCOM_0_I2CM_SDAHOLD 0x2
#endif
// <q> Run in stand-by
// <i> Determine if the module shall run in standby sleep mode
// <id> i2c_master_arch_runstdby
#ifndef CONF_SERCOM_0_I2CM_RUNSTDBY
#define CONF_SERCOM_0_I2CM_RUNSTDBY 0
#endif
// <o> Debug Stop Mode
// <i> Behavior of the baud-rate generator when CPU is halted by external debugger.
// <0=>Keep running
// <1=>Halt
// <id> i2c_master_arch_dbgstop
#ifndef CONF_SERCOM_0_I2CM_DEBUG_STOP_MODE
#define CONF_SERCOM_0_I2CM_DEBUG_STOP_MODE 0
#endif
// </e>
#ifndef CONF_SERCOM_0_I2CM_SPEED
#define CONF_SERCOM_0_I2CM_SPEED 0x00 // Speed: Standard/Fast mode
#endif
#if CONF_SERCOM_0_I2CM_TRISE < 215 || CONF_SERCOM_0_I2CM_TRISE > 300
#warning Bad I2C Rise time for Standard/Fast mode, reset to 215ns
#undef CONF_SERCOM_0_I2CM_TRISE
#define CONF_SERCOM_0_I2CM_TRISE 215U
#endif
// gclk_freq - (i2c_scl_freq * 10) - (gclk_freq * i2c_scl_freq * Trise)
// BAUD + BAUDLOW = --------------------------------------------------------------------
// i2c_scl_freq
// BAUD: register value low [7:0]
// BAUDLOW: register value high [15:8], only used for odd BAUD + BAUDLOW
#define CONF_SERCOM_0_I2CM_BAUD_BAUDLOW \
(((CONF_GCLK_SERCOM0_CORE_FREQUENCY - (CONF_SERCOM_0_I2CM_BAUD * 10U) \
- (CONF_SERCOM_0_I2CM_TRISE * (CONF_SERCOM_0_I2CM_BAUD / 100U) * (CONF_GCLK_SERCOM0_CORE_FREQUENCY / 10000U) \
/ 1000U)) \
* 10U \
+ 5U) \
/ (CONF_SERCOM_0_I2CM_BAUD * 10U))
#ifndef CONF_SERCOM_0_I2CM_BAUD_RATE
#if CONF_SERCOM_0_I2CM_BAUD_BAUDLOW > (0xFF * 2)
#warning Requested I2C baudrate too low, please check
#define CONF_SERCOM_0_I2CM_BAUD_RATE 0xFF
#elif CONF_SERCOM_0_I2CM_BAUD_BAUDLOW <= 1
#warning Requested I2C baudrate too high, please check
#define CONF_SERCOM_0_I2CM_BAUD_RATE 1
#else
#define CONF_SERCOM_0_I2CM_BAUD_RATE \
((CONF_SERCOM_0_I2CM_BAUD_BAUDLOW & 0x1) \
? (CONF_SERCOM_0_I2CM_BAUD_BAUDLOW / 2) + ((CONF_SERCOM_0_I2CM_BAUD_BAUDLOW / 2 + 1) << 8) \
: (CONF_SERCOM_0_I2CM_BAUD_BAUDLOW / 2))
#endif
#endif
// Enable configuration of module
#ifndef CONF_SERCOM_1_SPI_ENABLE
#define CONF_SERCOM_1_SPI_ENABLE 1
@ -364,7 +499,7 @@
// <i> The SPI data transfer rate
// <id> spi_master_baud_rate
#ifndef CONF_SERCOM_5_SPI_BAUD
#define CONF_SERCOM_5_SPI_BAUD 50000
#define CONF_SERCOM_5_SPI_BAUD 8000000
#endif
// </h>

View File

@ -691,6 +691,86 @@
// <GCLK_PCHCTRL_GEN_GCLK11_Val"> Generic clock generator 11
// <i> Select the clock source for CORE.
#ifndef CONF_GCLK_SERCOM0_CORE_SRC
#define CONF_GCLK_SERCOM0_CORE_SRC GCLK_PCHCTRL_GEN_GCLK0_Val
#endif
// <y> Slow Clock Source
// <id> slow_gclk_selection
// <GCLK_PCHCTRL_GEN_GCLK0_Val"> Generic clock generator 0
// <GCLK_PCHCTRL_GEN_GCLK1_Val"> Generic clock generator 1
// <GCLK_PCHCTRL_GEN_GCLK2_Val"> Generic clock generator 2
// <GCLK_PCHCTRL_GEN_GCLK3_Val"> Generic clock generator 3
// <GCLK_PCHCTRL_GEN_GCLK4_Val"> Generic clock generator 4
// <GCLK_PCHCTRL_GEN_GCLK5_Val"> Generic clock generator 5
// <GCLK_PCHCTRL_GEN_GCLK6_Val"> Generic clock generator 6
// <GCLK_PCHCTRL_GEN_GCLK7_Val"> Generic clock generator 7
// <GCLK_PCHCTRL_GEN_GCLK8_Val"> Generic clock generator 8
// <GCLK_PCHCTRL_GEN_GCLK9_Val"> Generic clock generator 9
// <GCLK_PCHCTRL_GEN_GCLK10_Val"> Generic clock generator 10
// <GCLK_PCHCTRL_GEN_GCLK11_Val"> Generic clock generator 11
// <i> Select the slow clock source.
#ifndef CONF_GCLK_SERCOM0_SLOW_SRC
#define CONF_GCLK_SERCOM0_SLOW_SRC GCLK_PCHCTRL_GEN_GCLK3_Val
#endif
/**
* \def CONF_GCLK_SERCOM0_CORE_FREQUENCY
* \brief SERCOM0's Core Clock frequency
*/
#ifndef CONF_GCLK_SERCOM0_CORE_FREQUENCY
#define CONF_GCLK_SERCOM0_CORE_FREQUENCY 120000000
#endif
/**
* \def CONF_GCLK_SERCOM0_SLOW_FREQUENCY
* \brief SERCOM0's Slow Clock frequency
*/
#ifndef CONF_GCLK_SERCOM0_SLOW_FREQUENCY
#define CONF_GCLK_SERCOM0_SLOW_FREQUENCY 32768
#endif
// <y> Core Clock Source
// <id> core_gclk_selection
// <GCLK_PCHCTRL_GEN_GCLK0_Val"> Generic clock generator 0
// <GCLK_PCHCTRL_GEN_GCLK1_Val"> Generic clock generator 1
// <GCLK_PCHCTRL_GEN_GCLK2_Val"> Generic clock generator 2
// <GCLK_PCHCTRL_GEN_GCLK3_Val"> Generic clock generator 3
// <GCLK_PCHCTRL_GEN_GCLK4_Val"> Generic clock generator 4
// <GCLK_PCHCTRL_GEN_GCLK5_Val"> Generic clock generator 5
// <GCLK_PCHCTRL_GEN_GCLK6_Val"> Generic clock generator 6
// <GCLK_PCHCTRL_GEN_GCLK7_Val"> Generic clock generator 7
// <GCLK_PCHCTRL_GEN_GCLK8_Val"> Generic clock generator 8
// <GCLK_PCHCTRL_GEN_GCLK9_Val"> Generic clock generator 9
// <GCLK_PCHCTRL_GEN_GCLK10_Val"> Generic clock generator 10
// <GCLK_PCHCTRL_GEN_GCLK11_Val"> Generic clock generator 11
// <i> Select the clock source for CORE.
#ifndef CONF_GCLK_SERCOM1_CORE_SRC
#define CONF_GCLK_SERCOM1_CORE_SRC GCLK_PCHCTRL_GEN_GCLK0_Val

View File

@ -58,6 +58,7 @@
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_evsys.h" IsConfig="false" Hash="jT0K+r4kwAM8NXNsajf8mA" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_ext_irq.h" IsConfig="false" Hash="sm9cN3GPkLctaX5iRw7wzw" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_gpio.h" IsConfig="false" Hash="3mBEQ9Ix28YOArddDes83Q" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_i2c_m_sync.h" IsConfig="false" Hash="wYjgBbVVd/11drj/bh4EaQ" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_init.h" IsConfig="false" Hash="OrYSVpF3YA5XrOBImWpdSg" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_io.h" IsConfig="false" Hash="XZRSabc39WU/0MFBLYGLvQ" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_sleep.h" IsConfig="false" Hash="KuZDwgrLdU+fuMG82ZFTqg" />
@ -91,6 +92,7 @@
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_delay.c" IsConfig="false" Hash="vZ+YYOpHjTcAZaAaTE3Izg" />
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_evsys.c" IsConfig="false" Hash="lNdxWuQaRyRL4TGcI12LBQ" />
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_gpio.c" IsConfig="false" Hash="wIzN9zQd1b8qd+RDoSkD7Q" />
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_i2c_m_sync.c" IsConfig="false" Hash="rXHlXpjvdMJ9o6yJQwR90g" />
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_init.c" IsConfig="false" Hash="bJvq8kpNbbOE2nZfChOGTQ" />
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_io.c" IsConfig="false" Hash="FYpavzYSxhFzVrBQtcH2ZA" />
<AcmeProjectActionInfo Action="File" Source="hal/src/hal_sleep.c" IsConfig="false" Hash="3ebghfB3jYLpnqoi3fhq3g" />
@ -145,12 +147,14 @@
<AcmeProjectActionInfo Action="File" Source="hri/hri_trng_e51.h" IsConfig="false" Hash="mIMn5U92QRANdYDX/auQVw" />
<AcmeProjectActionInfo Action="File" Source="hri/hri_usb_e51.h" IsConfig="false" Hash="x6M7vYgNCS2oECqykr5+yw" />
<AcmeProjectActionInfo Action="File" Source="hri/hri_wdt_e51.h" IsConfig="false" Hash="o9Rg/hyuMzwOCphVc7uG1w" />
<AcmeProjectActionInfo Action="File" Source="bosch_sensor/bno055.c" IsConfig="false" Hash="XPPPZU9L/b9idSrKk8NVQA" />
<AcmeProjectActionInfo Action="File" Source="bosch_sensor/bno055.h" IsConfig="false" Hash="CwBdWSXvpYKMOGYgDpbcHQ" />
<AcmeProjectActionInfo Action="File" Source="main.c" IsConfig="false" Hash="k0AH7j+BrmdFhBPzCCMptA" />
<AcmeProjectActionInfo Action="File" Source="driver_init.c" IsConfig="false" Hash="Hu+v5td2Bt9AhrhbYtm1iQ" />
<AcmeProjectActionInfo Action="File" Source="driver_init.h" IsConfig="false" Hash="ZxylnjHZ7Ov2Jlrlr3r1RA" />
<AcmeProjectActionInfo Action="File" Source="atmel_start_pins.h" IsConfig="false" Hash="jhbQsyKOzZ+9eewfwdzIxQ" />
<AcmeProjectActionInfo Action="File" Source="examples/driver_examples.h" IsConfig="false" Hash="UdXjxLfbMqByNE44aloMqA" />
<AcmeProjectActionInfo Action="File" Source="examples/driver_examples.c" IsConfig="false" Hash="Pjg3RztiNdKibSzIRtrm7A" />
<AcmeProjectActionInfo Action="File" Source="driver_init.c" IsConfig="false" Hash="be/M5vy49HKRV6Tq8qbQqg" />
<AcmeProjectActionInfo Action="File" Source="driver_init.h" IsConfig="false" Hash="mFwQVZxJZ+vquTfAxVSFAg" />
<AcmeProjectActionInfo Action="File" Source="atmel_start_pins.h" IsConfig="false" Hash="6fDzwmi32d15DysbSDGNEQ" />
<AcmeProjectActionInfo Action="File" Source="examples/driver_examples.h" IsConfig="false" Hash="91mEn8bnzq7OcOmWxtLjLA" />
<AcmeProjectActionInfo Action="File" Source="examples/driver_examples.c" IsConfig="false" Hash="C/c9wBUBffta8/6WE4hsvA" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_adc_sync.h" IsConfig="false" Hash="ez1X5T9kpYwT+1+5x4Pxqg" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_pwm.h" IsConfig="false" Hash="RXcBZcci/7vXKRJKNIq/Kw" />
<AcmeProjectActionInfo Action="File" Source="hal/include/hal_timer.h" IsConfig="false" Hash="5pZVthtMl40VMvofOld2ng" />
@ -201,8 +205,10 @@
<AcmeProjectActionInfo Action="File" Source="hpl/tc/tc_lite.h" IsConfig="false" Hash="837i/ZOZgAj+upvb6cSvgg" />
<AcmeProjectActionInfo Action="File" Source="hpl/tcc/hpl_tcc.c" IsConfig="false" Hash="DC3UZSTUv1CDjekNxClhVg" />
<AcmeProjectActionInfo Action="File" Source="hpl/tcc/hpl_tcc.h" IsConfig="false" Hash="rdWkAK12qkOYV59tWwzy6A" />
<AcmeProjectActionInfo Action="File" Source="atmel_start.h" IsConfig="false" Hash="9RBG5E2ViQiSP2Gn4/FGpA" />
<AcmeProjectActionInfo Action="File" Source="atmel_start.c" IsConfig="false" Hash="1RHIE7zTtYK4DURNPUqF9w" />
<AcmeProjectActionInfo Action="File" Source="bosch_sensor_main.c" IsConfig="false" Hash="f/YKvbgItg1dW89VyJ9jWg" />
<AcmeProjectActionInfo Action="File" Source="bosch_sensor_main.h" IsConfig="false" Hash="riKo9R29boLAR/R3G/0bdw" />
<AcmeProjectActionInfo Action="File" Source="atmel_start.h" IsConfig="false" Hash="VZC7DgC4gqnis/WYR1EMzQ" />
<AcmeProjectActionInfo Action="File" Source="atmel_start.c" IsConfig="false" Hash="ZSBXIMLBuZ+jGf34dOaZDg" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_adc_config.h" IsConfig="true" Hash="XAOTvk5xMalucgzL/ILTWw" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_ccl_config.h" IsConfig="true" Hash="Q1yijLwNXjFOsGrwEEma+g" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_cmcc_config.h" IsConfig="true" Hash="bmtxQ8rLloaRtAo2HeXZRQ" />
@ -214,10 +220,11 @@
<AcmeProjectActionInfo Action="File" Source="config/hpl_osc32kctrl_config.h" IsConfig="true" Hash="HgvzEqDUH4jq/syjj/+G+Q" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_oscctrl_config.h" IsConfig="true" Hash="Uje5LXAS+nQpGryt9t0fYA" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_port_config.h" IsConfig="true" Hash="rMTNR+5FXtu+wfT1NbfRRA" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_sercom_config.h" IsConfig="true" Hash="numF6I4TztrS530yBeH4SA" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_sercom_config.h" IsConfig="true" Hash="JZVS/MInf5fXoR+i2tUrDA" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_tc_config.h" IsConfig="true" Hash="T93Kr6C+WDuufZob89oPeg" />
<AcmeProjectActionInfo Action="File" Source="config/hpl_tcc_config.h" IsConfig="true" Hash="2LU7afZ/3Yx7FE2KzF9dSQ" />
<AcmeProjectActionInfo Action="File" Source="config/peripheral_clk_config.h" IsConfig="true" Hash="rqTY1slZEq9V5moV+8Q+hw" />
<AcmeProjectActionInfo Action="File" Source="config/peripheral_clk_config.h" IsConfig="true" Hash="6eU7+fZNEY4RDC37iHjvJQ" />
<AcmeProjectActionInfo Action="File" Source="config/bno055_config.h" IsConfig="true" Hash="2hRq4Yx9B3nZuMEdrYIG8Q" />
</AcmeActionInfos>
<NonsecureFilesInfo />
</AcmeProjectConfig>
@ -278,6 +285,7 @@
<Value>../hpl/tc</Value>
<Value>../hpl/tcc</Value>
<Value>../hri</Value>
<Value>../bosch_sensor</Value>
<Value>%24(PackRepoDir)\atmel\SAME51_DFP\1.1.139\include</Value>
</ListValues>
</armgcc.compiler.directories.IncludePaths>
@ -327,6 +335,7 @@
<Value>../hpl/tc</Value>
<Value>../hpl/tcc</Value>
<Value>../hri</Value>
<Value>../bosch_sensor</Value>
<Value>%24(PackRepoDir)\atmel\SAME51_DFP\1.1.139\include</Value>
</ListValues>
</armgcc.assembler.general.IncludePaths>
@ -356,6 +365,7 @@
<Value>../hpl/tc</Value>
<Value>../hpl/tcc</Value>
<Value>../hri</Value>
<Value>../bosch_sensor</Value>
<Value>%24(PackRepoDir)\atmel\SAME51_DFP\1.1.139\include</Value>
</ListValues>
</armgcc.preprocessingassembler.general.IncludePaths>
@ -402,6 +412,7 @@
<Value>../hpl/tc</Value>
<Value>../hpl/tcc</Value>
<Value>../hri</Value>
<Value>../bosch_sensor</Value>
<Value>%24(PackRepoDir)\atmel\SAME51_DFP\1.1.139\include</Value>
</ListValues>
</armgcc.compiler.directories.IncludePaths>
@ -452,6 +463,7 @@
<Value>../hpl/tc</Value>
<Value>../hpl/tcc</Value>
<Value>../hri</Value>
<Value>../bosch_sensor</Value>
<Value>%24(PackRepoDir)\atmel\SAME51_DFP\1.1.139\include</Value>
</ListValues>
</armgcc.assembler.general.IncludePaths>
@ -482,6 +494,7 @@
<Value>../hpl/tc</Value>
<Value>../hpl/tcc</Value>
<Value>../hri</Value>
<Value>../bosch_sensor</Value>
<Value>%24(PackRepoDir)\atmel\SAME51_DFP\1.1.139\include</Value>
</ListValues>
</armgcc.preprocessingassembler.general.IncludePaths>
@ -493,6 +506,12 @@
<Compile Include="arm_math.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="AS5048.c">
<SubType>compile</SubType>
</Compile>
<Compile Include="AS5048.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="atmel_start.c">
<SubType>compile</SubType>
</Compile>
@ -511,9 +530,30 @@
<Compile Include="bldc_types.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="BNO055_imu.c">
<SubType>compile</SubType>
</Compile>
<Compile Include="BNO055_imu.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="bosch_sensor\bno055.c">
<SubType>compile</SubType>
</Compile>
<Compile Include="bosch_sensor\bno055.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="bosch_sensor_main.c">
<SubType>compile</SubType>
</Compile>
<Compile Include="bosch_sensor_main.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="configuration.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="Config\bno055_config.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="Config\hpl_adc_config.h">
<SubType>compile</SubType>
</Compile>
@ -607,6 +647,9 @@
<Compile Include="hal\include\hal_gpio.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="hal\include\hal_i2c_m_sync.h">
<SubType>compile</SubType>
</Compile>
<Compile Include="hal\include\hal_init.h">
<SubType>compile</SubType>
</Compile>
@ -757,6 +800,9 @@
<Compile Include="hal\src\hal_gpio.c">
<SubType>compile</SubType>
</Compile>
<Compile Include="hal\src\hal_i2c_m_sync.c">
<SubType>compile</SubType>
</Compile>
<Compile Include="hal\src\hal_init.c">
<SubType>compile</SubType>
</Compile>
@ -1035,8 +1081,10 @@
</Compile>
</ItemGroup>
<ItemGroup>
<Folder Include="bosch_sensor\" />
<Folder Include="Config\" />
<Folder Include="Device_Startup\" />
<Folder Include="documentation\" />
<Folder Include="examples\" />
<Folder Include="hal\" />
<Folder Include="hal\documentation\" />
@ -1073,6 +1121,9 @@
<None Include="Device_Startup\same51j19a_sram.ld">
<SubType>compile</SubType>
</None>
<None Include="documentation\bosch_sensor_bno055.rst">
<SubType>compile</SubType>
</None>
<None Include="hal\documentation\adc_sync.rst">
<SubType>compile</SubType>
</None>
@ -1085,6 +1136,9 @@
<None Include="hal\documentation\ext_irq.rst">
<SubType>compile</SubType>
</None>
<None Include="hal\documentation\i2c_master_sync.rst">
<SubType>compile</SubType>
</None>
<None Include="hal\documentation\pwm.rst">
<SubType>compile</SubType>
</None>

View File

@ -6,4 +6,5 @@
void atmel_start_init(void)
{
system_init();
bosch_sensor_init();
}

View File

@ -6,6 +6,7 @@ extern "C" {
#endif
#include "driver_init.h"
#include "bosch_sensor_main.h"
/**
* Initializes MCU, drivers and middleware in the project

View File

@ -35,6 +35,8 @@
#define M1_HALLB GPIO(GPIO_PORTA, 5)
#define M1_HALLC GPIO(GPIO_PORTA, 6)
#define ECAT_SYNC GPIO(GPIO_PORTA, 7)
#define PA08 GPIO(GPIO_PORTA, 8)
#define PA09 GPIO(GPIO_PORTA, 9)
#define SPI2_MOSI GPIO(GPIO_PORTA, 12)
#define SPI2_SCK GPIO(GPIO_PORTA, 13)
#define SPI2_SS GPIO(GPIO_PORTA, 14)
@ -60,6 +62,7 @@
#define M2_IB GPIO(GPIO_PORTB, 7)
#define half_VREF GPIO(GPIO_PORTB, 8)
#define ALOG_2 GPIO(GPIO_PORTB, 9)
#define BNO055_NRESET GPIO(GPIO_PORTB, 10)
#define M1_PWMA GPIO(GPIO_PORTB, 12)
#define M1_PWMB GPIO(GPIO_PORTB, 13)
#define M1_PWMC GPIO(GPIO_PORTB, 14)

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,138 @@
/*
* Code generated from Atmel Start.
*
* This file will be overwritten when reconfiguring your Atmel Start project.
* Please copy examples or other code you want to keep to a separate file or main.c
* to avoid loosing it when reconfiguring.
*/
#include <atmel_start.h>
#include <bosch_sensor_main.h>
#include <hal_io.h>
#include <hal_delay.h>
#include <hal_i2c_m_sync.h>
#include <bno055_config.h>
#define I2C_BUFFER_LEN 8
#define BNO055_I2C_BUS_WRITE_ARRAY_INDEX ((u8)1)
/*----------------------------------------------------------------------------*
* struct bno055_t parameters can be accessed by using BNO055
* BNO055_t having the following parameters
* Bus write function pointer: BNO055_WR_FUNC_PTR
* Bus read function pointer: BNO055_RD_FUNC_PTR
* Burst read function pointer: BNO055_BRD_FUNC_PTR
* Delay function pointer: delay_msec
* I2C address: dev_addr
* Chip id of the sensor: chip_id
*---------------------------------------------------------------------------*/
static struct bno055_t ORIENTATION_SENSOR_0_desc;
/* \Brief: The function is used as I2C bus write
* \Return : Status of the I2C write
* \param dev_addr : The device address of the sensor
* \param reg_addr : Address of the first register, will data is going to be written
* \param reg_data : It is a value hold in the array,
* will be used for write the value into the register
* \param cnt : The no of byte of data to be write
*/
static s8 ORIENTATION_SENSOR_0_I2C_bus_write(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt)
{
int32_t rst;
u8 array[I2C_BUFFER_LEN];
u8 stringpos = BNO055_INIT_VALUE;
array[BNO055_INIT_VALUE] = reg_addr;
for (stringpos = BNO055_INIT_VALUE; stringpos < cnt; stringpos++) {
array[stringpos + BNO055_I2C_BUS_WRITE_ARRAY_INDEX] = *(reg_data + stringpos);
}
i2c_m_sync_set_slaveaddr(&COMMUNICATION_IO, dev_addr, I2C_M_SEVEN);
rst = io_write(&COMMUNICATION_IO.io, array, cnt + 1);
if (rst != cnt + 1) {
return BNO055_ERROR;
}
return (s8)BNO055_SUCCESS;
}
/* \Brief: The function is used as I2C bus read
* \Return : Status of the I2C read
* \param dev_addr : The device address of the sensor
* \param reg_addr : Address of the first register, will data is going to be read
* \param reg_data : This data read from the sensor, which is hold in an array
* \param cnt : The no of byte of data to be read
*/
static s8 ORIENTATION_SENSOR_0_I2C_bus_read(u8 dev_addr, u8 reg_addr, u8 *reg_data, u8 cnt)
{
int32_t rst;
u8 array[I2C_BUFFER_LEN] = {BNO055_INIT_VALUE};
u8 stringpos = BNO055_INIT_VALUE;
array[BNO055_INIT_VALUE] = reg_addr;
/* Select BNO055 as I2C slave target */
i2c_m_sync_set_slaveaddr(&COMMUNICATION_IO, dev_addr, I2C_M_SEVEN);
/* Set slave internal register address to read from (I2C write) */
rst = io_write(&COMMUNICATION_IO.io, (uint8_t *)&reg_addr, 1);
if (rst != 1) {
return BNO055_ERROR;
}
/* Read value from BNO055 (I2C read) */
rst = io_read(&COMMUNICATION_IO.io, (uint8_t *)array, cnt);
if (rst != cnt) {
return BNO055_ERROR;
}
for (stringpos = BNO055_INIT_VALUE; stringpos < cnt; stringpos++) {
*(reg_data + stringpos) = array[stringpos];
}
/* add delay to fit with BNO055 continuous communication timing
* requirement, refer to BNO055 datasheet 4.6 I2C Protocol */
delay_ms(1);
return (s8)BNO055_SUCCESS;
}
BNO055_RETURN_FUNCTION_TYPE ORIENTATION_SENSOR_0_init(void)
{
ORIENTATION_SENSOR_0_desc.bus_write = ORIENTATION_SENSOR_0_I2C_bus_write;
ORIENTATION_SENSOR_0_desc.bus_read = ORIENTATION_SENSOR_0_I2C_bus_read;
ORIENTATION_SENSOR_0_desc.delay_msec = (void (*)(BNO055_MDELAY_DATA_TYPE))delay_ms;
ORIENTATION_SENSOR_0_desc.dev_addr = CONF_BNO055_I2C_ADDR;
/* Reset BNO055 by applying a low signal to the nRESET pin for at least
* 20ns, from reset to config mode need 650ms.
* Refer to BNO055 Datasheet 3.2 Power management and 1.2 Electrical and
* physical characteristics.
*/
gpio_set_pin_level(BNO055_NRESET, false);
delay_us(1);
gpio_set_pin_level(BNO055_NRESET, true);
delay_ms(650);
return bno055_init(&ORIENTATION_SENSOR_0_desc);
}
void ORIENTATION_SENSOR_0_example(void)
{
/* variable used to read the accel x data */
s16 accel_datax = BNO055_INIT_VALUE;
/* variable used to read the accel y data */
s16 accel_datay = BNO055_INIT_VALUE;
/* variable used to read the accel z data */
s16 accel_dataz = BNO055_INIT_VALUE;
/* Raw accel X, Y and Z data can read from the register page - page 0
register - 0x08 to 0x0D */
bno055_read_accel_x(&accel_datax);
bno055_read_accel_y(&accel_datay);
bno055_read_accel_z(&accel_dataz);
}
void bosch_sensor_init(void)
{
ORIENTATION_SENSOR_0_init();
}

View File

@ -0,0 +1,25 @@
/*
* Code generated from Atmel Start.
*
* This file will be overwritten when reconfiguring your Atmel Start project.
* Please copy examples or other code you want to keep to a separate file or main.c
* to avoid loosing it when reconfiguring.
*/
#ifndef BOSCH_SENSOR_MAIN_H
#define BOSCH_SENSOR_MAIN_H
#ifdef __cplusplus
extern "C" {
#endif
#include <bno055.h>
void bosch_sensor_init(void);
BNO055_RETURN_FUNCTION_TYPE ORIENTATION_SENSOR_0_init(void);
void ORIENTATION_SENSOR_0_example(void);
#ifdef __cplusplus
}
#endif
#endif /* BOSCH_SENSOR_MAIN_H */

View File

@ -0,0 +1,26 @@
======================================================
Bosch BNO055 9-axis absolute orientation sensor driver
======================================================
This software component contains the Bosch Sensortec MEMS BNO055 sensor driver (sensor API).
Refer to http://www.bosch-sensortec.com/bst/products/all_products/bno055 for more details.
The BNO055 is a system in package (SiP) chip that includes a 3-axis 14-bit
accelerometer, a 3-axis 16-bit gyroscope and a 3-axis magnetometer.
Features
--------
* Initialization the sensor with I2C communication
* Power mode configuration of the sensor
* Reading data from sensor
Dependencies
------------
* An instance of the I2C Master Sync driver is used by this driver.
Limitations
-----------
* IO read/write operation should be synchronous

View File

@ -21,6 +21,8 @@ struct adc_sync_descriptor ADC_0;
struct adc_sync_descriptor ADC_1;
struct i2c_m_sync_desc COMMUNICATION_IO;
struct spi_s_sync_descriptor SPI_1_MSIF;
struct spi_m_async_descriptor SPI_2;
@ -185,6 +187,45 @@ void EVENT_SYSTEM_0_init(void)
event_system_init();
}
void COMMUNICATION_IO_PORT_init(void)
{
gpio_set_pin_pull_mode(PA08,
// <y> Pull configuration
// <id> pad_pull_config
// <GPIO_PULL_OFF"> Off
// <GPIO_PULL_UP"> Pull-up
// <GPIO_PULL_DOWN"> Pull-down
GPIO_PULL_OFF);
gpio_set_pin_function(PA08, PINMUX_PA08C_SERCOM0_PAD0);
gpio_set_pin_pull_mode(PA09,
// <y> Pull configuration
// <id> pad_pull_config
// <GPIO_PULL_OFF"> Off
// <GPIO_PULL_UP"> Pull-up
// <GPIO_PULL_DOWN"> Pull-down
GPIO_PULL_OFF);
gpio_set_pin_function(PA09, PINMUX_PA09C_SERCOM0_PAD1);
}
void COMMUNICATION_IO_CLOCK_init(void)
{
hri_gclk_write_PCHCTRL_reg(GCLK, SERCOM0_GCLK_ID_CORE, CONF_GCLK_SERCOM0_CORE_SRC | (1 << GCLK_PCHCTRL_CHEN_Pos));
hri_gclk_write_PCHCTRL_reg(GCLK, SERCOM0_GCLK_ID_SLOW, CONF_GCLK_SERCOM0_SLOW_SRC | (1 << GCLK_PCHCTRL_CHEN_Pos));
hri_mclk_set_APBAMASK_SERCOM0_bit(MCLK);
}
void COMMUNICATION_IO_init(void)
{
COMMUNICATION_IO_CLOCK_init();
i2c_m_sync_init(&COMMUNICATION_IO, SERCOM0);
COMMUNICATION_IO_PORT_init();
}
void SPI_1_MSIF_PORT_init(void)
{
@ -500,8 +541,32 @@ void system_init(void)
// GPIO on PB00
gpio_set_pin_level(SPI3_SS,
// <y> Initial level
// <id> pad_initial_level
// <false"> Low
// <true"> High
true);
// Set pin direction to output
gpio_set_pin_direction(SPI3_SS, GPIO_DIRECTION_OUT);
gpio_set_pin_function(SPI3_SS, GPIO_PIN_FUNCTION_OFF);
// GPIO on PB10
gpio_set_pin_level(BNO055_NRESET,
// <y> Initial level
// <id> pad_initial_level
// <false"> Low
// <true"> High
true);
// Set pin direction to output
gpio_set_pin_direction(BNO055_NRESET, GPIO_DIRECTION_OUT);
gpio_set_pin_function(BNO055_NRESET, GPIO_PIN_FUNCTION_OFF);
ADC_0_init();
ADC_1_init();
@ -512,6 +577,8 @@ void system_init(void)
EVENT_SYSTEM_0_init();
COMMUNICATION_IO_init();
SPI_1_MSIF_init();
SPI_2_init();

View File

@ -31,6 +31,8 @@ extern "C" {
#include <hal_evsys.h>
#include <hal_i2c_m_sync.h>
#include <hal_spi_s_sync.h>
#include <hal_spi_m_async.h>
@ -50,6 +52,8 @@ extern struct adc_sync_descriptor ADC_0;
extern struct adc_sync_descriptor ADC_1;
extern struct i2c_m_sync_desc COMMUNICATION_IO;
extern struct spi_s_sync_descriptor SPI_1_MSIF;
extern struct spi_m_async_descriptor SPI_2;
@ -72,6 +76,10 @@ void DIGITAL_GLUE_LOGIC_0_PORT_init(void);
void DIGITAL_GLUE_LOGIC_0_CLOCK_init(void);
void DIGITAL_GLUE_LOGIC_0_init(void);
void COMMUNICATION_IO_CLOCK_init(void);
void COMMUNICATION_IO_init(void);
void COMMUNICATION_IO_PORT_init(void);
void SPI_1_MSIF_PORT_init(void);
void SPI_1_MSIF_CLOCK_init(void);
void SPI_1_MSIF_init(void);

View File

@ -70,6 +70,16 @@ void EXTERNAL_IRQ_0_example(void)
ext_irq_register(PIN_PB31, button_on_PB31_pressed);
}
void COMMUNICATION_IO_example(void)
{
struct io_descriptor *COMMUNICATION_IO_io;
i2c_m_sync_get_io_descriptor(&COMMUNICATION_IO, &COMMUNICATION_IO_io);
i2c_m_sync_enable(&COMMUNICATION_IO);
i2c_m_sync_set_slaveaddr(&COMMUNICATION_IO, 0x12, I2C_M_SEVEN);
io_write(COMMUNICATION_IO_io, (uint8_t *)"Hello World!", 12);
}
/**
* Example of using SPI_1_MSIF to write "Hello World" using the IO abstraction.
*/

View File

@ -20,6 +20,8 @@ void DIGITAL_GLUE_LOGIC_0_example(void);
void EXTERNAL_IRQ_0_example(void);
void COMMUNICATION_IO_example(void);
void SPI_2_example(void);
void TIMER_0_example(void);

View File

@ -0,0 +1,87 @@
=============================
I2C Master synchronous driver
=============================
I2C (Inter-Integrated Circuit) is a two wire serial interface usually used
for on-board low-speed bi-directional communication between controllers and
peripherals. The master device is responsible for initiating and controlling
all transfers on the I2C bus. Only one master device can be active on the I2C
bus at the time, but the master role can be transferred between devices on the
same I2C bus. I2C uses only two bidirectional open-drain lines, usually
designated SDA (Serial Data Line) and SCL (Serial Clock Line), with pull up
resistors.
The stop condition is automatically controlled by the driver if the I/O write and
read functions are used, but can be manually controlled by using the
i2c_m_sync_transfer function.
Often a master accesses different information in the slave by accessing
different registers in the slave. This is done by first sending a message to
the target slave containing the register address, followed by a repeated start
condition (no stop condition between) ending with transferring register data.
This scheme is supported by the i2c_m_sync_cmd_write and i2c_m_sync_cmd_read
function, but limited to 8-bit register addresses.
I2C Modes (standard mode/fastmode+/highspeed mode) can only be selected in
Atmel Start. If the SCL frequency (baudrate) has changed run-time, make sure to
stick within the SCL clock frequency range supported by the selected mode.
The requested SCL clock frequency is not validated by the
i2c_m_sync_set_baudrate function against the selected I2C mode.
Features
--------
* I2C Master support
* Initialization and de-initialization
* Enabling and disabling
* Run-time bus speed configuration
* Write and read I2C messages
* Slave register access functions (limited to 8-bit address)
* Manual or automatic stop condition generation
* 10- and 7- bit addressing
* I2C Modes supported
+----------------------+-------------------+
|* Standard/Fast mode | (SCL: 1 - 400kHz) |
+----------------------+-------------------+
|* Fastmode+ | (SCL: 1 - 1000kHz)|
+----------------------+-------------------+
|* Highspeed mode | (SCL: 1 - 3400kHz)|
+----------------------+-------------------+
Applications
------------
* Transfer data to and from one or multiple I2C slaves like I2C connected sensors, data storage or other I2C capable peripherals
* Data communication between micro controllers
* Controlling displays
Dependencies
------------
* I2C Master capable hardware
Concurrency
-----------
N/A
Limitations
-----------
General
^^^^^^^
* System Managmenet Bus (SMBus) not supported.
* Power Management Bus (PMBus) not supported.
Clock considerations
^^^^^^^^^^^^^^^^^^^^
The register value for the requested I2C speed is calculated and placed in the correct register, but not validated if it works correctly with the clock/prescaler settings used for the module. To validate the I2C speed setting use the formula found in the configuration file for the module. Selectable speed is automatically limited within the speed range defined by the I2C mode selected.
Known issues and workarounds
----------------------------
N/A

View File

@ -0,0 +1,244 @@
/**
* \file
*
* \brief Sync I2C Hardware Abstraction Layer(HAL) declaration.
*
* Copyright (c) 2014-2018 Microchip Technology Inc. and its subsidiaries.
*
* \asf_license_start
*
* \page License
*
* Subject to your compliance with these terms, you may use Microchip
* software and any derivatives exclusively with Microchip products.
* It is your responsibility to comply with third party license terms applicable
* to your use of third party software (including open source software) that
* may accompany Microchip software.
*
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS". NO WARRANTIES,
* WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE. IN NO EVENT WILL MICROCHIP BE
* LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, INCIDENTAL OR CONSEQUENTIAL
* LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER RELATED TO THE
* SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF THE
* POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT
* ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY
* RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY,
* THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
*
* \asf_license_stop
*
*/
#ifndef _HAL_I2C_M_SYNC_H_INCLUDED
#define _HAL_I2C_M_SYNC_H_INCLUDED
#include <hpl_i2c_m_sync.h>
#include <hal_io.h>
#ifdef __cplusplus
extern "C" {
#endif
/**
* \addtogroup doc_driver_hal_i2c_master_sync
*
* @{
*/
#define I2C_M_MAX_RETRY 1
/**
* \brief I2C descriptor structure, embed i2c_device & i2c_interface
*/
struct i2c_m_sync_desc {
struct _i2c_m_sync_device device;
struct io_descriptor io;
uint16_t slave_addr;
};
/**
* \brief Initialize synchronous I2C interface
*
* This function initializes the given I/O descriptor to be used as a
* synchronous I2C interface descriptor.
* It checks if the given hardware is not initialized and if the given hardware
* is permitted to be initialized.
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
* \param[in] hw The pointer to hardware instance
*
* \return Initialization status.
* \retval -1 The passed parameters were invalid or the interface is already initialized
* \retval 0 The initialization is completed successfully
*/
int32_t i2c_m_sync_init(struct i2c_m_sync_desc *i2c, void *hw);
/**
* \brief Deinitialize I2C interface
*
* This function deinitializes the given I/O descriptor.
* It checks if the given hardware is initialized and if the given hardware is permitted to be deinitialized.
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
*
* \return Uninitialization status.
* \retval -1 The passed parameters were invalid or the interface is already deinitialized
* \retval 0 The de-initialization is completed successfully
*/
int32_t i2c_m_sync_deinit(struct i2c_m_sync_desc *i2c);
/**
* \brief Set the slave device address
*
* This function sets the next transfer target slave I2C device address.
* It takes no effect to any already started access.
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
* \param[in] addr The slave address to access
* \param[in] addr_len The slave address length, can be I2C_M_TEN or I2C_M_SEVEN
*
* \return Masked slave address. The mask is a maximum 10-bit address, and 10th
* bit is set if a 10-bit address is used
*/
int32_t i2c_m_sync_set_slaveaddr(struct i2c_m_sync_desc *i2c, int16_t addr, int32_t addr_len);
/**
* \brief Set baudrate
*
* This function sets the I2C device to the specified baudrate.
* It only takes effect when the hardware is disabled.
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
* \param[in] clkrate Unused parameter. Should always be 0
* \param[in] baudrate The baudrate value set to master
*
* \return Whether successfully set the baudrate
* \retval -1 The passed parameters were invalid or the device is already enabled
* \retval 0 The baudrate set is completed successfully
*/
int32_t i2c_m_sync_set_baudrate(struct i2c_m_sync_desc *i2c, uint32_t clkrate, uint32_t baudrate);
/**
* \brief Sync version of enable hardware
*
* This function enables the I2C device, and then waits for this enabling operation to be done
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
*
* \return Whether successfully enable the device
* \retval -1 The passed parameters were invalid or the device enable failed
* \retval 0 The hardware enabling is completed successfully
*/
int32_t i2c_m_sync_enable(struct i2c_m_sync_desc *i2c);
/**
* \brief Sync version of disable hardware
*
* This function disables the I2C device and then waits for this disabling operation to be done
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
*
* \return Whether successfully disable the device
* \retval -1 The passed parameters were invalid or the device disable failed
* \retval 0 The hardware disabling is completed successfully
*/
int32_t i2c_m_sync_disable(struct i2c_m_sync_desc *i2c);
/**
* \brief Sync version of write command to I2C slave
*
* This function will write the value to a specified register in the I2C slave device and
* then wait for this operation to be done.
*
* The sequence of this routine is
* sta->address(write)->ack->reg address->ack->resta->address(write)->ack->reg value->nack->stt
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
* \param[in] reg The internal address/register of the I2C slave device
* \param[in] buffer The buffer holding data to write to the I2C slave device
* \param[in] length The length (in bytes) to write to the I2C slave device
*
* \return Whether successfully write to the device
* \retval <0 The passed parameters were invalid or write fail
* \retval 0 Writing to register is completed successfully
*/
int32_t i2c_m_sync_cmd_write(struct i2c_m_sync_desc *i2c, uint8_t reg, uint8_t *buffer, uint8_t length);
/**
* \brief Sync version of read register value from I2C slave
*
* This function will read a byte value from a specified register in the I2C slave device and
* then wait for this operation to be done.
*
* The sequence of this routine is
* sta->address(write)->ack->reg address->ack->resta->address(read)->ack->reg value->nack->stt
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
* \param[in] reg The internal address/register of the I2C slave device
* \param[in] buffer The buffer to hold the read data from the I2C slave device
* \param[in] length The length (in bytes) to read from the I2C slave device
*
* \return Whether successfully read from the device
* \retval <0 The passed parameters were invalid or read fail
* \retval 0 Reading from register is completed successfully
*/
int32_t i2c_m_sync_cmd_read(struct i2c_m_sync_desc *i2c, uint8_t reg, uint8_t *buffer, uint8_t length);
/**
* \brief Sync version of transfer message to/from the I2C slave
*
* This function will transfer a message between the I2C slave and the master. This function will wait for the operation
* to be done.
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
* \param[in] msg An i2c_m_msg struct
*
* \return The status of the operation
* \retval 0 Operation completed successfully
* \retval <0 Operation failed
*/
int32_t i2c_m_sync_transfer(struct i2c_m_sync_desc *const i2c, struct _i2c_m_msg *msg);
/**
* \brief Sync version of send stop condition on the i2c bus
*
* This function will create a stop condition on the i2c bus to release the bus
*
* \param[in] i2c An I2C descriptor, which is used to communicate through I2C
*
* \return The status of the operation
* \retval 0 Operation completed successfully
* \retval <0 Operation failed
*/
int32_t i2c_m_sync_send_stop(struct i2c_m_sync_desc *const i2c);
/**
* \brief Return I/O descriptor for this I2C instance
*
* This function will return a I/O instance for this I2C driver instance
*
* \param[in] i2c_m_sync_desc An I2C descriptor, which is used to communicate through I2C
* \param[in] io_descriptor A pointer to an I/O descriptor pointer type
*
* \return Error code
* \retval 0 No error detected
* \retval <0 Error code
*/
int32_t i2c_m_sync_get_io_descriptor(struct i2c_m_sync_desc *const i2c, struct io_descriptor **io);
/**
* \brief Retrieve the current driver version
*
* \return Current driver version.
*/
uint32_t i2c_m_sync_get_version(void);
/**@}*/
#ifdef __cplusplus
}
#endif
#endif

View File

@ -0,0 +1,258 @@
/**
* \file
*
* \brief I/O I2C related functionality implementation.
*
* Copyright (c) 2014-2018 Microchip Technology Inc. and its subsidiaries.
*
* \asf_license_start
*
* \page License
*
* Subject to your compliance with these terms, you may use Microchip
* software and any derivatives exclusively with Microchip products.
* It is your responsibility to comply with third party license terms applicable
* to your use of third party software (including open source software) that
* may accompany Microchip software.
*
* THIS SOFTWARE IS SUPPLIED BY MICROCHIP "AS IS". NO WARRANTIES,
* WHETHER EXPRESS, IMPLIED OR STATUTORY, APPLY TO THIS SOFTWARE,
* INCLUDING ANY IMPLIED WARRANTIES OF NON-INFRINGEMENT, MERCHANTABILITY,
* AND FITNESS FOR A PARTICULAR PURPOSE. IN NO EVENT WILL MICROCHIP BE
* LIABLE FOR ANY INDIRECT, SPECIAL, PUNITIVE, INCIDENTAL OR CONSEQUENTIAL
* LOSS, DAMAGE, COST OR EXPENSE OF ANY KIND WHATSOEVER RELATED TO THE
* SOFTWARE, HOWEVER CAUSED, EVEN IF MICROCHIP HAS BEEN ADVISED OF THE
* POSSIBILITY OR THE DAMAGES ARE FORESEEABLE. TO THE FULLEST EXTENT
* ALLOWED BY LAW, MICROCHIP'S TOTAL LIABILITY ON ALL CLAIMS IN ANY WAY
* RELATED TO THIS SOFTWARE WILL NOT EXCEED THE AMOUNT OF FEES, IF ANY,
* THAT YOU HAVE PAID DIRECTLY TO MICROCHIP FOR THIS SOFTWARE.
*
* \asf_license_stop
*
*/
#include <hal_i2c_m_sync.h>
#include <utils.h>
#include <utils_assert.h>
/**
* \brief Driver version
*/
#define DRIVER_VERSION 0x00000001u
/**
* \brief Sync version of I2C I/O read
*/
static int32_t i2c_m_sync_read(struct io_descriptor *io, uint8_t *buf, const uint16_t n)
{
struct i2c_m_sync_desc *i2c = CONTAINER_OF(io, struct i2c_m_sync_desc, io);
struct _i2c_m_msg msg;
int32_t ret;
msg.addr = i2c->slave_addr;
msg.len = n;
msg.flags = I2C_M_STOP | I2C_M_RD;
msg.buffer = buf;
ret = _i2c_m_sync_transfer(&i2c->device, &msg);
if (ret) {
return ret;
}
return n;
}
/**
* \brief Sync version of I2C I/O write
*/
static int32_t i2c_m_sync_write(struct io_descriptor *io, const uint8_t *buf, const uint16_t n)
{
struct i2c_m_sync_desc *i2c = CONTAINER_OF(io, struct i2c_m_sync_desc, io);
struct _i2c_m_msg msg;
int32_t ret;
msg.addr = i2c->slave_addr;
msg.len = n;
msg.flags = I2C_M_STOP;
msg.buffer = (uint8_t *)buf;
ret = _i2c_m_sync_transfer(&i2c->device, &msg);
if (ret) {
return ret;
}
return n;
}
/**
* \brief Sync version of i2c initialize
*/
int32_t i2c_m_sync_init(struct i2c_m_sync_desc *i2c, void *hw)
{
int32_t init_status;
ASSERT(i2c);
init_status = _i2c_m_sync_init(&i2c->device, hw);
if (init_status) {
return init_status;
}
/* Init I/O */
i2c->io.read = i2c_m_sync_read;
i2c->io.write = i2c_m_sync_write;
return ERR_NONE;
}
/**
* \brief deinitialize
*/
int32_t i2c_m_sync_deinit(struct i2c_m_sync_desc *i2c)
{
int32_t status;
ASSERT(i2c);
status = _i2c_m_sync_deinit(&i2c->device);
if (status) {
return status;
}
i2c->io.read = NULL;
i2c->io.write = NULL;
return ERR_NONE;
}
/**
* \brief Sync version of i2c enable
*/
int32_t i2c_m_sync_enable(struct i2c_m_sync_desc *i2c)
{
return _i2c_m_sync_enable(&i2c->device);
}
/**
* \brief Sync version of i2c disable
*/
int32_t i2c_m_sync_disable(struct i2c_m_sync_desc *i2c)
{
return _i2c_m_sync_disable(&i2c->device);
}
/**
* \brief Sync version of i2c set slave address
*/
int32_t i2c_m_sync_set_slaveaddr(struct i2c_m_sync_desc *i2c, int16_t addr, int32_t addr_len)
{
return i2c->slave_addr = (addr & 0x3ff) | (addr_len & I2C_M_TEN);
}
/**
* \brief Sync version of i2c set baudrate
*/
int32_t i2c_m_sync_set_baudrate(struct i2c_m_sync_desc *i2c, uint32_t clkrate, uint32_t baudrate)
{
return _i2c_m_sync_set_baudrate(&i2c->device, clkrate, baudrate);
}
/**
* \brief Sync version of i2c write command
*/
int32_t i2c_m_sync_cmd_write(struct i2c_m_sync_desc *i2c, uint8_t reg, uint8_t *buffer, uint8_t length)
{
struct _i2c_m_msg msg;
int32_t ret;
msg.addr = i2c->slave_addr;
msg.len = 1;
msg.flags = 0;
msg.buffer = &reg;
ret = _i2c_m_sync_transfer(&i2c->device, &msg);
if (ret != 0) {
/* error occurred */
return ret;
}
msg.flags = I2C_M_STOP;
msg.buffer = buffer;
msg.len = length;
ret = _i2c_m_sync_transfer(&i2c->device, &msg);
if (ret != 0) {
/* error occurred */
return ret;
}
return ERR_NONE;
}
/**
* \brief Sync version of i2c read command
*/
int32_t i2c_m_sync_cmd_read(struct i2c_m_sync_desc *i2c, uint8_t reg, uint8_t *buffer, uint8_t length)
{
struct _i2c_m_msg msg;
int32_t ret;
msg.addr = i2c->slave_addr;
msg.len = 1;
msg.flags = 0;
msg.buffer = &reg;
ret = _i2c_m_sync_transfer(&i2c->device, &msg);
if (ret != 0) {
/* error occurred */
return ret;
}
msg.flags = I2C_M_STOP | I2C_M_RD;
msg.buffer = buffer;
msg.len = length;
ret = _i2c_m_sync_transfer(&i2c->device, &msg);
if (ret != 0) {
/* error occurred */
return ret;
}
return ERR_NONE;
}
/**
* \brief Sync version of i2c transfer command
*/
int32_t i2c_m_sync_transfer(struct i2c_m_sync_desc *const i2c, struct _i2c_m_msg *msg)
{
return _i2c_m_sync_transfer(&i2c->device, msg);
}
/**
* \brief Sync version of i2c send stop condition command
*/
int32_t i2c_m_sync_send_stop(struct i2c_m_sync_desc *const i2c)
{
return _i2c_m_sync_send_stop(&i2c->device);
}
/**
* \brief Retrieve I/O descriptor
*/
int32_t i2c_m_sync_get_io_descriptor(struct i2c_m_sync_desc *const i2c, struct io_descriptor **io)
{
*io = &i2c->io;
return ERR_NONE;
}
/**
* \brief Retrieve the current driver version
*/
uint32_t i2c_m_sync_get_version(void)
{
return DRIVER_VERSION;
}

View File

@ -10,7 +10,8 @@
#include "configuration.h"
#include "interrupts.h"
#include "statemachine.h"
#include "BNO055_imu.h"
#include "AS5048.h"
void process_currents()
{
@ -68,7 +69,7 @@ static struct timer_task Onems_task;
void One_ms_timer_init(void)
{
Onems_task.interval = 1;
Onems_task.interval = 10;
Onems_task.cb = One_ms_cycle_callback;
Onems_task.mode = TIMER_TASK_REPEAT;
timer_add_task(&TIMER_0, &Onems_task);
@ -187,6 +188,16 @@ void APPLICATION_StateMachine(void)
} // End switch(applicationStatus.currentstate)
} // inline void CONTROLLER_StateMachine(void)
/* variable used to read the accel x data */
s16 accel_datax = BNO055_INIT_VALUE;
/* variable used to read the accel y data */
s16 accel_datay = BNO055_INIT_VALUE;
/* variable used to read the accel z data */
s16 accel_dataz = BNO055_INIT_VALUE;
int main(void)
{
/* Initializes MCU, drivers and middleware */
@ -210,6 +221,10 @@ int main(void)
enable_NVIC_IRQ();
_dma_enable_transaction(CONF_SERCOM_1_RECEIVE_DMA_CHANNEL, false);
_dma_enable_transaction(CONF_SERCOM_1_TRANSMIT_DMA_CHANNEL, false);
as5048a_init(&SPI_3, &AS_1);
//ORIENTATION_SENSOR_0_init();
/* Replace with your application code */
while (1) {
@ -227,6 +242,15 @@ int main(void)
APPLICATION_StateMachine();
exec_commutation(&Motor1);
exec_commutation(&Motor2);
//*M3_Joint_abs_position = as5048a_getRawRotation(&AS_1);
*M3_Joint_abs_position = as5048a_getRotationDecInt(&AS_1);
volatile int y = 0;
/* Raw accel X, Y and Z data can read from the register page - page 0
register - 0x08 to 0x0D */
//bno055_read_accel_x(&accel_datax);
//bno055_read_accel_y(&accel_datay);
//bno055_read_accel_z(&accel_dataz);
}
//if (run_ECAT) {ECAT_STATE_MACHINE();}