Initial commit

This commit is contained in:
EmanuelFeru
2020-02-07 14:57:44 +01:00
commit 836e321549
551 changed files with 113644 additions and 0 deletions

168
Src/gd32f1x0_it.c Normal file
View File

@@ -0,0 +1,168 @@
/*!
\file gd32f1x0_it.h
\brief the header file of the ISR
*/
/*
Copyright (C) 2017 GigaDevice
2014-12-26, V1.0.0, platform GD32F1x0(x=3,5)
2016-01-15, V2.0.0, platform GD32F1x0(x=3,5,7,9)
2016-04-30, V3.0.0, firmware update for GD32F1x0(x=3,5,7,9)
2017-06-19, V3.1.0, firmware update for GD32F1x0(x=3,5,7,9)
*/
#include "gd32f1x0_it.h"
#include "systick.h"
#include "i2c_it.h"
#include "config.h"
/*!
\brief this function handles NMI exception
\param[in] none
\param[out] none
\retval none
*/
void NMI_Handler(void)
{
}
/*!
\brief this function handles HardFault exception
\param[in] none
\param[out] none
\retval none
*/
void HardFault_Handler(void)
{
/* if Hard Fault exception occurs, go to infinite loop */
while (1){
}
}
/*!
\brief this function handles MemManage exception
\param[in] none
\param[out] none
\retval none
*/
void MemManage_Handler(void)
{
/* if Memory Manage exception occurs, go to infinite loop */
while (1){
}
}
/*!
\brief this function handles BusFault exception
\param[in] none
\param[out] none
\retval none
*/
void BusFault_Handler(void)
{
/* if Bus Fault exception occurs, go to infinite loop */
while (1){
}
}
/*!
\brief this function handles UsageFault exception
\param[in] none
\param[out] none
\retval none
*/
void UsageFault_Handler(void)
{
/* if Usage Fault exception occurs, go to infinite loop */
while (1){
}
}
/*!
\brief this function handles SVC exception
\param[in] none
\param[out] none
\retval none
*/
void SVC_Handler(void)
{
}
/*!
\brief this function handles DebugMon exception
\param[in] none
\param[out] none
\retval none
*/
void DebugMon_Handler(void)
{
}
/*!
\brief this function handles PendSV exception
\param[in] none
\param[out] none
\retval none
*/
void PendSV_Handler(void)
{
}
/*!
\brief this function handles SysTick exception
\param[in] none
\param[out] none
\retval none
*/
void SysTick_Handler(void)
{
tick_count_increment();
delay_decrement();
}
/*!
\brief this function handles I2C0 event interrupt request exception
\param[in] none
\param[out] none
\retval none
*/
void I2C0_EV_IRQHandler(void)
{
I2C0_EventIRQ_Handler();
}
/*!
\brief this function handles I2C0 error interrupt request exception
\param[in] none
\param[out] none
\retval none
*/
void I2C0_ER_IRQHandler(void)
{
I2C0_ErrorIRQ_Handler();
}
#ifdef AUX45_USE_I2C
/*!
\brief this function handles I2C1 event interrupt request exception
\param[in] none
\param[out] none
\retval none
*/
void I2C1_EV_IRQHandler(void)
{
I2C1_EventIRQ_Handler();
}
/*!
\brief this function handles I2C1 error interrupt request exception
\param[in] none
\param[out] none
\retval none
*/
void I2C1_ER_IRQHandler(void)
{
I2C1_ErrorIRQ_Handler();
}
#endif

336
Src/i2c_it.c Normal file
View File

@@ -0,0 +1,336 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "gd32f1x0_i2c.h"
#include "i2c_it.h"
#include "util.h"
#include "systick.h"
#include "config.h"
void I2C0_EventIRQ_Handler(void)
{
uint16_t k;
if (i2c_ReadWriteCmd == WRITE) { // check for WRITE command
// ======================================== WRITE ========================================
// --------------------------------------------------------------------
// | Master | S | AD+W | | RA | | DATA | | DATA | | P |
// | Slave | | | ACK | | ACK | | ACK | | ACK | |
// --------------------------------------------------------------------
if (i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_SBSEND)) { // check if start condition is sent out in master mode
i2c_master_addressing(I2C0, i2c_slaveAddress, I2C_TRANSMITTER); // send slave address with Transmit request
} else if (i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_ADDSEND)) { // check if address is sent in master mode
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_ADDSEND); // clear ADDSEND bit
} else if (i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_TBE)) { // check if I2C_DATA is empty (Transmitted Byte Empty)
if (i2c_nRABytes > 0) { // check if the Register Address has been sent
i2c_data_transmit(I2C0, i2c_regAddress); // the master sends the Register Address byte
i2c_nRABytes--;
} else {
if (i2c_nDABytes > 0) {
i2c_data_transmit(I2C0, *i2c_txbuffer++); // the master sends a data byte
i2c_nDABytes--;
for(k=0; k<500; k++); // make some clock cycles delay (otherwise DMP writing will fail!! Reason unknown yet.. could be that writing to MPU6050 memory takes a bit more time)
} else {
i2c_stop_on_bus(I2C0); // the master sends a stop condition to I2C bus
i2c_status = 0; // 0 = Success
i2c_interrupt_disable(I2C0, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV); // disable the I2C0 interrupt
}
}
}
} else if (i2c_ReadWriteCmd == READ) { // check for READ command
// ======================================== READ ========================================
// --------------------------------------------------------------------------------------
// | Master | S | AD+W | | RA | | S | AD+R | | ACK | | NACK | P |
// | Slave | | | ACK | | ACK | | | ACK | DATA | | DATA | | |
// --------------------------------------------------------------------------------------
// <---------- Phase 1 ----------> <---------------- Phase 2 ---------------->
// Phase 1 - send the Register Address
if (i2c_nRABytes >= 0) {
if (i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_SBSEND)) { // check if start condition is sent out in master mode
i2c_master_addressing(I2C0, i2c_slaveAddress, I2C_TRANSMITTER); // send slave address with Transmit request
} else if (i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_ADDSEND)) { // check if address is sent in master mode
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_ADDSEND); // clear ADDSEND bit
} else if (i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_TBE)) { // check if I2C_DATA is empty (Transmitted Byte Empty)
if (i2c_nRABytes > 0) { // check RABytes
i2c_data_transmit(I2C0, i2c_regAddress); // the master sends the Register Address byte
} else {
i2c_start_on_bus(I2C0); // send start condition
}
i2c_nRABytes--;
}
// Phase 2 - read Data
} else {
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_SBSEND)){ // check if start condition is sent out in master mode
i2c_master_addressing(I2C0, i2c_slaveAddress, I2C_RECEIVER); // sends slave address with Receive Request
}else if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_ADDSEND)){ // check if address is sent in master mode
if((1 == i2c_nDABytes) || (2 == i2c_nDABytes)){
i2c_ack_config(I2C0, I2C_ACK_DISABLE); // clear the ACKEN before the ADDSEND is cleared
i2c_interrupt_flag_clear(I2C0,I2C_INT_FLAG_ADDSEND); // clear the ADDSEND bit
}else{
i2c_interrupt_flag_clear(I2C0,I2C_INT_FLAG_ADDSEND); // clear the ADDSEND bit
}
}else if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_RBNE)){ // check if I2C_DATA is not Empty (Received Byte Not Empty)
if(i2c_nDABytes > 0){
if(3 == i2c_nDABytes){
while(!i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_BTC)); // wait until the second last data byte is received into the shift register
i2c_ack_config(I2C0, I2C_ACK_DISABLE); // send a NACK for the last data byte
}
*i2c_rxbuffer++ = i2c_data_receive(I2C0); // read a data byte from I2C_DATA
i2c_nDABytes--;
if(0 == i2c_nDABytes){
i2c_stop_on_bus(I2C0); // send a stop condition
i2c_status = 0; // 0 = Success
i2c_ack_config(I2C0, I2C_ACK_ENABLE);
i2c_ackpos_config(I2C0, I2C_ACKPOS_CURRENT);
i2c_interrupt_disable(I2C0, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
}
}
}
}
}
}
void I2C0_ErrorIRQ_Handler(void)
{
/* no acknowledge received */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_AERR)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_AERR);
}
/* SMBus alert */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_SMBALT)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_SMBALT);
}
/* bus timeout in SMBus mode */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_SMBTO)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_SMBTO);
}
/* over-run or under-run when SCL stretch is disabled */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_OUERR)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_OUERR);
}
/* arbitration lost */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_LOSTARB)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_LOSTARB);
}
/* bus error */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_BERR)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_BERR);
}
/* CRC value doesn't match */
if(i2c_interrupt_flag_get(I2C0, I2C_INT_FLAG_PECERR)){
i2c_interrupt_flag_clear(I2C0, I2C_INT_FLAG_PECERR);
}
/* disable the error interrupt */
i2c_interrupt_disable(I2C0,I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
}
#ifdef AUX45_USE_I2C
/*!
\brief handle I2C1 event interrupt request
\param[in] none
\param[out] none
\retval none
*/
void I2C1_EventIRQ_Handler(void)
{
uint16_t k;
if (i2c_aux_ReadWriteCmd == WRITE) { // check for WRITE command
// ======================================== WRITE ========================================
// --------------------------------------------------------------------
// | Master | S | AD+W | | RA | | DATA | | DATA | | P |
// | Slave | | | ACK | | ACK | | ACK | | ACK | |
// --------------------------------------------------------------------
if (i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_SBSEND)) { // check if start condition is sent out in master mode
i2c_master_addressing(I2C1, i2c_aux_slaveAddress, I2C_TRANSMITTER); // send slave address with Transmit request
} else if (i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_ADDSEND)) { // check if address is sent in master mode
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_ADDSEND); // clear ADDSEND bit
} else if (i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_TBE)) { // check if I2C_DATA is empty (Transmitted Byte Empty)
if (i2c_aux_nRABytes > 0) { // check if the Register Address has been sent
i2c_data_transmit(I2C1, i2c_aux_regAddress); // the master sends the Register Address byte
i2c_aux_nRABytes--;
} else {
if (i2c_aux_nDABytes > 0) {
i2c_data_transmit(I2C1, *i2c_aux_txbuffer++); // the master sends a data byte
i2c_aux_nDABytes--;
for(k=0; k<500; k++); // make some clock cycles delay (otherwise DMP writing will fail!! Reason unknown yet.. could be that writing to MPU6050 memory takes a bit more time)
} else {
i2c_stop_on_bus(I2C1); // the master sends a stop condition to I2C bus
i2c_aux_status = 0; // 0 = Success
i2c_interrupt_disable(I2C1, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV); // disable the I2C0 interrupt
}
}
}
} else if (i2c_aux_ReadWriteCmd == READ) { // check for READ command
// ======================================== READ ========================================
// --------------------------------------------------------------------------------------
// | Master | S | AD+W | | RA | | S | AD+R | | ACK | | NACK | P |
// | Slave | | | ACK | | ACK | | | ACK | DATA | | DATA | | |
// --------------------------------------------------------------------------------------
// <---------- Phase 1 ----------> <---------------- Phase 2 ---------------->
// Phase 1 - send the Register Address
if (i2c_aux_nRABytes >= 0) {
if (i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_SBSEND)) { // check if start condition is sent out in master mode
i2c_master_addressing(I2C1, i2c_aux_slaveAddress, I2C_TRANSMITTER); // send slave address with Transmit request
} else if (i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_ADDSEND)) { // check if address is sent in master mode
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_ADDSEND); // clear ADDSEND bit
} else if (i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_TBE)) { // check if I2C_DATA is empty (Transmitted Byte Empty)
if (i2c_aux_nRABytes > 0) { // check RABytes
i2c_data_transmit(I2C1, i2c_aux_regAddress); // the master sends the Register Address byte
} else {
i2c_start_on_bus(I2C1); // send start condition
}
i2c_aux_nRABytes--;
}
// Phase 2 - read Data
} else {
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_SBSEND)){ // check if start condition is sent out in master mode
i2c_master_addressing(I2C1, i2c_aux_slaveAddress, I2C_RECEIVER); // sends slave address with Receive Request
}else if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_ADDSEND)){ // check if address is sent in master mode
if((1 == i2c_aux_nDABytes) || (2 == i2c_aux_nDABytes)){
i2c_ack_config(I2C1, I2C_ACK_DISABLE); // clear the ACKEN before the ADDSEND is cleared
i2c_interrupt_flag_clear(I2C1,I2C_INT_FLAG_ADDSEND); // clear the ADDSEND bit
}else{
i2c_interrupt_flag_clear(I2C1,I2C_INT_FLAG_ADDSEND); // clear the ADDSEND bit
}
}else if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_RBNE)){ // check if I2C_DATA is not Empty (Received Byte Not Empty)
if(i2c_aux_nDABytes > 0){
if(3 == i2c_aux_nDABytes){
while(!i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_BTC)); // wait until the second last data byte is received into the shift register
i2c_ack_config(I2C1, I2C_ACK_DISABLE); // send a NACK for the last data byte
}
*i2c_aux_rxbuffer++ = i2c_data_receive(I2C1); // read a data byte from I2C_DATA
i2c_aux_nDABytes--;
if(0 == i2c_aux_nDABytes){
i2c_stop_on_bus(I2C1); // send a stop condition
i2c_aux_status = 0; // 0 = Success
i2c_ack_config(I2C1, I2C_ACK_ENABLE);
i2c_ackpos_config(I2C1, I2C_ACKPOS_CURRENT);
i2c_interrupt_disable(I2C1, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
}
}
}
}
}
}
/*!
\brief handle I2C1 error interrupt request
\param[in] none
\param[out] none
\retval none
*/
void I2C1_ErrorIRQ_Handler(void)
{
/* no acknowledge received */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_AERR)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_AERR);
}
/* SMBus alert */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_SMBALT)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_SMBALT);
}
/* bus timeout in SMBus mode */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_SMBTO)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_SMBTO);
}
/* over-run or under-run when SCL stretch is disabled */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_OUERR)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_OUERR);
}
/* arbitration lost */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_LOSTARB)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_LOSTARB);
}
/* bus error */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_BERR)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_BERR);
}
/* CRC value doesn't match */
if(i2c_interrupt_flag_get(I2C1, I2C_INT_FLAG_PECERR)){
i2c_interrupt_flag_clear(I2C1, I2C_INT_FLAG_PECERR);
}
/* disable the error interrupt */
i2c_interrupt_disable(I2C0,I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
}
#endif

213
Src/main.c Normal file
View File

@@ -0,0 +1,213 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdio.h>
#include <string.h>
#include "gd32f1x0.h"
#include "systick.h"
#include "i2c_it.h"
#include "defines.h"
#include "setup.h"
#include "config.h"
#include "util.h"
#include "mpu6050.h"
#include "mpu6050_dmp.h"
#ifdef SERIAL_CONTROL
typedef struct{
uint16_t start;
int16_t roll;
int16_t pitch;
int16_t yaw;
uint16_t sensors;
uint16_t checksum;
} SerialSideboard;
SerialSideboard Sideboard;
#endif
#ifdef SERIAL_FEEDBACK
typedef struct{
uint16_t start;
int16_t cmd1;
int16_t cmd2;
int16_t speedR;
int16_t speedL;
int16_t speedR_meas;
int16_t speedL_meas;
int16_t batVoltage;
int16_t boardTemp;
int16_t checksum;
} SerialFeedback;
SerialFeedback Feedback;
SerialFeedback NewFeedback;
static int16_t timeoutCntSerial = 0; // Timeout counter for Rx Serial command
static uint8_t timeoutFlagSerial = 0; // Timeout Flag for Rx Serial command: 0 = OK, 1 = Problem detected (line disconnected or wrong Rx data)
#endif
extern MPU_Data mpu; // holds the MPU-6050 data
ErrStatus mpuStatus = SUCCESS; // holds the MPU-6050 status: SUCCESS or ERROR
uint8_t userCommand; // holds the user command input
uint8_t sensor1, sensor2; // holds the sensor1 and sensor 2 values
static uint32_t main_loop_counter; // main loop counter to perform task squeduling inside main()
int main(void)
{
systick_config(); // SysTick config
gpio_config(); // GPIO config
usart_config(USART_MAIN, USART_MAIN_BAUD); // USART config
i2c_config(); // I2C config
i2c_nvic_config(); // NVIC peripheral config
#ifdef SERIAL_CONTROL
usart_Tx_DMA_config(USART_MAIN, (uint8_t *)&Sideboard, sizeof(Sideboard));
#endif
#ifdef SERIAL_FEEDBACK
usart_Rx_DMA_config(USART_MAIN, (uint8_t *)&NewFeedback, sizeof(NewFeedback));
#endif
introDemoLED(100); // Short LEDs intro demo with 100 ms delay. This also gives some time for the MPU-6050 to initialize.
if(mpu_config()) { // IMU MPU-6050 config
mpuStatus = ERROR;
}
mpu_handle_input('h'); // Print the User Help commands to serial
while(1){
delay_1ms(DELAY_IN_MAIN_LOOP);
// ==================================== LEDs Handling ====================================
// gpio_bit_write(LED4_GPIO_Port, LED4_Pin, (bit_status)(1-gpio_input_bit_get(LED4_GPIO_Port, LED4_Pin))); // Toggle BLUE1 LED
if (SUCCESS == mpuStatus) {
gpio_bit_set(LED2_GPIO_Port, LED2_Pin); // Turn on GREEN LED
} else {
gpio_bit_set(LED1_GPIO_Port, LED1_Pin); // Turn on RED LED
}
// ==================================== USER Handling ====================================
#ifdef SERIAL_DEBUG
// Get the user Input as one character from Serial
if(SET == usart_flag_get(USART_MAIN, USART_FLAG_RBNE)) { // Check if Read Buffer Not Empty meanind Serial data is available
userCommand = usart_data_receive(USART_MAIN);
if (userCommand != 10 && userCommand != 13) { // Do not accept 'new line' (ascii 10) and 'carriage return' (ascii 13) commands
log_i("Command = %c\n", userCommand);
mpu_handle_input(userCommand);
}
}
#endif
// ==================================== MPU-6050 Handling ====================================
// Get MPU data. Because the MPU-6050 interrupt pin is not wired we have to check DMP data by pooling periodically
if (SUCCESS == mpuStatus) {
mpu_get_data();
}
// Print MPU data to Console
if (main_loop_counter % 50 == 0 && SUCCESS == mpuStatus) {
mpu_print_to_console();
}
// ==================================== SENSORS Handling ====================================
// SENSOR1
if (gpio_input_bit_get(SENSOR1_GPIO_Port, SENSOR1_Pin)) {
sensor1 = 1;
// Sensor ACTIVE: Do something here
gpio_bit_set(LED4_GPIO_Port, LED4_Pin);
consoleLog("-- SENSOR 1 Active --\n");
delay_1ms(50);
} else {
sensor1 = 0;
gpio_bit_reset(LED4_GPIO_Port, LED4_Pin);
}
// SENSOR2
if (gpio_input_bit_get(SENSOR2_GPIO_Port, SENSOR2_Pin)) {
sensor2 = 1;
// Sensor ACTIVE: Do something here
gpio_bit_set(LED5_GPIO_Port, LED5_Pin);
consoleLog("-- SENSOR 2 Active --\n");
delay_1ms(50);
} else {
sensor2 = 0;
gpio_bit_reset(LED5_GPIO_Port, LED5_Pin);
}
// ==================================== SERIAL Tx/Rx Handling ====================================
#ifdef SERIAL_CONTROL
// To transmit on USART
if (main_loop_counter % 50 == 0 && SET == dma_flag_get(DMA_CH3, DMA_FLAG_FTF)) { // check if DMA channel transfer complete (Full Transfer Finish flag == 1)
Sideboard.start = (uint16_t)SERIAL_START_FRAME;
Sideboard.roll = (int16_t)mpu.euler.roll;
Sideboard.pitch = (int16_t)mpu.euler.pitch;
Sideboard.yaw = (int16_t)mpu.euler.yaw;
Sideboard.sensors = (uint16_t)(sensor1 | (sensor2 << 1));
Sideboard.checksum = (uint16_t)(Sideboard.start ^ Sideboard.roll ^ Sideboard.pitch ^ Sideboard.yaw ^ Sideboard.sensors);
dma_channel_disable(DMA_CH3);
DMA_CHCNT(DMA_CH3) = sizeof(Sideboard);
DMA_CHMADDR(DMA_CH3) = (uint32_t)&Sideboard;
dma_channel_enable(DMA_CH3);
}
#endif
#ifdef SERIAL_FEEDBACK
uint16_t checksum;
checksum = (uint16_t)(NewFeedback.start ^ NewFeedback.cmd1 ^ NewFeedback.cmd2 ^ NewFeedback.speedR ^ NewFeedback.speedL
^ NewFeedback.speedR_meas ^ NewFeedback.speedL_meas ^ NewFeedback.batVoltage ^ NewFeedback.boardTemp);
if (NewFeedback.start == SERIAL_START_FRAME && NewFeedback.checksum == checksum) {
if (timeoutFlagSerial) { // Check for previous timeout flag
if (timeoutCntSerial-- <= 0) // Timeout de-qualification
timeoutFlagSerial = 0; // Timeout flag cleared
} else {
memcpy(&Feedback, &NewFeedback, sizeof(SerialFeedback)); // Copy the new data
NewFeedback.start = 0xFFFF; // Change the Start Frame for timeout detection in the next cycle
timeoutCntSerial = 0; // Reset the timeout counter
}
} else {
if (timeoutCntSerial++ >= SERIAL_TIMEOUT) { // Timeout qualification
timeoutFlagSerial = 1; // Timeout detected
timeoutCntSerial = SERIAL_TIMEOUT; // Limit timout counter value
}
// Check periodically the received Start Frame. If it is NOT OK, most probably we are out-of-sync. Try to re-sync by reseting the DMA
if (main_loop_counter % 50 == 0 && NewFeedback.start != SERIAL_START_FRAME && NewFeedback.start != 0xFFFF) {
dma_channel_disable(DMA_CH4);
usart_Rx_DMA_config(USART_MAIN, (uint8_t *)&NewFeedback, sizeof(NewFeedback));
}
}
if (timeoutFlagSerial) { // In case of timeout bring the system to a Safe State and indicate error if desired
gpio_bit_set(LED1_GPIO_Port, LED1_Pin); // Turn on Red LED
} else {
gpio_bit_reset(LED1_GPIO_Port, LED1_Pin); // Follow the Normal behavior
}
#endif
main_loop_counter++;
}
}

3919
Src/mpu6050.c Normal file

File diff suppressed because it is too large Load Diff

1337
Src/mpu6050_dmp.c Normal file

File diff suppressed because it is too large Load Diff

301
Src/setup.c Normal file
View File

@@ -0,0 +1,301 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
// Includes
#include "gd32f1x0.h"
#include "systick.h"
#include "setup.h"
#include "defines.h"
#include "config.h"
#include "util.h"
// Global variables
extern volatile ErrStatus status;
// Private variables
static rcu_periph_enum USART_CLK[USARTn] = {USART_AUX_CLK,
USART_MAIN_CLK
};
static uint32_t USART_TX_PIN[USARTn] = {USART_AUX_TX_PIN,
USART_MAIN_TX_PIN
};
static uint32_t USART_RX_PIN[USARTn] = {USART_AUX_RX_PIN,
USART_MAIN_RX_PIN
};
void gpio_config(void) {
/* =========================== Configure LEDs GPIOs =========================== */
/* enable the GPIO clock */
rcu_periph_clock_enable(RCU_GPIOA);
rcu_periph_clock_enable(RCU_GPIOB);
/* configure GPIO port */
gpio_mode_set(LED1_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED1_Pin);
gpio_mode_set(LED2_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED2_Pin);
gpio_mode_set(LED3_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED3_Pin);
gpio_mode_set(LED4_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED4_Pin);
gpio_mode_set(LED5_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, LED5_Pin);
gpio_output_options_set(LED1_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, LED1_Pin);
gpio_output_options_set(LED2_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, LED2_Pin);
gpio_output_options_set(LED3_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, LED3_Pin);
gpio_output_options_set(LED4_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, LED4_Pin);
gpio_output_options_set(LED5_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, LED5_Pin);
/* reset GPIO pin */
gpio_bit_reset(LED1_GPIO_Port, LED1_Pin);
gpio_bit_reset(LED2_GPIO_Port, LED2_Pin);
gpio_bit_reset(LED3_GPIO_Port, LED3_Pin);
gpio_bit_reset(LED4_GPIO_Port, LED4_Pin);
gpio_bit_reset(LED5_GPIO_Port, LED5_Pin);
/* =========================== Configure Sensors GPIOs =========================== */
/* enable the GPIO clock */
rcu_periph_clock_enable(RCU_GPIOA);
rcu_periph_clock_enable(RCU_GPIOC);
/* configure GPIO port */
gpio_mode_set(SENSOR1_GPIO_Port, GPIO_MODE_INPUT, GPIO_PUPD_NONE, SENSOR1_Pin);
gpio_mode_set(SENSOR2_GPIO_Port, GPIO_MODE_INPUT, GPIO_PUPD_NONE, SENSOR2_Pin);
/* =========================== Configure I2C GPIOs =========================== */
/* enable I2C clock */
rcu_periph_clock_enable(RCU_GPIOB);
rcu_periph_clock_enable(MPU_RCU_I2C);
/* connect PB6 to I2C_SCL and PB7 to I2C_SDA */
gpio_af_set(MPU_SCL_GPIO_Port, GPIO_AF_1, MPU_SCL_Pin);
gpio_af_set(MPU_SDA_GPIO_Port, GPIO_AF_1, MPU_SDA_Pin);
/* configure GPIO port */
gpio_mode_set(MPU_SCL_GPIO_Port, GPIO_MODE_AF, GPIO_PUPD_PULLUP, MPU_SCL_Pin);
gpio_output_options_set(MPU_SCL_GPIO_Port, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, MPU_SCL_Pin);
gpio_mode_set(MPU_SDA_GPIO_Port, GPIO_MODE_AF, GPIO_PUPD_PULLUP, MPU_SDA_Pin);
gpio_output_options_set(MPU_SDA_GPIO_Port, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, MPU_SDA_Pin);
#ifdef AUX45_USE_I2C
/* enable I2C clock */
rcu_periph_clock_enable(RCU_GPIOA);
rcu_periph_clock_enable(AUX_RCU_I2C);
/* connect PB6 to I2C_SCL and PB7 to I2C_SDA */
gpio_af_set(AUX_SCL_GPIO_Port, GPIO_AF_1, AUX_SCL_Pin);
gpio_af_set(AUX_SDA_GPIO_Port, GPIO_AF_1, AUX_SDA_Pin);
/* configure GPIO port */
gpio_mode_set(AUX_SCL_GPIO_Port, GPIO_MODE_AF, GPIO_PUPD_PULLUP, AUX_SCL_Pin);
gpio_output_options_set(AUX_SCL_GPIO_Port, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, AUX_SCL_Pin);
gpio_mode_set(AUX_SDA_GPIO_Port, GPIO_MODE_AF, GPIO_PUPD_PULLUP, AUX_SDA_Pin);
gpio_output_options_set(AUX_SDA_GPIO_Port, GPIO_OTYPE_OD, GPIO_OSPEED_50MHZ, AUX_SDA_Pin);
#endif
/* =========================== Configure AUX GPIOs =========================== */
/* configure AUX GPIO port */
rcu_periph_clock_enable(RCU_GPIOA);
rcu_periph_clock_enable(RCU_GPIOB);
rcu_periph_clock_enable(RCU_GPIOC);
/* configure GPIO port - inputs */
gpio_mode_set(AUX1_PU_GPIO_Port, GPIO_MODE_INPUT, GPIO_PUPD_NONE, AUX1_PU_Pin);
/* configure GPIO port - outputs */
gpio_mode_set(AUX2_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, AUX2_Pin);
gpio_mode_set(AUX3_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, AUX3_Pin);
gpio_output_options_set(AUX2_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, AUX2_Pin);
gpio_output_options_set(AUX3_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, AUX3_Pin);
/* reset GPIO pin */
gpio_bit_reset(AUX2_GPIO_Port, AUX2_Pin);
gpio_bit_reset(AUX3_GPIO_Port, AUX3_Pin);
#ifdef AUX45_USE_GPIO
/* configure GPIO port - outputs */
gpio_mode_set(AUX4_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, AUX4_Pin);
gpio_mode_set(AUX5_GPIO_Port, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, AUX5_Pin);
gpio_output_options_set(AUX4_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, AUX4_Pin);
gpio_output_options_set(AUX5_GPIO_Port, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, AUX5_Pin);
/* reset GPIO pin */
gpio_bit_reset(AUX4_GPIO_Port, AUX4_Pin);
gpio_bit_reset(AUX5_GPIO_Port, AUX5_Pin);
#endif
}
void usart_config(uint32_t selUSART, uint32_t selBaudRate) {
/* enable GPIO clock */
uint32_t USART_ID = 0U;
if(selUSART == USART0){
USART_ID = 0U;
}
if(selUSART == USART1){
USART_ID = 1U;
}
rcu_periph_clock_enable(USART_GPIO_CLK);
/* enable USART clock */
rcu_periph_clock_enable(USART_CLK[USART_ID]);
/* connect port to USARTx_Tx */
gpio_af_set(USART_GPIO_PORT, USART_AF, USART_TX_PIN[USART_ID]);
/* connect port to USARTx_Rx */
gpio_af_set(USART_GPIO_PORT, USART_AF, USART_RX_PIN[USART_ID]);
/* configure USART Tx as alternate function push-pull */
gpio_mode_set(USART_GPIO_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, USART_TX_PIN[USART_ID]);
gpio_output_options_set(USART_GPIO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, USART_TX_PIN[USART_ID]);
/* configure USART Rx as alternate function push-pull */
gpio_mode_set(USART_GPIO_PORT, GPIO_MODE_AF, GPIO_PUPD_PULLUP, USART_RX_PIN[USART_ID]);
gpio_output_options_set(USART_GPIO_PORT, GPIO_OTYPE_PP, GPIO_OSPEED_10MHZ, USART_RX_PIN[USART_ID]);
/* USART configure */
usart_deinit(selUSART);
usart_baudrate_set(selUSART, selBaudRate);
usart_transmit_config(selUSART, USART_TRANSMIT_ENABLE);
usart_receive_config(selUSART, USART_RECEIVE_ENABLE);
usart_enable(selUSART);
}
// DMA_CH1 = USART0_TX
// DMA_CH2 = USART0_RX
// DMA_CH3 = USART1_TX
// DMA_CH4 = USART1_RX
void usart_Tx_DMA_config(uint32_t selUSART, uint8_t *pData, uint32_t Size) {
dma_parameter_struct dma_init_struct;
// --------------------------- TX Channel ---------------------------
/* enable DMA clock */
rcu_periph_clock_enable(RCU_DMA);
/* deinitialize DMA channel2 */
dma_deinit(DMA_CH3);
dma_init_struct.direction = DMA_MEMORY_TO_PERIPHERAL;
dma_init_struct.memory_addr = (uint32_t)pData;
dma_init_struct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dma_init_struct.memory_width = DMA_MEMORY_WIDTH_8BIT;
dma_init_struct.number = Size;
dma_init_struct.periph_addr = USART1_TDATA_ADDRESS;
dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
dma_init_struct.periph_width = DMA_PERIPHERAL_WIDTH_8BIT;
dma_init_struct.priority = DMA_PRIORITY_ULTRA_HIGH; // Priorities: *_LOW, *_MEDIUM, *_HIGH, *_ULTRA_HIGH,
dma_init(DMA_CH3, dma_init_struct);
/* configure DMA mode */
dma_circulation_disable(DMA_CH3);
dma_memory_to_memory_disable(DMA_CH3);
/* enable DMA channel1 */
dma_channel_enable(DMA_CH3);
/* USART DMA enable for transmission and reception */
usart_dma_transmit_config(selUSART, USART_DENT_ENABLE);
/* wait DMA channel transfer complete */
// while (RESET == dma_flag_get(DMA_CH3, DMA_FLAG_FTF));
}
void usart_Rx_DMA_config(uint32_t selUSART, uint8_t *pData, uint32_t Size) {
dma_parameter_struct dma_init_struct;
// --------------------------- RX Channel ---------------------------
/* deinitialize DMA channel4 */
dma_deinit(DMA_CH4);
dma_init_struct.direction = DMA_PERIPHERAL_TO_MEMORY;
dma_init_struct.memory_addr = (uint32_t)pData;
dma_init_struct.memory_inc = DMA_MEMORY_INCREASE_ENABLE;
dma_init_struct.memory_width = DMA_MEMORY_WIDTH_8BIT;
dma_init_struct.number = Size;
dma_init_struct.periph_addr = USART1_RDATA_ADDRESS;
dma_init_struct.periph_inc = DMA_PERIPH_INCREASE_DISABLE;
dma_init_struct.periph_width = DMA_PERIPHERAL_WIDTH_8BIT;
dma_init_struct.priority = DMA_PRIORITY_ULTRA_HIGH; // Priorities: *_LOW, *_MEDIUM, *_HIGH, *_ULTRA_HIGH,
dma_init(DMA_CH4, dma_init_struct);
/* configure DMA mode */
dma_circulation_enable(DMA_CH4); // dma_circulation_disable(DMA_CH4);
dma_memory_to_memory_disable(DMA_CH4);
dma_channel_enable(DMA_CH4);
usart_dma_receive_config(selUSART, USART_DENR_ENABLE);
/* wait DMA channel transfer complete */
// while (RESET == dma_flag_get(DMA_CH4, DMA_FLAG_FTF));
}
void i2c_config(void) {
/* I2C clock configure */
//i2c_clock_config(MPU_I2C, MPU_I2C_SPEED, I2C_DTCY_2); // I2C duty cycle in fast mode
i2c_clock_config(MPU_I2C, MPU_I2C_SPEED, I2C_DTCY_16_9); // I2C duty cycle in fast mode plus
/* I2C address configure */
i2c_mode_addr_config(MPU_I2C, I2C_I2CMODE_ENABLE, I2C_ADDFORMAT_7BITS, I2C_OWN_ADDRESS7);
/* enable I2C */
i2c_enable(MPU_I2C);
/* enable acknowledge */
i2c_ack_config(MPU_I2C, I2C_ACK_ENABLE);
#ifdef AUX45_USE_I2C
/* I2C clock configure */
//i2c_clock_config(AUX_I2C, AUX_I2C_SPEED, I2C_DTCY_2); // I2C duty cycle in fast mode
i2c_clock_config(AUX_I2C, AUX_I2C_SPEED, I2C_DTCY_16_9); // I2C duty cycle in fast mode plus
/* I2C address configure */
i2c_mode_addr_config(AUX_I2C, I2C_I2CMODE_ENABLE, I2C_ADDFORMAT_7BITS, AUX_I2C_OWN_ADDRESS7);
/* enable I2C */
i2c_enable(AUX_I2C);
/* enable acknowledge */
i2c_ack_config(AUX_I2C, I2C_ACK_ENABLE);
#endif
}
void i2c_nvic_config(void)
{
/* configure the NVIC peripheral */
nvic_priority_group_set(NVIC_PRIGROUP_PRE1_SUB3);
nvic_irq_enable(I2C0_EV_IRQn, 0, 3);
nvic_irq_enable(I2C0_ER_IRQn, 0, 2);
#ifdef AUX45_USE_I2C
nvic_irq_enable(I2C1_EV_IRQn, 0, 4);
nvic_irq_enable(I2C1_ER_IRQn, 0, 1);
#endif
}

108
Src/systick.c Normal file
View File

@@ -0,0 +1,108 @@
/*!
\file systick.c
\brief the systick configuration file
\version 2016-01-15, V1.0.0, demo for GD32F1x0
\version 2016-05-13, V2.0.0, demo for GD32F1x0
\version 2019-11-20, V3.0.0, demo for GD32F1x0
*/
/*
Copyright (c) 2019, GigaDevice Semiconductor Inc.
Redistribution and use in source and binary forms, with or without modification,
are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. Redistributions in binary form must reproduce the above copyright notice,
this list of conditions and the following disclaimer in the documentation
and/or other materials provided with the distribution.
3. Neither the name of the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software without
specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
OF SUCH DAMAGE.
*/
#include "gd32f1x0.h"
#include "systick.h"
volatile static uint32_t delay;
volatile static unsigned long tick_count_ms = 0;
/*!
\brief configure systick
\param[in] none
\param[out] none
\retval none
*/
void systick_config(void)
{
/* setup systick timer for 1000Hz interrupts */
if (SysTick_Config(SystemCoreClock / 1000)){
/* capture error */
while (1){
}
}
/* configure the systick handler priority */
NVIC_SetPriority(SysTick_IRQn, 0x00);
}
/*!
\brief delay a time in milliseconds
\param[in] count: count in milliseconds
\param[out] none
\retval none
*/
void delay_1ms(uint32_t count)
{
delay = count;
while(0 != delay){
}
}
/*!
\brief delay decrement
\param[in] none
\param[out] none
\retval none
*/
void delay_decrement(void)
{
if (0 != delay){
delay--;
}
}
/*!
\brief tick count increment in ms
\param[in] none
\param[out] none
\retval none
*/
void tick_count_increment()
{
tick_count_ms++;
}
/*!
\brief get tick count in ms
\param[in] *count: pointer to count
\param[out] none
\retval none
*/
void get_tick_count_ms(unsigned long *count)
{
*count = tick_count_ms;
}

299
Src/util.c Normal file
View File

@@ -0,0 +1,299 @@
/**
* This file is part of the hoverboard-sideboard-hack project.
*
* Copyright (C) 2020-2021 Emanuel FERU <aerdronix@gmail.com>
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
// Includes
#include <stdio.h>
#include "systick.h"
#include "gd32f1x0.h"
#include "defines.h"
#include "config.h"
#include "util.h"
// MAIN I2C variables
volatile int8_t i2c_status;
volatile i2c_cmd i2c_ReadWriteCmd;
volatile uint8_t i2c_regAddress;
volatile uint8_t i2c_slaveAddress;
volatile uint8_t* i2c_txbuffer;
volatile uint8_t* i2c_rxbuffer;
volatile uint8_t i2c_nDABytes;
volatile int8_t i2c_nRABytes;
volatile uint8_t buffer[14];
#ifdef AUX45_USE_I2C
// AUX I2C variables
volatile int8_t i2c_aux_status;
volatile i2c_cmd i2c_aux_ReadWriteCmd;
volatile uint8_t i2c_aux_regAddress;
volatile uint8_t i2c_aux_slaveAddress;
volatile uint8_t* i2c_aux_txbuffer;
volatile uint8_t* i2c_aux_rxbuffer;
volatile uint8_t i2c_aux_nDABytes;
volatile int8_t i2c_aux_nRABytes;
#endif
/* =========================== General Functions =========================== */
void consoleLog(char *message)
{
#ifdef SERIAL_DEBUG
log_i("%s", message);
#endif
}
/* retarget the C library printf function to the USART */
int fputc(int ch, FILE *f)
{
usart_data_transmit(USART_MAIN, (uint8_t)ch);
while(RESET == usart_flag_get(USART_MAIN, USART_FLAG_TBE));
return ch;
}
void introDemoLED(uint32_t tDelay)
{
int i;
for (i = 0; i < 6; i++) {
gpio_bit_set(LED1_GPIO_Port, LED1_Pin);
gpio_bit_reset(LED3_GPIO_Port, LED3_Pin);
delay_1ms(tDelay);
gpio_bit_set(LED2_GPIO_Port, LED2_Pin);
gpio_bit_reset(LED1_GPIO_Port, LED1_Pin);
delay_1ms(tDelay);
gpio_bit_set(LED3_GPIO_Port, LED3_Pin);
gpio_bit_reset(LED2_GPIO_Port, LED2_Pin);
delay_1ms(tDelay);
}
for (i = 0; i < 2; i++) {
gpio_bit_set(LED1_GPIO_Port, LED1_Pin);
gpio_bit_set(LED2_GPIO_Port, LED2_Pin);
gpio_bit_set(LED3_GPIO_Port, LED3_Pin);
gpio_bit_set(LED4_GPIO_Port, LED4_Pin);
gpio_bit_set(LED5_GPIO_Port, LED5_Pin);
delay_1ms(tDelay);
gpio_bit_reset(LED1_GPIO_Port, LED1_Pin);
gpio_bit_reset(LED2_GPIO_Port, LED2_Pin);
gpio_bit_reset(LED3_GPIO_Port, LED3_Pin);
gpio_bit_reset(LED4_GPIO_Port, LED4_Pin);
gpio_bit_reset(LED5_GPIO_Port, LED5_Pin);
}
}
/* =========================== I2C WRITE Functions =========================== */
/*
* write bytes to chip register
*/
int8_t i2c_writeBytes(uint8_t slaveAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
{
// assign WRITE command
i2c_ReadWriteCmd = WRITE;
// assign inputs
i2c_status = -1;
i2c_slaveAddress = slaveAddr << 1; // Address is shifted one position to the left. LSB is reserved for the Read/Write bit.
i2c_regAddress = regAddr;
i2c_txbuffer = data;
i2c_nDABytes = length;
i2c_nRABytes = 1;
// enable the I2C0 interrupt
i2c_interrupt_enable(MPU_I2C, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
// the master waits until the I2C bus is idle
while(i2c_flag_get(MPU_I2C, I2C_FLAG_I2CBSY));
// the master sends a start condition to I2C bus
i2c_start_on_bus(MPU_I2C);
// Wait until all data bytes are sent/received
while(i2c_nDABytes > 0);
return i2c_status;
}
/*
* write 1 byte to chip register
*/
int8_t i2c_writeByte(uint8_t slaveAddr, uint8_t regAddr, uint8_t data)
{
return i2c_writeBytes(slaveAddr, regAddr, 1, &data);
}
/*
* write one bit to chip register
*/
int8_t i2c_writeBit(uint8_t slaveAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data) {
uint8_t b;
i2c_readByte(slaveAddr, regAddr, &b);
b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum));
return i2c_writeByte(slaveAddr, regAddr, b);
}
/* =========================== I2C READ Functions =========================== */
/*
* read bytes from chip register
*/
int8_t i2c_readBytes(uint8_t slaveAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
{
// assign READ command
i2c_ReadWriteCmd = READ;
// assign inputs
i2c_status = -1;
i2c_slaveAddress = slaveAddr << 1; // Address is shifted one position to the left. LSB is reserved for the Read/Write bit.
i2c_regAddress = regAddr;
i2c_rxbuffer = data;
i2c_nDABytes = length;
i2c_nRABytes = 1;
// enable the I2C0 interrupt
i2c_interrupt_enable(MPU_I2C, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
if(2 == i2c_nDABytes){
i2c_ackpos_config(MPU_I2C, I2C_ACKPOS_NEXT); // send ACK for the next byte
}
// the master waits until the I2C bus is idle
while(i2c_flag_get(MPU_I2C, I2C_FLAG_I2CBSY));
// the master sends a start condition to I2C bus
i2c_start_on_bus(MPU_I2C);
// Wait until all data bytes are sent/received
while(i2c_nDABytes > 0);
// Return status
return i2c_status;
}
/*
* read 1 byte from chip register
*/
int8_t i2c_readByte(uint8_t slaveAddr, uint8_t regAddr, uint8_t *data)
{
return i2c_readBytes(slaveAddr, regAddr, 1, data);
}
/*
* read 1 bit from chip register
*/
int8_t i2c_readBit(uint8_t slaveAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data)
{
uint8_t b;
int8_t status = i2c_readByte(slaveAddr, regAddr, &b);
*data = b & (1 << bitNum);
return status;
}
#ifdef AUX45_USE_I2C
/*
* write bytes to chip register
*/
int8_t i2c_aux_writeBytes(uint8_t slaveAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
{
// assign WRITE command
i2c_aux_ReadWriteCmd = WRITE;
// assign inputs
i2c_aux_status = -1;
i2c_aux_slaveAddress = slaveAddr << 1; // Address is shifted one position to the left. LSB is reserved for the Read/Write bit.
i2c_aux_regAddress = regAddr;
i2c_aux_txbuffer = data;
i2c_aux_nDABytes = length;
i2c_aux_nRABytes = 1;
// enable the I2C0 interrupt
i2c_interrupt_enable(AUX_I2C, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
// the master waits until the I2C bus is idle
while(i2c_flag_get(AUX_I2C, I2C_FLAG_I2CBSY));
// the master sends a start condition to I2C bus
i2c_start_on_bus(AUX_I2C);
// Wait until all data bytes are sent/received
while(i2c_aux_nDABytes > 0);
return i2c_aux_status;
}
/*
* read bytes from chip register
*/
int8_t i2c_aux_readBytes(uint8_t slaveAddr, uint8_t regAddr, uint8_t length, uint8_t *data)
{
// assign READ command
i2c_aux_ReadWriteCmd = READ;
// assign inputs
i2c_aux_status = -1;
i2c_aux_slaveAddress = slaveAddr << 1; // Address is shifted one position to the left. LSB is reserved for the Read/Write bit.
i2c_aux_regAddress = regAddr;
i2c_aux_rxbuffer = data;
i2c_aux_nDABytes = length;
i2c_aux_nRABytes = 1;
// enable the I2C0 interrupt
i2c_interrupt_enable(AUX_I2C, I2C_INT_ERR | I2C_INT_BUF | I2C_INT_EV);
if(2 == i2c_aux_nDABytes){
i2c_ackpos_config(AUX_I2C, I2C_ACKPOS_NEXT); // send ACK for the next byte
}
// the master waits until the I2C bus is idle
while(i2c_flag_get(AUX_I2C, I2C_FLAG_I2CBSY));
// the master sends a start condition to I2C bus
i2c_start_on_bus(AUX_I2C);
// Wait until all data bytes are sent/received
while(i2c_aux_nDABytes > 0);
// Return status
return i2c_aux_status;
}
#endif