diff --git a/source/lib/hal_mcu/CMakeLists.txt b/source/lib/hal_mcu/CMakeLists.txt
index b93e14c24af30ec462678cdc56560351767cf1e6..e450b2630d7aa5cd54b196e85471ff75fbe2a7b5 100644
--- a/source/lib/hal_mcu/CMakeLists.txt
+++ b/source/lib/hal_mcu/CMakeLists.txt
@@ -8,5 +8,6 @@ add_library(
   hal_f2_timerA0.c
   hal_f2_timerB0.c
   hal_f5_timerB0.c
+  hal_fr5_timer.c
   hal_mcu.c
   )
diff --git a/source/lib/hal_mcu/hal_fr5_timer.c b/source/lib/hal_mcu/hal_fr5_timer.c
new file mode 100644
index 0000000000000000000000000000000000000000..652f7bea1a1d4e02af71203efa83352f82cf5f68
--- /dev/null
+++ b/source/lib/hal_mcu/hal_fr5_timer.c
@@ -0,0 +1,336 @@
+/******************************************************************************
+ *  Filename: hal_f5_timerB0.c
+ *
+ *  Description: Timer abstration layer api
+ *
+ *  Copyright (C) 2013 Texas Instruments Incorporated - http://www.ti.com/
+ *
+ *
+ *  Redistribution and use in source and binary forms, with or without
+ *  modification, are permitted provided that the following conditions
+ *  are met:
+ *
+ *    Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *
+ *    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.
+ *
+ *    Neither the name of Texas Instruments Incorporated 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
+ *  OWNER 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.
+ *
+ *******************************************************************************/
+
+#if defined (__MSP430FR5994__)
+#include "msp430.h"
+#include "hal_timer.h"
+
+unsigned char volatile timer_event;
+unsigned long volatile time_counter = 0;
+
+/******************************************************************************
+ * @fn         hal_timer_init
+ *
+ * @brief      Start packet timer using Timer using ACLK as reference
+ *
+ *
+ * input parameters
+ *
+ * @param       unsigned int master_count - master packet timer value
+ *
+ * output parameters
+ *
+ * @return      void
+ *
+ */
+
+void hal_timer_init(unsigned int master_count) {
+
+  // Start Timer 0 using the ACLK as a source (this enables the use of
+  // various low power modes). Timer 0 will be used to keep RF burst time
+  TBCCR0  = master_count - 1;              // Seting for MASTER SCHEDULE
+  TBCCR1  = 0;                             // will be used for burst alignnment
+  TBCCR2  = 0;                             // will be used for expiration counter
+  TBCTL   = TBSSEL_1 + MC_1 + TBCLR + ID_0;// ACLK, Up to CCR0, clear TB0R, div/1
+
+  return;
+}
+
+
+/******************************************************************************
+ * @fn         hal_timer_adjust
+ *
+ * @brief      Align packet timer by modifying the main count value
+ *
+ *
+ * input parameters
+ *
+ * @param       unsigned int adjust - modify the timer count value
+ *
+ * output parameters
+ *
+ * @return      void
+ *
+ */
+void hal_timer_adjust(unsigned int adjust) {
+
+  TB0R = adjust;
+
+  return;
+}
+
+/******************************************************************************
+ * @fn         hal_timer_get
+ *
+ * @brief      Get the current timer count value
+ *
+ *
+ * input parameters
+ *
+ * @param       void
+ *
+ * output parameters
+ *
+ * @return      unsigned int timer count value
+ *
+ */
+unsigned int hal_timer_get(void) {
+
+	return(TB0R);
+}
+
+
+/******************************************************************************
+ * @fn         hal_timer_get_time
+ *
+ * @brief      Calculate the time in seconds and milliseconds after last reset
+ *
+ *
+ * input parameters
+ *
+ * @param       unsigned long *sec - pointer to seconds counter value
+ *              unsigned long *ms  - pointer to millisecond count value
+ *
+ * output parameters
+ *
+ * @return      unsigned int timer count value
+ *
+ */
+unsigned int hal_timer_get_time(unsigned long *sec, unsigned long *ms) {
+
+	unsigned int ms_uint;
+	unsigned long ms_long;
+
+	/* grap the time counter values from the global value */
+	*sec = time_counter;
+
+	/* grap the time counter value (1/32768) second resolution */
+	ms_uint = TB0R;
+
+	/* convert information to milliseconds */
+	ms_long = (unsigned long)ms_uint * 1000;
+	ms_long = ms_long>>15;
+	*ms = ms_long;
+
+	/* return count value */
+	return(ms_uint);
+}
+
+/******************************************************************************
+ * @fn         hal_timer_stop
+ *
+ * @brief      Stop the timer
+ *
+ *
+ * input parameters
+ *
+ * @param       void
+ *
+ * output parameters
+ *
+ * @return      void
+ *
+ */
+
+void hal_timer_stop(void) {
+
+  /* clear timer configuration register, stopping the timer */
+  TBCTL = 0;
+
+  return;
+}
+
+/******************************************************************************
+ * @fn         hal_timer_expire
+ *
+ * @brief      wait until the timer master count expires (for packet alignment)
+ *
+ *
+ * input parameters
+ *
+ * @param       void
+ *
+ * output parameters
+ *
+ * @return      void
+ *
+ */
+void hal_timer_expire(void) {
+
+  /* enable timer interrupt */
+  TBCCTL1 = CCIE;
+
+  /* enter low power mode and wait */
+  _BIS_SR(LPM0_bits + GIE);
+
+  /* disable interrupt again */
+  TBCCTL1 = 0;
+
+  return;
+}
+
+/******************************************************************************
+ * @fn         hal_timer_wait
+ *
+ * @brief      wait an asigned amount of time or until a GPIO event (packet)
+ *
+ *
+ * input parameters
+ *
+ * @param       unsigned int time  - maximum time to wait
+ *
+ * output parameters
+ *
+ * @return      unsigned int time - actual time waited
+ *
+ */
+unsigned int hal_timer_wait(unsigned int time) {
+  unsigned int wait_count, TBR_init;
+
+  TBR_init = TB0R;   // store the current value of the timer register
+  wait_count = TBR_init + time;
+
+  // if the requested wait time exceeds the TBCCR0 (max value) then make a loop
+  while(wait_count > TBCCR0) {
+
+	  // configure the timeout for 1 less than the master clock
+	  TBCCR2  = TBCCR0-1;
+
+	  // calculate the remaining wait time remaining
+	  wait_count = wait_count - (TBCCR2 - TBR_init);
+
+	  // do not count the initial timer values more that once, zero it out
+	  timer_event = 0;
+	  TBR_init = 0;
+
+	  // enable interupts and wait for timer (or CC1x GDO ISR)
+	  TBCCTL2 = CCIE;                       // interrupt enabled
+	  _BIS_SR(LPM0_bits + GIE);             // Enter LPM0
+
+      // check to see if the timer woke us up or not
+	  if (timer_event == 0)
+		  // it did not, return imidiately and note time actual delay
+		  return (time - (wait_count - TB0R));
+  }
+
+  // in the case of loop, this executes the remaining wait, in the case of no
+  // loop this is the only wait that gets executed
+
+  /* define maximum timeout by using timer counter 2 */
+  TBCCR2  = wait_count;
+
+  /* enable interrupt */
+  TBCCTL2 = CCIE;
+
+  /* enter low power mode and wait for event (timer or radio) */
+  _BIS_SR(LPM0_bits + GIE);
+
+  /* disable interupts on CCR2 */
+  TBCCTL2 = 0;
+
+  /* return the time spend in sleep */
+  return (time - (wait_count-TB0R));
+}
+
+/******************************************************************************
+ * @fn         TIMERB0_ISR
+ *
+ * @brief      Timer interrupt service routine
+ *
+ *
+ * input parameters
+ *
+ * @param       void
+ *
+ * output parameters
+ *
+ * @return      void
+ *
+ */
+// Timer B0 interrupt service routine
+#pragma vector=TIMERB0_VECTOR
+__interrupt void TIMERB0_ISR (void) {
+   //_BIC_SR_IRQ(LPM3_bits);                       // Clear LPM3 bits from 0(SR)
+}
+
+/******************************************************************************
+ * @fn         TIMERB0_ISR
+ *
+ * @brief      Timer interrupt service routine
+ *
+ *
+ * input parameters
+ *
+ * @param       void
+ *
+ * output parameters
+ *
+ * @return      void
+ *
+ */
+#pragma vector=TIMERB1_VECTOR
+__interrupt void TIMERB1_ISR(void) {
+
+	/* Any access, read or write, of the TBIV register automatically
+	 * resets the highest "pending" interrupt flag. */
+
+	switch( __even_in_range(TBIV,14) ) {
+    case  TB0IV_NONE: break;               // No interrupt
+    case  TB0IV_TBCCR1:                    // Used to wake up radio from sleep
+      timer_event = TB0IV_TBCCR1;
+      _BIC_SR_IRQ(LPM3_bits);              // Clear LPM3 bits from 0(SR)
+      break;
+    case  TB0IV_TBCCR2:                    // Use as secondary timer function
+       timer_event = TB0IV_TBCCR2;
+      _BIC_SR_IRQ(LPM3_bits);              // Clear LPM3 bits from 0(SR)
+      break;
+    case  TB0IV_TBCCR3:                    // CCR3 not used
+    	break;
+    case  TB0IV_TBCCR4:                    // CCR4 not used
+    	break;
+    case  TB0IV_TBCCR5:                    // CCR5 not used
+    	break;
+    case  TB0IV_TBCCR6:                    // CCR6 not used
+    	break;
+    case  TB0IV_TBIFG:                     // IFG not used
+    	break;
+    default:
+    	break;
+  }
+}
+
+#endif
diff --git a/source/lib/radio_drv/hal_spi_rf_exp430fr5994.h b/source/lib/radio_drv/hal_spi_rf_exp430fr5994.h
new file mode 100644
index 0000000000000000000000000000000000000000..e270d86f77d07cc7fefee47e835b975ad8e69aea
--- /dev/null
+++ b/source/lib/radio_drv/hal_spi_rf_exp430fr5994.h
@@ -0,0 +1,208 @@
+/******************************************************************************
+*  Filename: hal_spi_rf_exp5529.h
+*
+*  Description: Common header file for spi access to the different tranceiver
+*               radios. Supports CC1101/CC112X radios
+*				 
+*  Copyright (C) 2013 Texas Instruments Incorporated - http://www.ti.com/
+*
+*
+*  Redistribution and use in source and binary forms, with or without
+*  modification, are permitted provided that the following conditions
+*  are met:
+*
+*    Redistributions of source code must retain the above copyright
+*    notice, this list of conditions and the following disclaimer.
+*
+*    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.
+*
+*    Neither the name of Texas Instruments Incorporated 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
+*  OWNER 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.
+*
+*******************************************************************************/
+
+#ifndef HAL_SPI_RF_TRXEB_H
+#define HAL_SPI_RF_TRXEB_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/******************************************************************************
+ * INCLUDES
+ */
+#include <msp430.h>
+#include "hal_types.h"
+#include "hal_defs.h"
+
+/******************************************************************************
+ * DEFINE THE TRANSCEIVER TO USE
+ */
+#define USE_CC1101                     /* use the CC110x transciever commands */
+//#define USE_CC112X                     /* use the CC112x transciever commands */
+#define RF_XTAL 26000                  /* default is 26000 for CC1101 */
+                                       /* 32000 for CC1120 */
+									   /* 40000 for CC1125 */
+//#define ENABLE_RANGE_EXTENDER          /* use external range extender */
+
+/******************************************************************************
+ * CONSTANTS
+ */
+
+/* Transceiver SPI signal */
+#define     RF_PORT_SEL            P3SEL
+#define     RF_PORT_OUT            P3OUT
+#define     RF_PORT_DIR            P3DIR
+#define     RF_PORT_IN             P3IN
+
+#define     RF_MOSI_PIN            BIT0
+#define     RF_MISO_PIN            BIT1
+#define     RF_SCLK_PIN            BIT2
+
+/* Transceiver chip select signal */
+#define     RF_CS_N_PORT_SEL       P2SEL
+#define     RF_CS_N_PORT_DIR       P2DIR
+#define     RF_CS_N_PORT_OUT       P2OUT
+#define     RF_CS_N_PIN            BIT2
+
+/* Transciever optional reset signal */
+#define     RF_RESET_N_PORT_SEL       P2SEL
+#define     RF_RESET_N_PORT_DIR       P2DIR
+#define     RF_RESET_N_PORT_OUT       P2OUT
+#define     RF_RESET_N_PIN            BIT6
+
+/* CC1190 Control signals */
+#define    RF_LNA_EN_PxOUT         P1OUT
+#define    RF_LNA_EN_PxDIR         P1DIR
+#define    RF_LNA_EN_PIN           BIT6
+
+#define    RF_PA_EN_PxOUT          P2OUT
+#define    RF_PA_EN_PxDIR          P2DIR
+#define    RF_PA_EN_PIN            BIT7
+
+/* Transceiver interrupt configuration */
+#define     RF_PORT_VECTOR         PORT2_VECTOR
+#define     RF_GDO_OUT             P2OUT
+#define     RF_GDO_DIR             P2DIR
+#define     RF_GDO_IN              P2IN
+#define     RF_GDO_SEL             P2SEL
+#define     RF_GDO_PxIES           P2IES
+#define     RF_GDO_PxIFG           P2IFG
+#define     RF_GDO_PxIE            P2IE
+#define     RF_GDO_PIN             BIT0
+
+/* Optional button interrupt configuration */
+#define     BUTTON_VECTOR          PORT1_VECTOR
+#define     BUTTON_OUT             P1OUT
+#define     BUTTON_DIR             P1DIR
+#define     BUTTON_IN              P1IN
+#define     BUTTON_SEL             P1SEL
+#define     BUTTON_PxIES           P1IES
+#define     BUTTON_PxIFG           P1IFG
+#define     BUTTON_PxIE            P1IE
+#define     BUTTON_PIN             BIT1
+#define     BUTTON_REN             P1REN
+
+/* Macro to enable LEDs */
+#define     LED1_PxOUT      P1OUT
+#define     LED1_PxDIR      P1DIR
+#define     LED1_PIN        BIT0
+#define     LED2_PxOUT      P4OUT
+#define     LED2_PxDIR      P4DIR
+#define     LED2_PIN        BIT7
+#define     LED3_PxOUT      P1OUT
+#define     LED3_PxDIR      P1DIR
+#define     LED3_PIN        BIT0
+#define     LED4_PxOUT      P4OUT
+#define     LED4_PxDIR      P4DIR
+#define     LED4_PIN        BIT7
+
+#define     HAL_LED1_ON()     LED1_PxOUT |= LED1_PIN
+#define     HAL_LED2_ON()     LED2_PxOUT |= LED2_PIN
+#define     HAL_LED3_ON()     LED3_PxOUT |= LED3_PIN
+#define     HAL_LED4_ON()     LED4_PxOUT |= LED4_PIN
+
+#define     HAL_LED1_OFF()      LED1_PxOUT &= ~LED1_PIN
+#define     HAL_LED2_OFF()      LED2_PxOUT &= ~LED2_PIN
+#define     HAL_LED3_OFF()      LED3_PxOUT &= ~LED3_PIN
+#define     HAL_LED4_OFF()      LED4_PxOUT &= ~LED4_PIN
+
+#define     HAL_LED1_TOGGLE()  LED1_PxOUT ^= LED1_PIN
+#define     HAL_LED2_TOGGLE()  LED2_PxOUT ^= LED2_PIN
+#define     HAL_LED3_TOGGLE()  LED3_PxOUT ^= LED3_PIN
+#define     HAL_LED4_TOGGLE()  LED4_PxOUT ^= LED4_PIN
+
+#define     RADIO_BURST_ACCESS      0x40
+#define     RADIO_SINGLE_ACCESS     0x00
+#define     RADIO_READ_ACCESS       0x80
+#define     RADIO_WRITE_ACCESS      0x00
+
+/* Bit fields in the chip status byte */
+#define STATUS_CHIP_RDYn_BM              0x80
+#define STATUS_STATE_BM                  0x70
+#define STATUS_FIFO_BYTES_AVAILABLE_BM   0x0F
+
+/******************************************************************************
+ *  Macros for Tranceivers(TRX)
+ */
+
+#define RF_SPI_BEGIN()              st( RF_CS_N_PORT_OUT &= ~RF_CS_N_PIN; NOP(); )
+#define RF_SPI_TX(x)                st( UCB0IFG &= ~UCRXIFG; UCB0TXBUF= (x); )
+#define RF_SPI_WAIT_DONE()          st( while(!(UCB0IFG & UCRXIFG)); )
+#define RF_SPI_WAIT_TX_DONE()       st( while(!(UCB0IFG & UCTXIFG)); )
+#define RF_SPI_RX()                 UCB0RXBUF
+#define RF_SPI_WAIT_MISO_LOW(x)     st( uint8 count = 200; \
+                                           while(RF_PORT_IN & RF_SPI_MISO_PIN) \
+                                           { \
+                                              __delay_cycles(5000); \
+                                              count--; \
+                                              if (count == 0) break; \
+                                           } \
+                                           if(count>0) (x) = 1; \
+                                           else (x) = 0; )
+
+#define RF_SPI_END()                st( NOP(); RF_CS_N_PORT_OUT |= RF_CS_N_PIN; )
+
+/******************************************************************************
+ * TYPEDEFS
+ */
+
+typedef struct
+{
+  uint16  addr;
+  uint8   data;
+}registerSetting_t;
+
+typedef uint8 rfStatus_t;
+
+/******************************************************************************
+ * PROTOTYPES
+ */
+
+void trxRfSpiInterfaceInit(uint8 prescalerValue);
+rfStatus_t trx8BitRegAccess(uint8 accessType, uint8 addrByte, uint8 *pData, uint16 len);
+rfStatus_t trxSpiCmdStrobe(uint8 cmd);
+
+/* CC112X specific prototype function */
+rfStatus_t trx16BitRegAccess(uint8 accessType, uint8 extAddr, uint8 regAddr, uint8 *pData, uint8 len);
+
+#ifdef  __cplusplus
+}
+#endif
+
+#endif