summaryrefslogtreecommitdiffstats
path: root/mcc_generated_files
diff options
context:
space:
mode:
authorNao Pross <naopross@thearcway.org>2018-05-01 22:18:39 +0200
committerNao Pross <naopross@thearcway.org>2018-05-01 22:18:39 +0200
commit482612524d786c2c8f5dbabc9eb304508e504d89 (patch)
tree53a7bfcf36bdcfbdad41a83b7e9c4d967a75616e /mcc_generated_files
parentAdd Led class implementation (diff)
downloadSAMLiquidSmoke-482612524d786c2c8f5dbabc9eb304508e504d89.tar.gz
SAMLiquidSmoke-482612524d786c2c8f5dbabc9eb304508e504d89.zip
Add HAL generated by MCC
Diffstat (limited to 'mcc_generated_files')
-rw-r--r--mcc_generated_files/interrupt_manager.cpp67
-rw-r--r--mcc_generated_files/interrupt_manager.hpp78
-rw-r--r--mcc_generated_files/mcc.cpp156
-rw-r--r--mcc_generated_files/mcc.hpp134
-rw-r--r--mcc_generated_files/pin_manager.cpp131
-rw-r--r--mcc_generated_files/pin_manager.hpp530
-rw-r--r--mcc_generated_files/uart1.cpp390
-rw-r--r--mcc_generated_files/uart1.hpp624
8 files changed, 2110 insertions, 0 deletions
diff --git a/mcc_generated_files/interrupt_manager.cpp b/mcc_generated_files/interrupt_manager.cpp
new file mode 100644
index 0000000..32ca3f4
--- /dev/null
+++ b/mcc_generated_files/interrupt_manager.cpp
@@ -0,0 +1,67 @@
+/**
+ System Interrupts Generated Driver File
+
+ @Company:
+ Microchip Technology Inc.
+
+ @File Name:
+ interrupt_manager.h
+
+ @Summary:
+ This is the generated driver implementation file for setting up the
+ interrupts using PIC32MX MCUs
+
+ @Description:
+ This source file provides implementations for PIC32MX MCUs interrupts.
+ Generation Information :
+ Product Revision : PIC32MX MCUs - pic32mx : v1.35
+ Device : PIC32MX470F512H
+ Version : 1.01
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+*/
+/*
+ (c) 2016 Microchip Technology Inc. and its subsidiaries. You may use this
+ software and any derivatives exclusively with Microchip products.
+
+ 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, OR ITS INTERACTION WITH MICROCHIP PRODUCTS, COMBINATION
+ WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
+
+ 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.
+
+ MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE OF THESE
+ TERMS.
+*/
+
+/**
+ Section: Includes
+*/
+#include <xc.h>
+
+/**
+ void INTERRUPT_Initialize (void)
+*/
+void INTERRUPT_Initialize (void)
+{
+ // UERI: UART1 Error
+ // Priority: 1
+ // SubPriority: 0
+ IPC7bits.U1IP = 1;
+ IPC7bits.U1IS = 0;
+
+ // Enable the multi vector
+ INTCONbits.MVEC = 1;
+ // Enable Global Interrupts
+ __builtin_mtc0(12,0,(__builtin_mfc0(12,0) | 0x0001));
+
+}
diff --git a/mcc_generated_files/interrupt_manager.hpp b/mcc_generated_files/interrupt_manager.hpp
new file mode 100644
index 0000000..a01aacd
--- /dev/null
+++ b/mcc_generated_files/interrupt_manager.hpp
@@ -0,0 +1,78 @@
+/**
+ System Interrupts Generated Driver File
+
+ @Company:
+ Microchip Technology Inc.
+
+ @File Name:
+ interrupt_manager.h
+
+ @Summary:
+ This is the generated driver implementation file for setting up the
+ interrupts using PIC32MX MCUs
+
+ @Description:
+ This source file provides implementations for PIC32MX MCUs interrupts.
+ Generation Information :
+ Product Revision : PIC32MX MCUs - pic32mx : v1.35
+ Device : PIC32MX470F512H
+ Version : 1.01
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+*/
+/*
+ (c) 2016 Microchip Technology Inc. and its subsidiaries. You may use this
+ software and any derivatives exclusively with Microchip products.
+
+ 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, OR ITS INTERACTION WITH MICROCHIP PRODUCTS, COMBINATION
+ WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
+
+ 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.
+
+ MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE OF THESE
+ TERMS.
+*/
+
+#ifndef _INTERRUPT_MANAGER_H
+#define _INTERRUPT_MANAGER_H
+
+/**
+ @Summary
+ Initializes the interrupt priorities of the PIC32MX470F512H
+
+ @Description
+ This routine sets the interrupt priorities of the modules that have been configured
+ for the PIC32MX470F512H
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ void SYSTEM_Initialize(void)
+ {
+ // Other initializers are called from this function
+ INTERRUPT_Initialize ();
+ }
+ </code>
+
+*/
+void INTERRUPT_Initialize(void);
+
+#endif \ No newline at end of file
diff --git a/mcc_generated_files/mcc.cpp b/mcc_generated_files/mcc.cpp
new file mode 100644
index 0000000..3d34379
--- /dev/null
+++ b/mcc_generated_files/mcc.cpp
@@ -0,0 +1,156 @@
+/**
+ @Generated PIC32MX MCUs Source File
+
+ @Company:
+ Microchip Technology Inc.
+
+ @File Name:
+ mcc.c
+
+ @Summary:
+ This is the mcc.c file generated using PIC32MX MCUs
+
+ @Description:
+ This header file provides implementations for driver APIs for all modules selected in the GUI.
+ Generation Information :
+ Product Revision : PIC32MX MCUs - pic32mx : v1.35
+ Device : PIC32MX470F512H
+ Driver Version : 1.02
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+*/
+
+/*
+ (c) 2016 Microchip Technology Inc. and its subsidiaries. You may use this
+ software and any derivatives exclusively with Microchip products.
+
+ 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, OR ITS INTERACTION WITH MICROCHIP PRODUCTS, COMBINATION
+ WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
+
+ 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.
+
+ MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE OF THESE
+ TERMS.
+*/
+
+// Configuration bits: selected in the GUI
+
+// DEVCFG3
+#pragma config FSRSSEL = PRIORITY_7 // Shadow Register Set Priority Select->SRS Priority 7
+#pragma config PMDL1WAY = ON // Peripheral Module Disable Configuration->Allow only one reconfiguration
+#pragma config IOL1WAY = ON // Peripheral Pin Select Configuration->Allow only one reconfiguration
+#pragma config FUSBIDIO = ON // USB USID Selection->Controlled by the USB Module
+#pragma config FVBUSONIO = ON // USB VBUS ON Selection->Controlled by USB Module
+
+// DEVCFG2
+#pragma config FPLLIDIV = DIV_12 // PLL Input Divider->12x Divider
+#pragma config FPLLMUL = MUL_24 // PLL Multiplier->24x Multiplier
+#pragma config UPLLIDIV = DIV_12 // USB PLL Input Divider->12x Divider
+#pragma config UPLLEN = OFF // USB PLL Enable->Disabled and Bypassed
+#pragma config FPLLODIV = DIV_256 // System PLL Output Clock Divider->PLL Divide by 256
+
+// DEVCFG1
+#pragma config FNOSC = FRCDIV // Oscillator Selection Bits->Fast RC Osc w/Div-by-N (FRCDIV)
+#pragma config FSOSCEN = ON // Secondary Oscillator Enable->Enabled
+#pragma config IESO = ON // Internal/External Switch Over->Enabled
+#pragma config POSCMOD = OFF // Primary Oscillator Configuration->Primary osc disabled
+#pragma config OSCIOFNC = OFF // CLKO Output Signal Active on the OSCO Pin->Disabled
+#pragma config FPBDIV = DIV_8 // Peripheral Clock Divisor->Pb_Clk is Sys_Clk/8
+#pragma config FCKSM = CSDCMD // Clock Switching and Monitor Selection->Clock Switch Disable, FSCM Disabled
+#pragma config WDTPS = PS1048576 // Watchdog Timer Postscaler->1:1048576
+#pragma config WINDIS = OFF // Watchdog Timer Window Enable->Watchdog Timer is in Non-Window Mode
+#pragma config FWDTEN = OFF // Watchdog Timer Enable->WDT Disabled (SWDTEN Bit Controls)
+#pragma config FWDTWINSZ = WINSZ_25 // Watchdog Timer Window Size->Window Size is 25%
+
+// DEVCFG0
+#pragma config DEBUG = OFF // Background Debugger Enable->Debugger is Disabled
+#pragma config JTAGEN = ON // JTAG Enable->JTAG Port Enabled
+#pragma config ICESEL = ICS_PGx1 // ICE/ICD Comm Channel Select->Communicate on PGEC1/PGED1
+#pragma config PWP = OFF // Program Flash Write Protect->Disable
+#pragma config BWP = OFF // Boot Flash Write Protect bit->Protection Disabled
+#pragma config CP = OFF // Code Protect->Protection Disabled
+
+#include "mcc.hpp"
+
+/**
+ @Summary
+ Indicates the exception cause.
+
+ @Description
+ This array identifies the cause for exception.
+ */
+
+static char *cause[] =
+{
+ "Interrupt", "Undefined", "Undefined", "Undefined",
+ "Load/fetch address error", "Store address error",
+ "Instruction bus error", "Data bus error", "Syscall",
+ "Breakpoint", "Reserved instruction", "Coprocessor unusable",
+ "Arithmetic overflow", "Trap", "Reserved", "Reserved",
+ "Reserved", "Reserved", "Reserved"
+};
+
+void SYSTEM_Initialize(void)
+{
+ PIN_MANAGER_Initialize();
+ OSCILLATOR_Initialize();
+ UART1_Initialize();
+ INTERRUPT_Initialize();
+}
+
+void SYSTEM_RegUnlock(void)
+{
+ SYSKEY = 0x12345678;
+ SYSKEY = 0xAA996655;
+ SYSKEY = 0x556699AA;
+}
+
+void SYSTEM_RegLock(void)
+{
+ SYSKEY = 0x00000000;
+}
+
+void OSCILLATOR_Initialize(void)
+{
+ SYSTEM_RegUnlock();
+ // CF no clock failure; COSC FRCDIV; PLLODIV DIV_256; UFRCEN disabled; PBDIVRDY disabled; SLOCK out of lock; FRCDIV FRC/1; SLPEN Idle on WAIT instruction; NOSC FRCDIV; PLLMULT MUL_24; SOSCEN disabled; PBDIV DIV_8; CLKLOCK unlocked; OSWEN Switch is Complete; SOSCRDY disabled;
+ OSCCON = 0x381F7700;
+ SYSTEM_RegLock();
+ // TUN Center Frequency;
+ OSCTUN = 0x0;
+ // DIVSWEN disabled; RSLP disabled; ACTIVE Active; ROSEL SYSCLK; OE Not Driven out on REFCLKO pin; SIDL disabled; RODIV 0; ON disabled;
+ REFOCON = 0x100;
+ // ROTRIM 0;
+ REFOTRIM = 0x0;
+}
+
+void _general_exception_handler ()
+{
+ /* Mask off the ExcCode Field from the Cause Register
+ Refer to the MIPs Software User's manual */
+ uint8_t _excep_code;
+ uint8_t _excep_addr;
+ uint8_t *_cause_str;
+
+ _excep_code = (_CP0_GET_CAUSE() & 0x0000007C) >> 2;
+ _excep_addr = _CP0_GET_EPC();
+ _cause_str = reinterpret_cast<uint8_t*>(cause[_excep_code]);
+
+ while(1) {
+
+ }
+}
+
+/**
+ End of File
+*/ \ No newline at end of file
diff --git a/mcc_generated_files/mcc.hpp b/mcc_generated_files/mcc.hpp
new file mode 100644
index 0000000..fe747b5
--- /dev/null
+++ b/mcc_generated_files/mcc.hpp
@@ -0,0 +1,134 @@
+/**
+ @Generated PIC32MX MCUs Header File
+
+ @Company:
+ Microchip Technology Inc.
+
+ @File Name:
+ mcc.h
+
+ @Summary:
+ This is the mcc.h file generated using PIC32MX MCUs
+
+ @Description:
+ This header file provides implementations for driver APIs for all modules selected in the GUI.
+ Generation Information :
+ Product Revision : PIC32MX MCUs - pic32mx : v1.35
+ Device : PIC32MX470F512H
+ Version : 1.02
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+*/
+
+/*
+ (c) 2016 Microchip Technology Inc. and its subsidiaries. You may use this
+ software and any derivatives exclusively with Microchip products.
+
+ 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, OR ITS INTERACTION WITH MICROCHIP PRODUCTS, COMBINATION
+ WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
+
+ 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.
+
+ MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE OF THESE
+ TERMS.
+*/
+
+#ifndef MCC_H
+#define MCC_H
+#include <xc.h>
+#include "pin_manager.hpp"
+#include <stdint.h>
+#include <stdbool.h>
+#include "uart1.hpp"
+#include "interrupt_manager.hpp"
+
+#define _XTAL_FREQ 8000000UL
+
+/**
+ * @Param
+ none
+ * @Returns
+ none
+ * @Description
+ Unlocks the write protected register to enable any write operation
+ * MCC GUI
+ * @Example
+ SYSTEM_RegUnlock();
+ */
+void SYSTEM_RegUnlock(void);
+
+/**
+ * @Param
+ none
+
+ * @Returns
+ none
+
+ * @Description
+ Locks the write protected register to disable any write operation
+
+ * @Example
+ SYSTEM_RegLock();
+ */
+
+void SYSTEM_RegLock(void);
+
+/**
+ * @Param
+ none
+
+ * @Returns
+ none
+
+ * @Description
+ Initializes the device to the default states configured in the
+ * MCC GUI
+ * @Example
+ SYSTEM_Initialize(void);
+ */
+
+void SYSTEM_Initialize(void);
+
+/**
+ * @Param
+ none
+ * @Returns
+ none
+ * @Description
+ Initializes the oscillator to the default states configured in the
+ * MCC GUI
+ * @Example
+ OSCILLATOR_Initialize(void);
+ */
+void OSCILLATOR_Initialize(void);
+
+/**
+ * @Param
+ none
+
+ * @Returns
+ none
+
+ * @Description
+ Automatically called whenever there is a un-handled exception
+
+ * @Example
+ none
+ */
+
+void _general_exception_handler (void);
+
+#endif /* MCC_H */
+/**
+ End of File
+*/ \ No newline at end of file
diff --git a/mcc_generated_files/pin_manager.cpp b/mcc_generated_files/pin_manager.cpp
new file mode 100644
index 0000000..6124d56
--- /dev/null
+++ b/mcc_generated_files/pin_manager.cpp
@@ -0,0 +1,131 @@
+/**
+ System Interrupts Generated Driver File
+
+ @Company:
+ Microchip Technology Inc.
+
+ @File Name:
+ pin_manager.c
+
+ @Summary:
+ This is the generated manager file for the MPLAB(c) Code Configurator device. This manager
+ configures the pins direction, initial state, analog setting.
+ The peripheral pin select, PPS, configuration is also handled by this manager.
+
+ @Description:
+ This source file provides implementations for MPLAB(c) Code Configurator interrupts.
+ Generation Information :
+ Product Revision : MPLAB(c) Code Configurator - 4.45
+ Device : PIC32MX470F512H
+ Version : 1.02
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+
+ Copyright (c) 2013 - 2015 released Microchip Technology Inc. All rights reserved.
+
+ Microchip licenses to you the right to use, modify, copy and distribute
+ Software only when embedded on a Microchip microcontroller or digital signal
+ controller that is integrated into your product or third party product
+ (pursuant to the sublicense terms in the accompanying license agreement).
+
+ You should refer to the license agreement accompanying this Software for
+ additional information regarding your rights and obligations.
+
+ SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND,
+ EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT LIMITATION, ANY WARRANTY OF
+ MERCHANTABILITY, TITLE, NON-INFRINGEMENT AND FITNESS FOR A PARTICULAR PURPOSE.
+ IN NO EVENT SHALL MICROCHIP OR ITS LICENSORS BE LIABLE OR OBLIGATED UNDER
+ CONTRACT, NEGLIGENCE, STRICT LIABILITY, CONTRIBUTION, BREACH OF WARRANTY, OR
+ OTHER LEGAL EQUITABLE THEORY ANY DIRECT OR INDIRECT DAMAGES OR EXPENSES
+ INCLUDING BUT NOT LIMITED TO ANY INCIDENTAL, SPECIAL, INDIRECT, PUNITIVE OR
+ CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF PROCUREMENT OF
+ SUBSTITUTE GOODS, TECHNOLOGY, SERVICES, OR ANY CLAIMS BY THIRD PARTIES
+ (INCLUDING BUT NOT LIMITED TO ANY DEFENSE THEREOF), OR OTHER SIMILAR COSTS.
+
+*/
+
+
+/**
+ Section: Includes
+*/
+#include <xc.h>
+#include <sys/attribs.h>
+#include "pin_manager.hpp"
+#include "mcc.hpp"
+
+/**
+ void PIN_MANAGER_Initialize(void)
+*/
+void PIN_MANAGER_Initialize(void)
+{
+ /****************************************************************************
+ * Setting the Output Latch SFR(s)
+ ***************************************************************************/
+ LATB = 0x0000;
+ LATC = 0x0000;
+ LATD = 0x0000;
+ LATE = 0x0000;
+ LATF = 0x0000;
+ LATG = 0x0000;
+
+ /****************************************************************************
+ * Setting the GPIO Direction SFR(s)
+ ***************************************************************************/
+ TRISB = 0xFFFF;
+ TRISC = 0xF000;
+ TRISD = 0x0FFF;
+ TRISE = 0x002F;
+ TRISF = 0x003A;
+ TRISG = 0x03C0;
+
+ /****************************************************************************
+ * Setting the Weak Pull Up and Weak Pull Down SFR(s)
+ ***************************************************************************/
+ CNPDB = 0x0000;
+ CNPDC = 0x0000;
+ CNPDD = 0x0000;
+ CNPDE = 0x0000;
+ CNPDF = 0x0000;
+ CNPDG = 0x0000;
+ CNPUB = 0x0000;
+ CNPUC = 0x0000;
+ CNPUD = 0x0000;
+ CNPUE = 0x0000;
+ CNPUF = 0x0000;
+ CNPUG = 0x0000;
+
+ /****************************************************************************
+ * Setting the Open Drain SFR(s)
+ ***************************************************************************/
+ ODCB = 0x0000;
+ ODCC = 0x0000;
+ ODCD = 0x0000;
+ ODCE = 0x0000;
+ ODCF = 0x0000;
+ ODCG = 0x0000;
+
+ /****************************************************************************
+ * Setting the Analog/Digital Configuration SFR(s)
+ ***************************************************************************/
+ ANSELB = 0xFFFC;
+ ANSELC = 0xF000;
+ ANSELD = 0x000E;
+ ANSELE = 0x00F4;
+ ANSELG = 0x03C0;
+
+ /****************************************************************************
+ * Set the PPS
+ ***************************************************************************/
+ SYSTEM_RegUnlock(); // unlock PPS
+ CFGCONbits.IOLOCK = 0;
+
+ U1RXRbits.U1RXR = 0x0004; //RF1->UART1:U1RX;
+ RPF0Rbits.RPF0R = 0x0003; //RF0->UART1:U1TX;
+
+ CFGCONbits.IOLOCK = 1; // lock PPS
+ SYSTEM_RegLock();
+
+
+}
+
diff --git a/mcc_generated_files/pin_manager.hpp b/mcc_generated_files/pin_manager.hpp
new file mode 100644
index 0000000..650fe9a
--- /dev/null
+++ b/mcc_generated_files/pin_manager.hpp
@@ -0,0 +1,530 @@
+/**
+ System Interrupts Generated Driver File
+
+ @Company:
+ Microchip Technology Inc.
+
+ @File Name:
+ pin_manager.h
+
+ @Summary:
+ This is the generated manager file for the MPLAB(c) Code Configurator device. This manager
+ configures the pins direction, initial state, analog setting.
+ The peripheral pin select, PPS, configuration is also handled by this manager.
+
+ @Description:
+ This source file provides implementations for MPLAB(c) Code Configurator interrupts.
+ Generation Information :
+ Product Revision : MPLAB(c) Code Configurator - 4.45
+ Device : PIC32MX470F512H
+ Version : 1.02
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+
+ Copyright (c) 2013 - 2015 released Microchip Technology Inc. All rights reserved.
+
+ Microchip licenses to you the right to use, modify, copy and distribute
+ Software only when embedded on a Microchip microcontroller or digital signal
+ controller that is integrated into your product or third party product
+ (pursuant to the sublicense terms in the accompanying license agreement).
+
+ You should refer to the license agreement accompanying this Software for
+ additional information regarding your rights and obligations.
+
+ SOFTWARE AND DOCUMENTATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND,
+ EITHER EXPRESS OR IMPLIED, INCLUDING WITHOUT LIMITATION, ANY WARRANTY OF
+ MERCHANTABILITY, TITLE, NON-INFRINGEMENT AND FITNESS FOR A PARTICULAR PURPOSE.
+ IN NO EVENT SHALL MICROCHIP OR ITS LICENSORS BE LIABLE OR OBLIGATED UNDER
+ CONTRACT, NEGLIGENCE, STRICT LIABILITY, CONTRIBUTION, BREACH OF WARRANTY, OR
+ OTHER LEGAL EQUITABLE THEORY ANY DIRECT OR INDIRECT DAMAGES OR EXPENSES
+ INCLUDING BUT NOT LIMITED TO ANY INCIDENTAL, SPECIAL, INDIRECT, PUNITIVE OR
+ CONSEQUENTIAL DAMAGES, LOST PROFITS OR LOST DATA, COST OF PROCUREMENT OF
+ SUBSTITUTE GOODS, TECHNOLOGY, SERVICES, OR ANY CLAIMS BY THIRD PARTIES
+ (INCLUDING BUT NOT LIMITED TO ANY DEFENSE THEREOF), OR OTHER SIMILAR COSTS.
+
+*/
+
+#ifndef _PIN_MANAGER_H
+#define _PIN_MANAGER_H
+/**
+ Section: Includes
+*/
+#include <xc.h>
+/**
+ Section: Device Pin Macros
+*/
+/**
+ @Summary
+ Sets the GPIO pin, RE4, high using LATEbits.LATE4.
+
+ @Description
+ Sets the GPIO pin, RE4, high using LATEbits.LATE4.
+
+ @Preconditions
+ The RE4 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Set RE4 high (1)
+ LED1_SetHigh();
+ </code>
+
+*/
+#define LED1_SetHigh() LATEbits.LATE4 = 1
+/**
+ @Summary
+ Sets the GPIO pin, RE4, low using LATEbits.LATE4.
+
+ @Description
+ Sets the GPIO pin, RE4, low using LATEbits.LATE4.
+
+ @Preconditions
+ The RE4 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Set RE4 low (0)
+ LED1_SetLow();
+ </code>
+
+*/
+#define LED1_SetLow() LATEbits.LATE4 = 0
+/**
+ @Summary
+ Toggles the GPIO pin, RE4, using LATEbits.LATE4.
+
+ @Description
+ Toggles the GPIO pin, RE4, using LATEbits.LATE4.
+
+ @Preconditions
+ The RE4 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Toggle RE4
+ LED1_Toggle();
+ </code>
+
+*/
+#define LED1_Toggle() LATEbits.LATE4 ^= 1
+/**
+ @Summary
+ Reads the value of the GPIO pin, RE4.
+
+ @Description
+ Reads the value of the GPIO pin, RE4.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ uint16_t portValue;
+
+ // Read RE4
+ postValue = LED1_GetValue();
+ </code>
+
+*/
+#define LED1_GetValue() PORTEbits.RE4
+/**
+ @Summary
+ Configures the GPIO pin, RE4, as an input.
+
+ @Description
+ Configures the GPIO pin, RE4, as an input.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Sets the RE4 as an input
+ LED1_SetDigitalInput();
+ </code>
+
+*/
+#define LED1_SetDigitalInput() TRISEbits.TRISE4 = 1
+/**
+ @Summary
+ Configures the GPIO pin, RE4, as an output.
+
+ @Description
+ Configures the GPIO pin, RE4, as an output.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Sets the RE4 as an output
+ LED1_SetDigitalOutput();
+ </code>
+
+*/
+#define LED1_SetDigitalOutput() TRISEbits.TRISE4 = 0
+/**
+ @Summary
+ Sets the GPIO pin, RE6, high using LATEbits.LATE6.
+
+ @Description
+ Sets the GPIO pin, RE6, high using LATEbits.LATE6.
+
+ @Preconditions
+ The RE6 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Set RE6 high (1)
+ LED2_SetHigh();
+ </code>
+
+*/
+#define LED2_SetHigh() LATEbits.LATE6 = 1
+/**
+ @Summary
+ Sets the GPIO pin, RE6, low using LATEbits.LATE6.
+
+ @Description
+ Sets the GPIO pin, RE6, low using LATEbits.LATE6.
+
+ @Preconditions
+ The RE6 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Set RE6 low (0)
+ LED2_SetLow();
+ </code>
+
+*/
+#define LED2_SetLow() LATEbits.LATE6 = 0
+/**
+ @Summary
+ Toggles the GPIO pin, RE6, using LATEbits.LATE6.
+
+ @Description
+ Toggles the GPIO pin, RE6, using LATEbits.LATE6.
+
+ @Preconditions
+ The RE6 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Toggle RE6
+ LED2_Toggle();
+ </code>
+
+*/
+#define LED2_Toggle() LATEbits.LATE6 ^= 1
+/**
+ @Summary
+ Reads the value of the GPIO pin, RE6.
+
+ @Description
+ Reads the value of the GPIO pin, RE6.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ uint16_t portValue;
+
+ // Read RE6
+ postValue = LED2_GetValue();
+ </code>
+
+*/
+#define LED2_GetValue() PORTEbits.RE6
+/**
+ @Summary
+ Configures the GPIO pin, RE6, as an input.
+
+ @Description
+ Configures the GPIO pin, RE6, as an input.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Sets the RE6 as an input
+ LED2_SetDigitalInput();
+ </code>
+
+*/
+#define LED2_SetDigitalInput() TRISEbits.TRISE6 = 1
+/**
+ @Summary
+ Configures the GPIO pin, RE6, as an output.
+
+ @Description
+ Configures the GPIO pin, RE6, as an output.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Sets the RE6 as an output
+ LED2_SetDigitalOutput();
+ </code>
+
+*/
+#define LED2_SetDigitalOutput() TRISEbits.TRISE6 = 0
+/**
+ @Summary
+ Sets the GPIO pin, RE7, high using LATEbits.LATE7.
+
+ @Description
+ Sets the GPIO pin, RE7, high using LATEbits.LATE7.
+
+ @Preconditions
+ The RE7 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Set RE7 high (1)
+ LED3_SetHigh();
+ </code>
+
+*/
+#define LED3_SetHigh() LATEbits.LATE7 = 1
+/**
+ @Summary
+ Sets the GPIO pin, RE7, low using LATEbits.LATE7.
+
+ @Description
+ Sets the GPIO pin, RE7, low using LATEbits.LATE7.
+
+ @Preconditions
+ The RE7 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Set RE7 low (0)
+ LED3_SetLow();
+ </code>
+
+*/
+#define LED3_SetLow() LATEbits.LATE7 = 0
+/**
+ @Summary
+ Toggles the GPIO pin, RE7, using LATEbits.LATE7.
+
+ @Description
+ Toggles the GPIO pin, RE7, using LATEbits.LATE7.
+
+ @Preconditions
+ The RE7 must be set to an output.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Toggle RE7
+ LED3_Toggle();
+ </code>
+
+*/
+#define LED3_Toggle() LATEbits.LATE7 ^= 1
+/**
+ @Summary
+ Reads the value of the GPIO pin, RE7.
+
+ @Description
+ Reads the value of the GPIO pin, RE7.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ uint16_t portValue;
+
+ // Read RE7
+ postValue = LED3_GetValue();
+ </code>
+
+*/
+#define LED3_GetValue() PORTEbits.RE7
+/**
+ @Summary
+ Configures the GPIO pin, RE7, as an input.
+
+ @Description
+ Configures the GPIO pin, RE7, as an input.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Sets the RE7 as an input
+ LED3_SetDigitalInput();
+ </code>
+
+*/
+#define LED3_SetDigitalInput() TRISEbits.TRISE7 = 1
+/**
+ @Summary
+ Configures the GPIO pin, RE7, as an output.
+
+ @Description
+ Configures the GPIO pin, RE7, as an output.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ // Sets the RE7 as an output
+ LED3_SetDigitalOutput();
+ </code>
+
+*/
+#define LED3_SetDigitalOutput() TRISEbits.TRISE7 = 0
+
+/**
+ Section: Function Prototypes
+*/
+/**
+ @Summary
+ Configures the pin settings of the PIC32MX470F512H
+ The peripheral pin select, PPS, configuration is also handled by this manager.
+
+ @Description
+ This is the generated manager file for the MPLAB(c) Code Configurator device. This manager
+ configures the pins direction, initial state, analog setting.
+ The peripheral pin select, PPS, configuration is also handled by this manager.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ void SYSTEM_Initialize(void)
+ {
+ // Other initializers are called from this function
+ PIN_MANAGER_Initialize();
+ }
+ </code>
+
+*/
+void PIN_MANAGER_Initialize(void);
+
+#endif
diff --git a/mcc_generated_files/uart1.cpp b/mcc_generated_files/uart1.cpp
new file mode 100644
index 0000000..96ed3e3
--- /dev/null
+++ b/mcc_generated_files/uart1.cpp
@@ -0,0 +1,390 @@
+/**
+ UART1 Generated Driver File
+
+ @Company
+ Microchip Technology Inc.
+
+ @File Name
+ uart1.c
+
+ @Summary
+ This is the generated source file for the UART1 driver using PIC32MX MCUs
+
+ @Description
+ This source file provides APIs for driver for UART1.
+ Generation Information :
+ Product Revision : PIC32MX MCUs - pic32mx : v1.35
+ Device : PIC32MX470F512H
+ Driver Version : 0.5
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+*/
+
+/*
+ (c) 2016 Microchip Technology Inc. and its subsidiaries. You may use this
+ software and any derivatives exclusively with Microchip products.
+
+ 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, OR ITS INTERACTION WITH MICROCHIP PRODUCTS, COMBINATION
+ WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
+
+ 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.
+
+ MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE OF THESE
+ TERMS.
+*/
+
+/**
+ Section: Included Files
+*/
+
+#include "uart1.hpp"
+
+/**
+ Section: Data Type Definitions
+*/
+
+/** UART Driver Queue Status
+
+ @Summary
+ Defines the object required for the status of the queue.
+*/
+
+union UART_BYTEQ_STATUS
+{
+ struct
+ {
+ uint8_t full:1;
+ uint8_t empty:1;
+ uint8_t reserved:6;
+ } s;
+ uint8_t status;
+};
+
+/** UART Driver Hardware Instance Object
+
+ @Summary
+ Defines the object required for the maintenance of the hardware instance.
+
+*/
+struct UART_OBJECT
+{
+ /* RX Byte Q */
+ uint8_t *rxTail;
+ uint8_t *rxHead;
+
+ /* TX Byte Q */
+ uint8_t *txTail;
+ uint8_t *txHead;
+ UART_BYTEQ_STATUS rxStatus;
+ UART_BYTEQ_STATUS txStatus;
+
+};
+
+static UART_OBJECT uart1_obj;
+
+/** UART Driver Queue Length
+
+ @Summary
+ Defines the length of the Transmit and Receive Buffers
+
+*/
+
+#define UART1_CONFIG_TX_BYTEQ_LENGTH 8
+#define UART1_CONFIG_RX_BYTEQ_LENGTH 8
+
+
+/** UART Driver Queue
+
+ @Summary
+ Defines the Transmit and Receive Buffers
+
+*/
+
+static uint8_t uart1_txByteQ[UART1_CONFIG_TX_BYTEQ_LENGTH];
+static uint8_t uart1_rxByteQ[UART1_CONFIG_RX_BYTEQ_LENGTH];
+
+/** UART Hardware FIFO Buffer Length
+
+ @Summary
+ Defines the length of the Transmit and Receive FIFOs
+
+*/
+
+#define UART1_TX_FIFO_LENGTH 1
+#define UART1_RX_FIFO_LENGTH 1
+
+/**
+ Section: Driver Interface
+*/
+
+
+void UART1_Initialize (void)
+{
+ // STSEL 1S; IREN disabled; PDSEL 8N; RTSMD disabled; RXINV disabled; SIDL disabled; WAKE disabled; ABAUD disabled; LPBACK disabled; BRGH enabled; UEN TX_RX; ON enabled;
+ U1MODE = 0x8008;
+ // UTXISEL TX_ONE_CHAR; UTXINV disabled; ADDR 0; URXEN disabled; OERR disabled; ADM_EN disabled; URXISEL RX_ONE_CHAR; UTXBRK disabled; UTXEN disabled; ADDEN disabled;
+ U1STA = 0x0;
+ // U1TXREG 0;
+ U1TXREG = 0x0;
+ // BaudRate = 9600; Frequency = 1000000 Hz; BRG 25;
+ U1BRG = 0x19;
+
+ IEC1bits.U1RXIE = 1;
+
+ U1STAbits.UTXEN = 1;
+ U1STAbits.URXEN = 1;
+
+ //Enabling UART
+ U1MODEbits.ON = 1;
+
+ uart1_obj.txHead = uart1_txByteQ;
+ uart1_obj.txTail = uart1_txByteQ;
+ uart1_obj.rxHead = uart1_rxByteQ;
+ uart1_obj.rxTail = uart1_rxByteQ;
+ uart1_obj.rxStatus.s.empty = true;
+ uart1_obj.txStatus.s.empty = true;
+ uart1_obj.txStatus.s.full = false;
+ uart1_obj.rxStatus.s.full = false;
+}
+
+
+/**
+ Maintains the driver's transmitter/receiver/error state machine and implements its ISR
+*/
+void __ISR(_UART_1_VECTOR, IPL1AUTO) _UART_1 (void)
+{
+ if(IFS1bits.U1RXIF) {
+ int count = 0;
+
+ while((count < UART1_RX_FIFO_LENGTH) && (U1STAbits.URXDA == 1)) {
+ count++;
+
+ *uart1_obj.rxTail = U1RXREG;
+ uart1_obj.rxTail++;
+
+ if(uart1_obj.rxTail == (uart1_rxByteQ + UART1_CONFIG_RX_BYTEQ_LENGTH)) {
+ uart1_obj.rxTail = uart1_rxByteQ;
+ }
+
+ uart1_obj.rxStatus.s.empty = false;
+
+ if(uart1_obj.rxTail == uart1_obj.rxHead) {
+ //Sets the flag RX full
+ uart1_obj.rxStatus.s.full = true;
+ break;
+ }
+ }
+
+ IFS1CLR= 1 << _IFS1_U1RXIF_POSITION;
+ } else if (IFS1bits.U1TXIF) {
+ if(uart1_obj.txStatus.s.empty) {
+ IEC1bits.U1TXIE = false;
+ return;
+ }
+
+ IFS1CLR= 1 << _IFS1_U1TXIF_POSITION;
+
+ int count = 0;
+ while((count < UART1_TX_FIFO_LENGTH)&& !(U1STAbits.UTXBF == 1)) {
+ count++;
+
+ U1TXREG = *uart1_obj.txHead;
+
+ uart1_obj.txHead++;
+
+ if(uart1_obj.txHead == (uart1_txByteQ + UART1_CONFIG_TX_BYTEQ_LENGTH)) {
+ uart1_obj.txHead = uart1_txByteQ;
+ }
+
+ uart1_obj.txStatus.s.full = false;
+
+ if(uart1_obj.txHead == uart1_obj.txTail) {
+ uart1_obj.txStatus.s.empty = true;
+ break;
+ }
+ }
+ } else {
+ if ((U1STAbits.OERR == 1)) {
+ U1STAbits.OERR = 0;
+ }
+
+ IFS1CLR= 1 << _IFS1_U1EIF_POSITION;
+ }
+}
+
+/**
+ Section: UART Driver Client Routines
+*/
+
+uint8_t UART1_Read(void)
+{
+ uint8_t data = 0;
+
+ data = *uart1_obj.rxHead;
+
+ uart1_obj.rxHead++;
+
+ if (uart1_obj.rxHead == (uart1_rxByteQ + UART1_CONFIG_RX_BYTEQ_LENGTH)) {
+ uart1_obj.rxHead = uart1_rxByteQ;
+ }
+
+ if (uart1_obj.rxHead == uart1_obj.rxTail) {
+ uart1_obj.rxStatus.s.empty = true;
+ }
+
+ uart1_obj.rxStatus.s.full = false;
+
+ return data;
+}
+
+
+unsigned int UART1_ReadBuffer(uint8_t *buffer, const unsigned int bufLen)
+{
+ unsigned int numBytesRead = 0;
+
+ while (numBytesRead < ( bufLen )) {
+ if(uart1_obj.rxStatus.s.empty) {
+ break;
+ } else {
+ buffer[numBytesRead++] = UART1_Read () ;
+ }
+ }
+
+ return numBytesRead ;
+}
+
+
+
+void UART1_Write(const uint8_t byte)
+{
+ IEC1bits.U1TXIE = false;
+
+ *uart1_obj.txTail = byte;
+ uart1_obj.txTail++;
+
+ if (uart1_obj.txTail == (uart1_txByteQ + UART1_CONFIG_TX_BYTEQ_LENGTH)) {
+ uart1_obj.txTail = uart1_txByteQ;
+ }
+
+ uart1_obj.txStatus.s.empty = false;
+
+ if (uart1_obj.txHead == uart1_obj.txTail) {
+ uart1_obj.txStatus.s.full = true;
+ }
+
+ IEC1bits.U1TXIE = true ;
+
+}
+
+
+unsigned int UART1_WriteBuffer(const uint8_t *buffer , const unsigned int bufLen )
+{
+ unsigned int numBytesWritten = 0 ;
+
+ while ( numBytesWritten < ( bufLen )) {
+ if((uart1_obj.txStatus.s.full)) {
+ break;
+ } else {
+ UART1_Write (buffer[numBytesWritten++] ) ;
+ }
+ }
+
+ return numBytesWritten ;
+
+}
+
+
+UART1_TRANSFER_STATUS UART1_TransferStatusGet (void)
+{
+ uint8_t status = 0;
+
+ if(uart1_obj.txStatus.s.full) {
+ status |= UART1_TRANSFER_STATUS_TX_FULL;
+ }
+
+ if(uart1_obj.txStatus.s.empty) {
+ status |= UART1_TRANSFER_STATUS_TX_EMPTY;
+ }
+
+ if(uart1_obj.rxStatus.s.full) {
+ status |= UART1_TRANSFER_STATUS_RX_FULL;
+ }
+
+ if(uart1_obj.rxStatus.s.empty) {
+ status |= UART1_TRANSFER_STATUS_RX_EMPTY;
+ } else {
+ status |= UART1_TRANSFER_STATUS_RX_DATA_PRESENT;
+ }
+
+ return static_cast<UART1_TRANSFER_STATUS>(status);
+}
+
+
+uint8_t UART1_Peek(uint16_t offset)
+{
+ if( (uart1_obj.rxHead + offset) > (uart1_rxByteQ + UART1_CONFIG_RX_BYTEQ_LENGTH)) {
+ return uart1_rxByteQ[offset - (uart1_rxByteQ + UART1_CONFIG_RX_BYTEQ_LENGTH - uart1_obj.rxHead)];
+ } else {
+ return *(uart1_obj.rxHead + offset);
+ }
+}
+
+
+unsigned int UART1_ReceiveBufferSizeGet(void)
+{
+ if(!uart1_obj.rxStatus.s.full) {
+ if(uart1_obj.rxHead > uart1_obj.rxTail) {
+ return(uart1_obj.rxHead - uart1_obj.rxTail);
+ } else {
+ return(UART1_CONFIG_RX_BYTEQ_LENGTH - (uart1_obj.rxTail - uart1_obj.rxHead));
+ }
+ }
+ return 0;
+}
+
+
+unsigned int UART1_TransmitBufferSizeGet(void)
+{
+ if(!uart1_obj.txStatus.s.full) {
+ if(uart1_obj.txHead > uart1_obj.txTail) {
+ return (uart1_obj.txHead - uart1_obj.txTail);
+ } else {
+ return (UART1_CONFIG_TX_BYTEQ_LENGTH - (uart1_obj.txTail - uart1_obj.txHead));
+ }
+ }
+ return 0;
+}
+
+
+bool UART1_ReceiveBufferIsEmpty (void)
+{
+ return(uart1_obj.rxStatus.s.empty);
+}
+
+
+bool UART1_TransmitBufferIsFull(void)
+{
+ return(uart1_obj.txStatus.s.full);
+}
+
+
+UART1_STATUS UART1_StatusGet (void)
+{
+ return static_cast<UART1_STATUS>(U1STA);
+}
+
+
+
+/**
+ End of File
+*/
diff --git a/mcc_generated_files/uart1.hpp b/mcc_generated_files/uart1.hpp
new file mode 100644
index 0000000..db61d1e
--- /dev/null
+++ b/mcc_generated_files/uart1.hpp
@@ -0,0 +1,624 @@
+/**
+ UART1 Generated Driver API Header File
+
+ @Company
+ Microchip Technology Inc.
+
+ @File Name
+ uart1.h
+
+ @Summary
+ This is the generated header file for the UART1 driver using PIC32MX MCUs
+
+ @Description
+ This header file provides APIs for driver for UART1.
+ Generation Information :
+ Product Revision : PIC32MX MCUs - pic32mx : v1.35
+ Device : PIC32MX470F512H
+ Driver Version : 0.5
+ The generated drivers are tested against the following:
+ Compiler : XC32 1.42
+ MPLAB : MPLAB X 3.55
+*/
+
+/*
+ (c) 2016 Microchip Technology Inc. and its subsidiaries. You may use this
+ software and any derivatives exclusively with Microchip products.
+
+ 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, OR ITS INTERACTION WITH MICROCHIP PRODUCTS, COMBINATION
+ WITH ANY OTHER PRODUCTS, OR USE IN ANY APPLICATION.
+
+ 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.
+
+ MICROCHIP PROVIDES THIS SOFTWARE CONDITIONALLY UPON YOUR ACCEPTANCE OF THESE
+ TERMS.
+*/
+
+#ifndef _UART1_H
+#define _UART1_H
+
+/**
+ Section: Included Files
+*/
+
+#include <xc.h>
+#include <stdbool.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <sys/attribs.h>
+#ifdef __cplusplus // Provide C++ Compatibility
+
+ extern "C" {
+
+#endif
+
+/**
+ Section: Data Types
+*/
+
+/** UART1 Driver Hardware Flags
+
+ @Summary
+ Specifies the status of the hardware receive or transmit
+
+ @Description
+ This type specifies the status of the hardware receive or transmit.
+ More than one of these values may be OR'd together to create a complete
+ status value. To test a value of this type, the bit of interest must be
+ AND'ed with value and checked to see if the result is non-zero.
+*/
+typedef enum
+{
+ /* Indicates that Receive buffer has data, at least one more character can be read */
+ UART1_RX_DATA_AVAILABLE
+ /*DOM-IGNORE-BEGIN*/ = (1 << 0) /*DOM-IGNORE-END*/,
+
+ /* Indicates that Receive buffer has overflowed */
+ UART1_RX_OVERRUN_ERROR
+ /*DOM-IGNORE-BEGIN*/ = (1 << 1) /*DOM-IGNORE-END*/,
+
+ /* Indicates that Framing error has been detected for the current character */
+ UART1_FRAMING_ERROR
+ /*DOM-IGNORE-BEGIN*/ = (1 << 2) /*DOM-IGNORE-END*/,
+
+ /* Indicates that Parity error has been detected for the current character */
+ UART1_PARITY_ERROR
+ /*DOM-IGNORE-BEGIN*/ = (1 << 3) /*DOM-IGNORE-END*/,
+
+ /* Indicates that Receiver is Idle */
+ UART1_RECEIVER_IDLE
+ /*DOM-IGNORE-BEGIN*/ = (1 << 4) /*DOM-IGNORE-END*/,
+
+ /* Indicates that the last transmission has completed */
+ UART1_TX_COMPLETE
+ /*DOM-IGNORE-BEGIN*/ = (1 << 8) /*DOM-IGNORE-END*/,
+
+ /* Indicates that Transmit buffer is full */
+ UART1_TX_FULL
+ /*DOM-IGNORE-BEGIN*/ = (1 << 9) /*DOM-IGNORE-END*/
+
+}UART1_STATUS;
+
+
+
+/** UART1 Driver Transfer Flags
+
+ @Summary
+ Specifies the status of the receive or transmit
+
+ @Description
+ This type specifies the status of the receive or transmit operation.
+ More than one of these values may be OR'd together to create a complete
+ status value. To test a value of this type, the bit of interest must be
+ AND'ed with value and checked to see if the result is non-zero.
+*/
+
+typedef enum
+{
+ /* Indicates that the core driver buffer is full */
+ UART1_TRANSFER_STATUS_RX_FULL
+ /*DOM-IGNORE-BEGIN*/ = (1 << 0) /*DOM-IGNORE-END*/,
+
+ /* Indicates that at least one byte of Data has been received */
+ UART1_TRANSFER_STATUS_RX_DATA_PRESENT
+ /*DOM-IGNORE-BEGIN*/ = (1 << 1) /*DOM-IGNORE-END*/,
+
+ /* Indicates that the core driver receiver buffer is empty */
+ UART1_TRANSFER_STATUS_RX_EMPTY
+ /*DOM-IGNORE-BEGIN*/ = (1 << 2) /*DOM-IGNORE-END*/,
+
+ /* Indicates that the core driver transmitter buffer is full */
+ UART1_TRANSFER_STATUS_TX_FULL
+ /*DOM-IGNORE-BEGIN*/ = (1 << 3) /*DOM-IGNORE-END*/,
+
+ /* Indicates that the core driver transmitter buffer is empty */
+ UART1_TRANSFER_STATUS_TX_EMPTY
+ /*DOM-IGNORE-BEGIN*/ = (1 << 4) /*DOM-IGNORE-END*/
+
+} UART1_TRANSFER_STATUS;
+
+
+/**
+ Section: UART1 Driver Routines
+*/
+
+void _UART_1(void);
+
+/**
+ @Summary
+ Initializes the UART instance : 1
+
+ @Description
+ This routine initializes the UART driver instance for : 1
+ index.
+ This routine must be called before any other UART routine is called.
+
+ @Preconditions
+ None.
+
+ @Returns
+ None.
+
+ @Param
+ None.
+
+ @Comment
+
+
+ @Example
+ <code>
+ const uint8_t writeBuffer[35] = "1234567890ABCDEFGHIJKLMNOP\n" ;
+ unsigned int numBytes = 0;
+ int writebufferLen = strlen((char *)writeBuffer);
+ UART1_Initialize();
+ while(numBytes < writebufferLen)
+ {
+ int bytesToWrite = UART1_TransmitBufferSizeGet();
+ numBytes = UART1_WriteBuffer ( writeBuffer+numBytes, bytesToWrite) ;
+ UART1_TasksTransmit ( );
+ if (!UART1_TransmitBufferisFull())
+ {
+ //continue other operation
+ }
+ }
+ </code>
+
+*/
+
+void UART1_Initialize(void);
+
+/**
+ @Summary
+ Read a byte of data from the UART1
+
+ @Description
+ This routine reads a byte of data from the UART1.
+
+ @Preconditions
+ UART1_Initializer function should have been called
+ before calling this function. The transfer status should be checked to see
+ if the receiver is not empty before calling this function.
+
+ @Param
+ None.
+
+ @Returns
+ A data byte received by the driver.
+
+ @Example
+ <code>
+ char myBuffer[MY_BUFFER_SIZE];
+ unsigned int numBytes;
+
+ numBytes = 0;
+ do
+ {
+ if( UART1_TRANSFER_STATUS_RX_DATA_PRESENT & UART1_TransferStatusGet() )
+ {
+ myBuffer[numBytes++] = UART1_Read();
+ }
+
+ // Do something else...
+
+ } while( numBytes < MY_BUFFER_SIZE);
+ </code>
+*/
+
+uint8_t UART1_Read( void);
+
+/**
+ @Summary
+ Returns the number of bytes read by the UART1 peripheral
+
+ @Description
+ This routine returns the number of bytes read by the Peripheral and fills the
+ application read buffer with the read data.
+
+ @Preconditions
+ UART1_Initializer function should have been called
+ before calling this function
+
+ @Param
+ buffer - Buffer into which the data read from the UART1
+
+ @Param
+ numbytes - Total number of bytes that need to be read from the UART1
+ (must be equal to or less than the size of the buffer)
+
+ @Returns
+ Number of bytes actually copied into the caller's buffer or -1 if there
+ is an error.
+
+ @Example
+ <code>
+ char myBuffer[MY_BUFFER_SIZE];
+ unsigned int numBytes;
+ UART1_TRANSFER_STATUS status ;
+
+ // Pre-initialize myBuffer with MY_BUFFER_SIZE bytes of valid data.
+
+ numBytes = 0;
+ while( numBytes < MY_BUFFER_SIZE);
+ {
+ status = UART1_TransferStatusGet ( ) ;
+ if (status & UART1_TRANSFER_STATUS_RX_FULL)
+ {
+ numBytes += UART1_ReadBuffer( myBuffer + numBytes, MY_BUFFER_SIZE - numBytes ) ;
+ if(numBytes < readbufferLen)
+ {
+ continue;
+ }
+ else
+ {
+ break;
+ }
+ }
+ else
+ {
+ continue;
+ }
+
+ // Do something else...
+ }
+ </code>
+*/
+
+unsigned int UART1_ReadBuffer( uint8_t *buffer , const unsigned int numbytes);
+
+/**
+ @Summary
+ Writes a byte of data to the UART1
+
+ @Description
+ This routine writes a byte of data to the UART1.
+
+ @Preconditions
+ UART1_Initializer function should have been called
+ before calling this function. The transfer status should be checked to see if
+ transmitter is not full before calling this function.
+
+ @Param
+ byte - Data byte to write to the UART1
+
+ @Returns
+ None.
+
+ @Example
+ <code>
+ char myBuffer[MY_BUFFER_SIZE];
+ unsigned int numBytes;
+
+ // Pre-initialize myBuffer with MY_BUFFER_SIZE bytes of valid data.
+
+ numBytes = 0;
+ while( numBytes < MY_BUFFER_SIZE);
+ {
+ if( !(UART1_TRANSFER_STATUS_TX_FULL & UART1_TransferStatusGet()) )
+ {
+ UART1_Write(handle, myBuffer[numBytes++]);
+ }
+
+ // Do something else...
+ }
+ </code>
+*/
+
+void UART1_Write( const uint8_t byte);
+
+/**
+ @Summary
+ Returns the number of bytes written into the internal buffer
+
+ @Description
+ This API transfers the data from application buffer to internal buffer and
+ returns the number of bytes added in that queue
+
+ @Preconditions
+ UART1_Initializer function should have been called
+ before calling this function
+
+ @Example
+ <code>
+ char myBuffer[MY_BUFFER_SIZE];
+ unsigned int numBytes;
+ UART1_TRANSFER_STATUS status ;
+
+ // Pre-initialize myBuffer with MY_BUFFER_SIZE bytes of valid data.
+
+ numBytes = 0;
+ while( numBytes < MY_BUFFER_SIZE);
+ {
+ status = UART1_TransferStatusGet ( ) ;
+ if (status & UART1_TRANSFER_STATUS_TX_EMPTY)
+ {
+ numBytes += UART1_WriteBuffer ( myBuffer + numBytes, MY_BUFFER_SIZE - numBytes ) ;
+ if(numBytes < writebufferLen)
+ {
+ continue;
+ }
+ else
+ {
+ break;
+ }
+ }
+ else
+ {
+ continue;
+ }
+
+ // Do something else...
+ }
+ </code>
+*/
+
+unsigned int UART1_WriteBuffer( const uint8_t *buffer , const unsigned int numbytes );
+
+/**
+ @Summary
+ Returns the transmitter and receiver transfer status
+
+ @Description
+ This returns the transmitter and receiver transfer status.The returned status
+ may contain a value with more than one of the bits
+ specified in the UART1_TRANSFER_STATUS enumeration set.
+ The caller should perform an "AND" with the bit of interest and verify if the
+ result is non-zero (as shown in the example) to verify the desired status
+ bit.
+
+ @Preconditions
+ UART1_Initializer function should have been called
+ before calling this function
+
+ @Param
+ None.
+
+ @Returns
+ A UART1_TRANSFER_STATUS value describing the current status
+ of the transfer.
+
+ @Example
+ Refer to UART1_ReadBuffer and UART1_WriteBuffer for example
+
+*/
+
+UART1_TRANSFER_STATUS UART1_TransferStatusGet (void );
+
+/**
+ @Summary
+ Returns the character in the read sequence at the offset provided, without
+ extracting it
+
+ @Description
+ This routine returns the character in the read sequence at the offset provided,
+ without extracting it
+
+ @Param
+ None.
+
+ @Example
+ <code>
+ const uint8_t readBuffer[5];
+ unsigned int data, numBytes = 0;
+ unsigned int readbufferLen = sizeof(readBuffer);
+ UART1_Initializer();
+
+ while(numBytes < readbufferLen)
+ {
+ UART1_TasksReceive ( );
+ //Check for data at a particular place in the buffer
+ data = UART1_Peek(3);
+ if(data == 5)
+ {
+ //discard all other data if byte that is wanted is received.
+ //continue other operation
+ numBytes += UART1_ReadBuffer ( readBuffer + numBytes , readbufferLen ) ;
+ }
+ else
+ {
+ break;
+ }
+ }
+ </code>
+
+*/
+
+uint8_t UART1_Peek(uint16_t offset);
+
+/**
+ @Summary
+ Returns the size of the receive buffer
+
+ @Description
+ This routine returns the size of the receive buffer.
+
+ @Param
+ None.
+
+ @Returns
+ Size of receive buffer.
+
+ @Example
+ <code>
+ const uint8_t readBuffer[5];
+ unsigned int size, numBytes = 0;
+ unsigned int readbufferLen = sizeof(readBuffer);
+ UART1__Initializer();
+
+ while(size < readbufferLen)
+ {
+ UART1_TasksReceive ( );
+ size = UART1_ReceiveBufferSizeGet();
+ }
+ numBytes = UART1_ReadBuffer ( readBuffer , readbufferLen ) ;
+ </code>
+
+*/
+
+unsigned int UART1_ReceiveBufferSizeGet(void);
+
+/**
+ @Summary
+ Returns the size of the transmit buffer
+
+ @Description
+ This routine returns the size of the transmit buffer.
+
+ @Param
+ None.
+
+ @Returns
+ Size of transmit buffer.
+
+ @Example
+ Refer to UART1_Initializer(); for example.
+*/
+
+unsigned int UART1_TransmitBufferSizeGet(void);
+
+/**
+ @Summary
+ Returns the status of the receive buffer
+
+ @Description
+ This routine returns if the receive buffer is empty or not.
+
+ @Param
+ None.
+
+ @Returns
+ True if the receive buffer is empty
+ False if the receive buffer is not empty
+
+ @Example
+ <code>
+ char myBuffer[MY_BUFFER_SIZE];
+ unsigned int numBytes;
+ UART1_TRANSFER_STATUS status ;
+
+ // Pre-initialize myBuffer with MY_BUFFER_SIZE bytes of valid data.
+
+ numBytes = 0;
+ while( numBytes < MY_BUFFER_SIZE);
+ {
+ status = UART1_TransferStatusGet ( ) ;
+ if (!UART1_ReceiveBufferIsEmpty())
+ {
+ numBytes += UART1_ReadBuffer( myBuffer + numBytes, MY_BUFFER_SIZE - numBytes ) ;
+ if(numBytes < readbufferLen)
+ {
+ continue;
+ }
+ else
+ {
+ break;
+ }
+ }
+ else
+ {
+ continue;
+ }
+
+ // Do something else...
+ }
+ </code>
+
+*/
+
+bool UART1_ReceiveBufferIsEmpty (void);
+
+/**
+ @Summary
+ Returns the status of the transmit buffer
+
+ @Description
+ This routine returns if the transmit buffer is full or not.
+
+ @Param
+ None.
+
+ @Returns
+ True if the transmit buffer is full
+ False if the transmit buffer is not full
+
+ @Example
+ Refer to UART1_Initializer() for example.
+
+*/
+
+bool UART1_TransmitBufferIsFull (void);
+
+/**
+ @Summary
+ Returns the transmitter and receiver status
+
+ @Description
+ This returns the transmitter and receiver status. The returned status may
+ contain a value with more than one of the bits
+ specified in the UART1_STATUS enumeration set.
+ The caller should perform an "AND" with the bit of interest and verify if the
+ result is non-zero (as shown in the example) to verify the desired status
+ bit.
+
+ @Preconditions
+ UART1_Initializer function should have been called
+ before calling this function
+
+ @Param
+ None.
+
+ @Returns
+ A UART1_STATUS value describing the current status
+ of the transfer.
+
+ @Example
+ <code>
+ while(!(UART1_StatusGet & UART1_TX_COMPLETE ))
+ {
+ // Wait for the tranmission to complete
+ }
+ </code>
+*/
+
+UART1_STATUS UART1_StatusGet (void );
+
+#ifdef __cplusplus // Provide C++ Compatibility
+
+ }
+
+#endif
+
+#endif // _UART1_H
+
+/*
+ End of File
+*/
+