Mahmood ul Hassan
Created February 2, 2020 © MIT

tinyMonster UAV - Autonomous Fire and Safe to Go Burnt Area

Detection of Safe to go/navigate in an area for Firefighters and rescue worker with fire aftermath.

ExpertFull instructions providedOver 2 days66

Things used in this project

Hardware components

Rapid IoT Prototyping Kit
NXP Rapid IoT Prototyping Kit
I was using to interface all the sensors and module but in the last week just before the final demo and testing it then suddenly stop working and then I have to shift everything on a different hardware.
×1
KIT-HGDRONEK66
NXP KIT-HGDRONEK66
×1
Grove - Infrared Temperature Sensor Array (AMG8833)
Seeed Studio Grove - Infrared Temperature Sensor Array (AMG8833)
×1
Gravity: Analog Carbon Monoxide Sensor (MQ7) For Arduino
DFRobot Gravity: Analog Carbon Monoxide Sensor (MQ7) For Arduino
×1
Gravity: Analog CO/Combustible Gas Sensor (MQ9) For Arduino
DFRobot Gravity: Analog CO/Combustible Gas Sensor (MQ9) For Arduino
×1
SparkFun Transceiver Breakout - nRF24L01+ (RP-SMA)
SparkFun Transceiver Breakout - nRF24L01+ (RP-SMA)
×2
mlx90614
×1
Sipeed Longan Nano - RISC-V GD32VF103CBT6 Development Board
Seeed Studio Sipeed Longan Nano - RISC-V GD32VF103CBT6 Development Board
×1
RSL10-SENSE-GEVK
onsemi RSL10-SENSE-GEVK
×1
STMicroelectronics stm32f746 discovery
×1
Seeed Studio Lipo Rider Plus
×1
3S 5200mAh lipo battery
×1
Li-Ion Battery 1000mAh
Li-Ion Battery 1000mAh
×3
Solo Propellers
3DR Solo Propellers
×1
DJI Phantom-3 Propeller Gaurd
×1
1W Led
×4
High Brightness LED, Red
High Brightness LED, Red
×4
High Brightness LED, Green
×1
DC to Dc LED driver
×1
USB-A to Micro-USB Cable
USB-A to Micro-USB Cable
×5
Neon Color Cable Tie Assortment Kit, 400 Pcs
Neon Color Cable Tie Assortment Kit, 400 Pcs
×1
Self locking Nut M3
×50
Screw, Hex Locking
Screw, Hex Locking
×50
USB Li Ion Battery Charger
Adafruit USB Li Ion Battery Charger
×1
Double sided foam tape
×1
Arduino MKRWAN 1300
×2
RDDRONE-FMUK66
NXP RDDRONE-FMUK66
×1

Software apps and online services

NXP MCUXpresso IDE
MDK-Essential Edition
Arm MDK-Essential Edition
PlatformIO IDE
PlatformIO IDE
STM32CUBEPROG
STMicroelectronics STM32CUBEPROG
TouchGFX Designer
MAVSDK
PX4 MAVSDK
QGroundControl
PX4 QGroundControl
MAVLink
PX4 MAVLink
onsemi ON Semiconductor IDE
mapbox.com

Hand tools and fabrication machines

Multitool, Screwdriver
Multitool, Screwdriver
Plier, Long Nose
Plier, Long Nose
Plier, Cutting
Plier, Cutting
Set Screw, Pack of 10
Set Screw, Pack of 10
Cable Cutter, 12.7mm
Cable Cutter, 12.7mm

Story

Read more

Schematics

NXP hovergames mapper

Code

Sipeed Longan Nano - MLX90614.h

C Header File
Modified the Adafruit MLX90614 Arduino Library from Arduino C++ to embedded C.
CAUTION ! Sipeed Longan Nano needed 1 bit left shifted i2c address. Also external pull-up resistor required otherwise this sensor will not work. And sensor will not work beyond standard I2C data rate of 100kbps
/*!
    \file  MLX90614.h
    \brief the header file of MLX90614
    
    \version 2019-06-05, V1.0.0, demo for GD32VF103
*/

#ifndef MLX90614_H
#define MLX90614_H

#include "gd32vf103.h"

#define MLX90614_I2CPORT I2C1
#define MLX90614_I2CADDR 0x5A<<1

// RAM
#define MLX90614_RAWIR1 0x04
#define MLX90614_RAWIR2 0x05
#define MLX90614_TA 0x06
#define MLX90614_TOBJ1 0x07
#define MLX90614_TOBJ2 0x08
// EEPROM
#define MLX90614_TOMAX 0x20
#define MLX90614_TOMIN 0x21
#define MLX90614_PWMCTRL 0x22
#define MLX90614_TARANGE 0x23
#define MLX90614_EMISS 0x24
#define MLX90614_CONFIG 0x25
#define MLX90614_ADDR 0x0E
#define MLX90614_ID1 0x3C
#define MLX90614_ID2 0x3D
#define MLX90614_ID3 0x3E
#define MLX90614_ID4 0x3F


/* initialize IR sensor */
uint8_t ir_init();

double ir_readObjectTempC(void);
double ir_readAmbientTempC(void);
double ir_readObjectTempF(void);
double ir_readAmbientTempF(void);

#endif  /* MLX90614_H */

Sipeed Longan Nano - MLX90614.c

C/C++
Modified the Adafruit MLX90614 Arduino Library from Arduino C++ to embedded C.
CAUTION ! Sipeed Longan Nano needed 1 bit left shifted i2c address. Also external pull-up resistor required otherwise this sensor will not work. And sensor will not work beyond standard I2C data rate of 100kbps
/*!
    \file  MLX90614.c
    \brief the read and write function file
    
    \version 2019-06-05, V1.0.0, demo for GD32VF103
*/

#include "ir_sensor/MLX90614.h"
#include "ir_sensor/i2c.h"
#include <stdint.h>
#include <stdio.h>


float ir_readTemp(uint8_t reg);
uint16_t ir_read16(uint8_t addr);

/*!
    \brief      initialize peripherals used by the I2C IR Sensor
    \param[in]  none
    \param[out] none
    \retval     1
*/
uint8_t ir_init(void) {
  i2c_config(MLX90614_I2CPORT);
  return 1;
}

double ir_readObjectTempF(void) {
  return (ir_readTemp(MLX90614_TOBJ1) * 9.0 / 5.0) + 32.0;
}

double ir_readAmbientTempF(void) {
  return (ir_readTemp(MLX90614_TA) * 9.0 / 5.0) + 32.0;
}

double ir_readObjectTempC(void) {
  return ir_readTemp(MLX90614_TOBJ1);
}

double ir_readAmbientTempC(void) {
  return ir_readTemp(MLX90614_TA);
}

float ir_readTemp(uint8_t reg) {
  float temp;
  
  temp = ir_read16(reg);
  temp *= .02;
  temp  -= 273.15;
  return temp;
}

/*!
    \brief      I2C read 16bit function
    \param[in]  Address
    \param[out] none
    \retval     16bit read Value 
*/
uint16_t ir_read16(uint8_t addr) {
  uint16_t ret=0;
  uint8_t p_buffer[2];
  i2c_read(MLX90614_I2CPORT, MLX90614_I2CADDR, addr, p_buffer, 2, 1000);
  ret=p_buffer[0]|(p_buffer[1]<<8);
  return ret;
}

Sipeed Longan Nano - AMG88xx.h

C Header File
Modified the Adafruit AMG8833 Arduino Library from Arduino C++ to embedded C.
CAUTION ! Sipeed Longan Nano needed 1 bit left shifted i2c address. Generally these module will have external pull resistors otherwise external pull-up resistor required to work with Sipeed Longan Nano.

And sensor is tested and used at I2C data rate of 400kbps.
#ifndef AMG_88XX_H
#define AMG_88XX_H

#include <stdint.h>

/*=========================================================================
    I2C ADDRESS/BITS
    -----------------------------------------------------------------------*/
    #define AMG88xx_ADDRESS                (0x69<<1)

	#define AMG88xx_PORT 					I2C0
/*=========================================================================*/

/*=========================================================================
    REGISTERS
    -----------------------------------------------------------------------*/
enum
    {
    AMG88xx_PCTL = 0x00,
		AMG88xx_RST = 0x01,
		AMG88xx_FPSC = 0x02,
		AMG88xx_INTC = 0x03,
		AMG88xx_STAT = 0x04,
		AMG88xx_SCLR = 0x05,
		//0x06 reserved
		AMG88xx_AVE = 0x07,
		AMG88xx_INTHL = 0x08,
		AMG88xx_INTHH = 0x09,
		AMG88xx_INTLL = 0x0A,
		AMG88xx_INTLH = 0x0B,
		AMG88xx_IHYSL = 0x0C,
		AMG88xx_IHYSH = 0x0D,
		AMG88xx_TTHL = 0x0E,
		AMG88xx_TTHH = 0x0F,
		AMG88xx_INT_OFFSET = 0x010,
		AMG88xx_PIXEL_OFFSET = 0x80
    };
	
enum power_modes{
		AMG88xx_NORMAL_MODE = 0x00,
		AMG88xx_SLEEP_MODE = 0x01,
		AMG88xx_STAND_BY_60 = 0x20,
		AMG88xx_STAND_BY_10 = 0x21
	};
	
enum sw_resets {
		AMG88xx_FLAG_RESET = 0x30,
		AMG88xx_INITIAL_RESET = 0x3F
	};
	
enum frame_rates {
		AMG88xx_FPS_10 = 0x00,
		AMG88xx_FPS_1 = 0x01
	};
	
enum int_enables{
		AMG88xx_INT_DISABLED = 0x00,
		AMG88xx_INT_ENABLED = 0x01
	};
	
enum int_modes {
		AMG88xx_DIFFERENCE = 0x00,
		AMG88xx_ABSOLUTE_VALUE = 0x01
	};
	
/*=========================================================================*/

#define AMG88xx_PIXEL_ARRAY_SIZE 64
#define AMG88xx_PIXEL_TEMP_CONVERSION .25f
#define AMG88xx_THERMISTOR_CONVERSION .0625f

/**************************************************************************/
/*! 
    @brief  Class that stores state and functions for interacting with AMG88xx IR sensor chips
*/
/**************************************************************************/

int amg88xxInit(void);
void readPixels(float *buf, uint8_t size/* = AMG88xx_PIXEL_ARRAY_SIZE */);
void readPixelsRaw(int16_t* buf);
float readThermistor(void);
void setMovingAverageMode(int mode);
void enableInterrupt(void);
void disableInterrupt(void);
void setInterruptMode(uint8_t mode);
void getInterrupt(uint8_t *buf, uint8_t /*size = 8 */);
void clearInterrupt(void);

//this will automatically set hysteresis to 95% of the high value
void setInterruptLevels(float high, float low);

//this will manually set hysteresis
void setInterruptLevelsHist(float high, float low, float hysteresis);

#endif

Sipeed Longan Nano - AMG88xx.c

C/C++
Modified the Adafruit AMG8833 Arduino Library from Arduino C++ to embedded C.
CAUTION ! Sipeed Longan Nano needed 1 bit left shifted i2c address. Generally these module will have external pull resistors otherwise external pull-up resistor required to work with Sipeed Longan Nano.

And sensor is tested and used at I2C data rate of 400kbps.
#include "ir_sensor/AMG88xx.h"
#include "ir_sensor/i2c.h"
#include <stdint.h>
#include <stdio.h>

#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))

		 // The power control register
struct pctl {
            // 0x00 = Normal Mode
			// 0x01 = Sleep Mode
			// 0x20 = Stand-by mode (60 sec intermittence)
			// 0x21 = Stand-by mode (10 sec intermittence)
         uint8_t PCTL : 8;
};


//reset register
struct rst {
			//0x30 = flag reset (all clear status reg 0x04, interrupt flag and interrupt table)
			//0x3F = initial reset (brings flag reset and returns to initial setting)
			uint8_t RST : 8;
};

//frame rate register
struct fpsc {
			//0 = 10FPS
			//1 = 1FPS
			uint8_t FPS : 1;

};


		//interrupt control register
struct intc {

			// 0 = INT output reactive (Hi-Z)
			// 1 = INT output active
			uint8_t INTEN : 1;

			// 0 = Difference interrupt mode
			// 1 = absolute value interrupt mode
			uint8_t INTMOD : 1;

};

		//status register
struct stat {
			uint8_t unused : 1;
			//interrupt outbreak (val of interrupt table reg)
			uint8_t INTF : 1;

			//temperature output overflow (val of temperature reg)
			uint8_t OVF_IRS : 1;

			//thermistor temperature output overflow (value of thermistor)
			uint8_t OVF_THS : 1;


};

		//status clear register
		//write to clear overflow flag and interrupt flag
		//after writing automatically turns to 0x00
struct sclr {
			uint8_t unused : 1;
			//interrupt flag clear
			uint8_t INTCLR : 1;
			//temp output overflow flag clear
			uint8_t OVS_CLR : 1;
			//thermistor temp output overflow flag clear
			uint8_t OVT_CLR : 1;
};

		//average register
		//for setting moving average output mode
struct ave {
			uint8_t unused : 5;
			//1 = twice moving average mode
			uint8_t MAMOD : 1;
};

		//interrupt level registers
		//for setting upper / lower limit hysteresis on interrupt level

		//interrupt level upper limit setting. Interrupt output
		// and interrupt pixel table are set when value exceeds set value
struct inthl {
			uint8_t INT_LVL_H : 8;
};

struct inthh {
			uint8_t INT_LVL_H : 4;
};

		//interrupt level lower limit. Interrupt output
		//and interrupt pixel table are set when value is lower than set value
struct intll {
			uint8_t INT_LVL_L : 8;
};

struct intlh {
			uint8_t INT_LVL_L : 4;
};

		//setting of interrupt hysteresis level when interrupt is generated.
		//should not be higher than interrupt level
struct ihysl {
			uint8_t INT_HYS : 8;
};

struct ihysh {
			uint8_t INT_HYS : 4;
};

		//thermistor register
		//SIGNED MAGNITUDE FORMAT
struct tthl {
			uint8_t TEMP : 8;
};

struct tthh {
			uint8_t TEMP : 3;
			uint8_t SIGN : 1;
};

		//temperature registers 0x80 - 0xFF
		/*
		//read to indicate temperature data per 1 pixel
		//SIGNED MAGNITUDE FORMAT
		struct t01l {
			uint8_t TEMP : 8;

			uint8_t get(){
				return TEMP;
			}
		};
		struct t01l _t01l;

		struct t01h {
			uint8_t TEMP : 3;
			uint8_t SIGN : 1;

			uint8_t get(){
				return ( (SIGN << 3) | TEMP) & 0xF;
			}
		};
		struct t01h _t01h;
		*/

struct pctl _pctl;
struct rst _rst;
struct fpsc _fpsc;
struct intc _intc;
struct stat _stat;
struct sclr _sclr;
struct ave _ave;
struct inthl _inthl;
struct inthh _inthh;
struct intll _intll;
struct intlh _intlh;
struct ihysl _ihysl;
struct ihysh _ihysh;
struct tthl _tthl;
struct tthh _tthh;

static uint8_t getPCTL(void){ return _pctl.PCTL; }
static uint8_t getRST(void){	return _rst.RST; }
static uint8_t getFPSC(void){ return _fpsc.FPS & 0x01; }
static uint8_t getINTC(void){ return (_intc.INTMOD << 1 | _intc.INTEN) & 0x03; }
static uint8_t getSTAT(void){ return ( (_stat.OVF_THS << 3) | (_stat.OVF_IRS << 2) | (_stat.INTF << 1) ) & 0x07; }
static uint8_t getSCLR(void){ return ((_sclr.OVT_CLR << 3) | (_sclr.OVS_CLR << 2) | (_sclr.INTCLR << 1)) & 0x07; }
static uint8_t getAVE(void){ return (_ave.MAMOD << 5); }
static uint8_t getINTHL(void){ return _inthl.INT_LVL_H; }
static uint8_t getINTHH(void){ return _inthh.INT_LVL_H; }
static uint8_t getINTLL(void){ return _intll.INT_LVL_L; }
static uint8_t getINTLH(void){ return (_intlh.INT_LVL_L & 0xF); }
static uint8_t getIHYSL(void){ return _ihysl.INT_HYS; }
static uint8_t getIHYSH(void){ return (_ihysh.INT_HYS & 0xF); }
static uint8_t getTTHL(void){ return _tthl.TEMP; }
static uint8_t getTTHH(void){ return ( (_tthh.SIGN << 3) | _tthh.TEMP) & 0xF; }
static uint8_t min(uint8_t a, uint8_t b){ return a < b ? a : b; }


static void write8(uint8_t reg, uint8_t value);
static uint8_t read8(uint8_t reg);

static void read(uint8_t read_address, uint8_t* p_buffer, uint8_t number_of_byte);
static void write(uint8_t write_address, uint8_t* p_buffer, uint8_t number_of_byte);

static float signedMag12ToFloat(uint16_t val);


/**************************************************************************/
/*! 
    @brief  Setups the I2C interface and hardware
    @param  addr Optional I2C address the sensor can be found on. Default is 0x69
    @returns True if device is set up, false on any failure
*/
/**************************************************************************/
int amg88xxInit(void)
{
	i2c_config(AMG88xx_PORT);
	//enter normal mode
	_pctl.PCTL = AMG88xx_NORMAL_MODE;
	write8(AMG88xx_PCTL, getPCTL());
	
	//software reset
	_rst.RST = AMG88xx_INITIAL_RESET;
	write8(AMG88xx_RST, getRST());
	
	//disable interrupts by default
	disableInterrupt();
	
	//set to 10 FPS
	_fpsc.FPS = AMG88xx_FPS_10;
	write8(AMG88xx_FPSC, getFPSC());

	delay_1ms(100);

	return 0;
}

/**************************************************************************/
/*! 
    @brief  Set the moving average mode.
    @param  mode if True is passed, output will be twice the moving average
*/
/**************************************************************************/
void setMovingAverageMode(int mode)
{
	_ave.MAMOD = mode;
	write8(AMG88xx_AVE, getAVE());
}

/**************************************************************************/
/*! 
    @brief  Set the interrupt levels. The hysteresis value defaults to .95 * high
    @param  high the value above which an interrupt will be triggered
    @param  low the value below which an interrupt will be triggered
*/
/**************************************************************************/
void setInterruptLevels(float high, float low)
{
	setInterruptLevelsHist(high, low, high * .95f);
}

/**************************************************************************/
/*! 
    @brief  Set the interrupt levels
    @param  high the value above which an interrupt will be triggered
    @param  low the value below which an interrupt will be triggered
    @param hysteresis the hysteresis value for interrupt detection
*/
/**************************************************************************/
void setInterruptLevelsHist(float high, float low, float hysteresis)
{
	int highConv = high / AMG88xx_PIXEL_TEMP_CONVERSION;
	highConv = constrain(highConv, -4095, 4095);
	_inthl.INT_LVL_H = highConv & 0xFF;
	_inthh.INT_LVL_H = (highConv & 0xF) >> 4;
	write8(AMG88xx_INTHL, getINTHL());
	write8(AMG88xx_INTHH, getINTHH());
	
	int lowConv = low / AMG88xx_PIXEL_TEMP_CONVERSION;
	lowConv = constrain(lowConv, -4095, 4095);
	_intll.INT_LVL_L = lowConv & 0xFF;
	_intlh.INT_LVL_L = (lowConv & 0xF) >> 4;
	write8(AMG88xx_INTLL, getINTLL());
	write8(AMG88xx_INTLH, getINTLH());
	
	int hysConv = hysteresis / AMG88xx_PIXEL_TEMP_CONVERSION;
	hysConv = constrain(hysConv, -4095, 4095);
	_ihysl.INT_HYS = hysConv & 0xFF;
	_ihysh.INT_HYS = (hysConv & 0xF) >> 4;
	write8(AMG88xx_IHYSL, getIHYSL());
	write8(AMG88xx_IHYSH, getIHYSH());
}

/**************************************************************************/
/*! 
    @brief  enable the interrupt pin on the device.
*/
/**************************************************************************/
void enableInterrupt()
{
	_intc.INTEN = 1;
	write8(AMG88xx_INTC, getINTC());
}

/**************************************************************************/
/*! 
    @brief  disable the interrupt pin on the device
*/
/**************************************************************************/
void disableInterrupt()
{
	_intc.INTEN = 0;
	write8(AMG88xx_INTC, getINTC());
}

/**************************************************************************/
/*! 
    @brief  Set the interrupt to either absolute value or difference mode
    @param  mode passing AMG88xx_DIFFERENCE sets the device to difference mode, AMG88xx_ABSOLUTE_VALUE sets to absolute value mode.
*/
/**************************************************************************/
void setInterruptMode(uint8_t mode)
{
	_intc.INTMOD = mode;
	write8(AMG88xx_INTC, getINTC());
}

/**************************************************************************/
/*! 
    @brief  Read the state of the triggered interrupts on the device. The full interrupt register is 8 bytes in length.
    @param  buf the pointer to where the returned data will be stored
    @param  size Optional number of bytes to read. Default is 8 bytes.
    @returns up to 8 bytes of data in buf
*/
/**************************************************************************/
void getInterrupt(uint8_t *buf, uint8_t size)
{
	uint8_t bytesToRead = min(size, (uint8_t)8);
	
	read(AMG88xx_INT_OFFSET, buf, bytesToRead);
}

/**************************************************************************/
/*! 
    @brief  Clear any triggered interrupts
*/
/**************************************************************************/
void clearInterrupt()
{
	_rst.RST = AMG88xx_FLAG_RESET;
	write8(AMG88xx_RST, getRST());
}

/**************************************************************************/
/*! 
    @brief  read the onboard thermistor
    @returns a the floating point temperature in degrees Celsius
*/
/**************************************************************************/
float readThermistor()
{
	uint8_t raw[2];
	read(AMG88xx_TTHL, raw, 2);
	uint16_t recast = ((uint16_t)raw[1] << 8) | ((uint16_t)raw[0]);

	return signedMag12ToFloat(recast) * AMG88xx_THERMISTOR_CONVERSION;
}

/**************************************************************************/
/*! 
    @brief  Read Infrared sensor values
    @param  buf the array to place the pixels in
    @param  size Optionsl number of bytes to read (up to 64). Default is 64 bytes.
    @return up to 64 bytes of pixel data in buf
*/
/**************************************************************************/
void readPixels(float *buf, uint8_t size)
{
	uint16_t recast;
	float converted;
	uint8_t bytesToRead = min((uint8_t)(size << 1), (uint8_t)(AMG88xx_PIXEL_ARRAY_SIZE << 1));
	uint8_t rawArray[bytesToRead];
	read(AMG88xx_PIXEL_OFFSET, rawArray, bytesToRead);
	
	for(int i=0; i<size; i++){
		uint8_t pos = i << 1;
		recast = ((uint16_t)rawArray[pos + 1] << 8) | ((uint16_t)rawArray[pos]);
		
		converted = signedMag12ToFloat(recast) * AMG88xx_PIXEL_TEMP_CONVERSION;
		buf[i] = converted;
	}
}


void readPixelsRaw(int16_t* buf)
{
	read(AMG88xx_PIXEL_OFFSET, (uint8_t*)buf, 128);
}

/**************************************************************************/
/*! 
    @brief  write one byte of data to the specified register
    @param  reg the register to write to
    @param  value the value to write
*/
/**************************************************************************/
static void write8(uint8_t reg, uint8_t value)
{
	write(reg, &value, 1);
}

/**************************************************************************/
/*! 
    @brief  read one byte of data from the specified register
    @param  reg the register to read
    @returns one byte of register data
*/
/**************************************************************************/
static uint8_t read8(uint8_t reg)
{
	uint8_t ret;
	read(reg, &ret, 1);
	
	return ret;
}

static void read(uint8_t read_address, uint8_t* p_buffer, uint8_t number_of_byte)
{  
	i2c_read(AMG88xx_PORT, AMG88xx_ADDRESS, read_address, p_buffer, number_of_byte, 1000);
}

static void write(uint8_t write_address, uint8_t* p_buffer, uint8_t number_of_byte)
{
	i2c_write(AMG88xx_PORT, AMG88xx_ADDRESS, write_address, p_buffer, number_of_byte, 1000);
}

/**************************************************************************/
/*! 
    @brief  convert a 12-bit signed magnitude value to a floating point number
    @param  val the 12-bit signed magnitude value to be converted
    @returns the converted floating point value
*/
/**************************************************************************/
static float signedMag12ToFloat(uint16_t val)
{
	//take first 11 bits as absolute val
	uint16_t absVal = (val & 0x7FF);
	
	return (val & 0x8000) ? 0 - (float)absVal : (float)absVal ;
}

Sipeed Longan Nano - nRF24L01.h

C Header File
nRF24L01+ configuration file. It is taken from Arduino RF24 library. The original Code is available on github: https://github.com/TMRh20
/*
    Copyright (c) 2007 Stefan Engelke <mbox@stefanengelke.de>
	Portions Copyright (C) 2011 Greg Copeland

    Permission is hereby granted, free of charge, to any person
    obtaining a copy of this software and associated documentation
    files (the "Software"), to deal in the Software without
    restriction, including without limitation the rights to use, copy,
    modify, merge, publish, distribute, sublicense, and/or sell copies
    of the Software, and to permit persons to whom the Software is
    furnished to do so, subject to the following conditions:

    The above copyright notice and this permission notice shall be
    included in all copies or substantial portions of the Software.

    THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
    EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
    MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
    NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT
    HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY,
    WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
    OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
    DEALINGS IN THE SOFTWARE.
*/

/*
 * Mbed support added by Akash Vibhute <akash.roboticist@gmail.com>
 * Porting completed on Nov/05/2015
 *
 * Updated 1: Synced with TMRh20's RF24 library on Nov/04/2015 from https://github.com/TMRh20
 * Updated 2: Synced with TMRh20's RF24 library on Apr/18/2015 from https://github.com/TMRh20
 *
 */

/* Memory Map */
#define NRF_CONFIG      0x00
#define EN_AA       0x01
#define EN_RXADDR   0x02
#define SETUP_AW    0x03
#define SETUP_RETR  0x04
#define RF_CH       0x05
#define RF_SETUP    0x06
#define NRF_STATUS  0x07
#define OBSERVE_TX  0x08
#define CD          0x09
#define RX_ADDR_P0  0x0A
#define RX_ADDR_P1  0x0B
#define RX_ADDR_P2  0x0C
#define RX_ADDR_P3  0x0D
#define RX_ADDR_P4  0x0E
#define RX_ADDR_P5  0x0F
#define TX_ADDR     0x10
#define RX_PW_P0    0x11
#define RX_PW_P1    0x12
#define RX_PW_P2    0x13
#define RX_PW_P3    0x14
#define RX_PW_P4    0x15
#define RX_PW_P5    0x16
#define FIFO_STATUS 0x17
#define DYNPD	    0x1C
#define FEATURE	    0x1D

/* Bit Mnemonics */
#define MASK_RX_DR  6
#define MASK_TX_DS  5
#define MASK_MAX_RT 4
#define EN_CRC      3
#define CRCO        2
#define PWR_UP      1
#define PRIM_RX     0
#define ENAA_P5     5
#define ENAA_P4     4
#define ENAA_P3     3
#define ENAA_P2     2
#define ENAA_P1     1
#define ENAA_P0     0
#define ERX_P5      5
#define ERX_P4      4
#define ERX_P3      3
#define ERX_P2      2
#define ERX_P1      1
#define ERX_P0      0
#define AW          0
#define ARD         4
#define ARC         0
#define PLL_LOCK    4
#define RF_DR       3
#define RF_PWR      6
#define RX_DR       6
#define TX_DS       5
#define MAX_RT      4
#define RX_P_NO     1
#define TX_FULL     0
#define PLOS_CNT    4
#define ARC_CNT     0
#define TX_REUSE    6
#define FIFO_FULL   5
#define TX_EMPTY    4
#define RX_FULL     1
#define RX_EMPTY    0
#define DPL_P5	    5
#define DPL_P4	    4
#define DPL_P3	    3
#define DPL_P2	    2
#define DPL_P1	    1
#define DPL_P0	    0
#define EN_DPL	    2
#define EN_ACK_PAY  1
#define EN_DYN_ACK  0

/* Instruction Mnemonics */
#define R_REGISTER    0x00
#define W_REGISTER    0x20
#define REGISTER_MASK 0x1F
#define ACTIVATE      0x50
#define R_RX_PL_WID   0x60
#define R_RX_PAYLOAD  0x61
#define W_TX_PAYLOAD  0xA0
#define W_ACK_PAYLOAD 0xA8
#define FLUSH_TX      0xE1
#define FLUSH_RX      0xE2
#define REUSE_TX_PL   0xE3
#define NOP           0xFF

/* Non-P omissions */
#define LNA_HCURR   0

/* P model memory Map */
#define RPD         0x09
#define W_TX_PAYLOAD_NO_ACK  0xB0

/* P model bit Mnemonics */
#define RF_DR_LOW   5
#define RF_DR_HIGH  3
#define RF_PWR_LOW  1
#define RF_PWR_HIGH 2

Sipeed Longan Nano - nRF24.h

C Header File
nRF24L01+ C library required for basic communication at maximum (2Mbps) rate communication with CRC functionality. Idea is taken from Arduino RF24 library.
#ifndef __nRF24_H__
#define __nRF24_H__

#include "nRF24L01.h"
#include "nRF24_hw.h"

typedef enum { RF24_PA_MIN = 0,RF24_PA_LOW, RF24_PA_HIGH, RF24_PA_MAX, RF24_PA_ERROR } rf24_pa_dbm_e ;
typedef enum { RF24_1MBPS = 0, RF24_2MBPS, RF24_250KBPS } rf24_datarate_e;
typedef enum { RF24_CRC_DISABLED = 0, RF24_CRC_8, RF24_CRC_16 } rf24_crclength_e;

uint8_t nRF24_read_buffer(uint8_t reg, uint8_t* buf, uint8_t len);
uint8_t nRF24_read_register(uint8_t reg);
uint8_t nRF24_write_buffer(uint8_t reg, uint8_t* buf, uint8_t len);
uint8_t nRF24_write_register(uint8_t reg, uint8_t value);
uint8_t nRF24_write_payload(uint8_t * buf, uint8_t data_len, uint8_t writeType);
uint8_t nRF24_read_payload(uint8_t * buf, uint8_t data_len);
uint8_t nRF24_flush_rx(void);
uint8_t nRF24_flush_tx(void);
uint8_t nRF24_get_status(void);
void nRF24_setChannel(uint8_t channel);
uint8_t nRF24_getChannel(void);
void nRF24_setPayloadSize(uint8_t size);
uint8_t nRF24_getPayloadSize(void);
void nRF24_setPALevel(uint8_t level);
uint8_t nRF24_getPALevel(void);
uint8_t nRF24_getARC(void);
bool nRF24_setDataRate(rf24_datarate_e speed);
rf24_datarate_e nRF24_getDataRate(void);
void nRF24_setCRCLength(rf24_crclength_e length);
rf24_crclength_e nRF24_getCRCLength(void);
void nRF24_disableCRC(void);
void nRF24_setRetries(uint8_t delay, uint8_t count);
bool nRF24_testCarrier(void);
bool nRF24_testRPD(void);

void nRF24_openWritingPipe(uint8_t* address);
void nRF24_openWritingPipe_d(uint8_t value);
void nRF24_setAddressWidth(uint8_t a_width);
void nRF24_openReadingPipe(uint8_t child, uint8_t* address);
void nRF24_openReadingPipe_d(uint8_t child, uint8_t address);

void nRF24_startListening(void);
void nRF24_stopListening(void);
void nRF24_closeReadingPipe(uint8_t pipe);

bool nRF24_available(void);
bool nRF24_available_d(uint8_t* pipe_num);

void nRF24_read(uint8_t* buf, uint8_t len);
bool nRF24_write(uint8_t* buf, uint8_t len);
bool nRF24_write_multi(uint8_t* buf, uint8_t len, const bool multicast);
void nRF24_startFastWrite(uint8_t* buf, uint8_t len, bool multicast, bool startTx);

bool nRF24_isChipConnected(void);
void nRF24_powerDown(void);
void nRF24_powerUp(void);
void nRF24_reUseTX(void);
bool nRF24_rxFifoFull(void);

void nRF24_init(void);
uint8_t nRF24_begin(void);

#endif // __RF24_H__

Sipeed Longan Nano - nRF24.c

C/C++
nRF24L01+ C library required for basic communication at maximum (2Mbps) rate communication with CRC functionality. Idea is taken from Arduino RF24 library.
#include "nRF24.h"


#define RF24_SPI_TIMEOUT 1
#define RF24_NOP 0xFF
#define _BV(x) (1<<(x))

#define delay(x)	delay_1ms(x)
#define delayMicroseconds(x)	delay_1us(x)

#define rf24_max(a,b) (a>b?a:b)
#define rf24_min(a,b) (a<b?a:b)

uint8_t payload_size; /**< Fixed size of payloads */
bool dynamic_payloads_enabled; /**< Whether dynamic payloads are enabled. */
bool p_variant; /* False for RF24L01 and true for RF24L01P */
uint8_t pipe0_reading_address[5]; /**< Last address set on pipe 0 for reading. */
uint8_t addr_width; /**< The address width to use - 3,4 or 5 bytes. */

uint8_t spi_rxbuff[32+1] ; //SPI receive buffer (payload max 32 bytes)
uint8_t spi_txbuff[32+1] ; //SPI transmit buffer (payload max 32 bytes + 1 byte for the command)

uint32_t txDelay;
uint32_t csDelay;


static const uint8_t child_pipe[] = {RX_ADDR_P0, RX_ADDR_P1, RX_ADDR_P2, RX_ADDR_P3, RX_ADDR_P4, RX_ADDR_P5};
static const uint8_t child_payload_size[] = {RX_PW_P0, RX_PW_P1, RX_PW_P2, RX_PW_P3, RX_PW_P4, RX_PW_P5};
static const uint8_t child_pipe_enable[] = {ERX_P0, ERX_P1, ERX_P2, ERX_P3, ERX_P4, ERX_P5};

uint8_t nRF24_read_buffer(uint8_t reg, uint8_t* buf, uint8_t len){
  uint8_t status;

	nRF24_csn(LOW);
	status = nRF24_spi_transfer( R_REGISTER | ( REGISTER_MASK & reg ), RF24_SPI_TIMEOUT);
	while ( len-- ){
		*buf++ = nRF24_spi_transfer(0xff, RF24_SPI_TIMEOUT);
	}
	nRF24_csn(HIGH);
	
  return status;
}

/* ************************************************************************** */
uint8_t nRF24_read_register(uint8_t reg){
	uint8_t result;

	nRF24_csn(LOW);
	nRF24_spi_transfer(R_REGISTER | (REGISTER_MASK & reg), RF24_SPI_TIMEOUT);
	result = nRF24_spi_transfer(0xff, RF24_SPI_TIMEOUT);
	nRF24_csn(HIGH);

	return result;
}

/* ************************************************************************** */
uint8_t nRF24_write_buffer(uint8_t reg, uint8_t* buf, uint8_t len){
	uint8_t status;

	nRF24_csn(LOW);
	status = nRF24_spi_transfer( W_REGISTER | ( REGISTER_MASK & reg ), RF24_SPI_TIMEOUT);
	while ( len-- )
		nRF24_spi_transfer(*buf++, RF24_SPI_TIMEOUT);
	nRF24_csn(HIGH);
	
	return status;
}

/* ************************************************************************** */
uint8_t nRF24_write_register(uint8_t reg, uint8_t value){
    uint8_t status;

	nRF24_csn(LOW);
    status = nRF24_spi_transfer(W_REGISTER | (REGISTER_MASK & reg), RF24_SPI_TIMEOUT);
    nRF24_spi_transfer(value, RF24_SPI_TIMEOUT);
	nRF24_csn(HIGH);

    return status;
}

/* ************************************************************************** */
uint8_t nRF24_write_payload(uint8_t * buf, uint8_t data_len, uint8_t writeType){
    uint8_t status;

	data_len = rf24_min(data_len, payload_size);
    uint8_t blank_len = dynamic_payloads_enabled ? 0 : payload_size - data_len;

	nRF24_csn(LOW);
	status = nRF24_spi_transfer( writeType, RF24_SPI_TIMEOUT);
	while ( data_len-- ) {
		nRF24_spi_transfer(*buf++, RF24_SPI_TIMEOUT);
	}
	while ( blank_len-- ) {
		nRF24_spi_transfer(0, RF24_SPI_TIMEOUT);
	}  
	nRF24_csn(HIGH);

    return status;
}

/* ************************************************************************** */
uint8_t nRF24_read_payload(uint8_t * buf, uint8_t data_len){
    uint8_t status;
	
    if (data_len > payload_size) {
        data_len = payload_size;
    }
    uint8_t blank_len = dynamic_payloads_enabled ? 0 : payload_size - data_len;

	nRF24_csn(LOW);
	status = nRF24_spi_transfer( R_RX_PAYLOAD, RF24_SPI_TIMEOUT);
	while ( data_len-- ) {
		*buf++ = nRF24_spi_transfer(0xFF, RF24_SPI_TIMEOUT);
	}
	while ( blank_len-- ) {
		nRF24_spi_transfer(0xff, RF24_SPI_TIMEOUT);
	}
  	nRF24_csn(HIGH);

    return status;
}

/* ************************************************************************** */
static uint8_t nRF24_spiTrans(uint8_t cmd){
    uint8_t status;

	nRF24_csn(LOW);
	status = nRF24_spi_transfer(cmd,  RF24_SPI_TIMEOUT);
	nRF24_csn(HIGH);

    return status;
}

/* ************************************************************************** */
uint8_t nRF24_flush_rx(void){
    return nRF24_spiTrans(FLUSH_RX);
}

/****************************************************************************/
uint8_t nRF24_flush_tx(void){
    return nRF24_spiTrans(FLUSH_TX);
}

/* ************************************************************************** */
uint8_t nRF24_get_status(void){
    return nRF24_spiTrans(RF24_NOP);
}

/* ************************************************************************** */
void nRF24_setChannel(uint8_t channel){
    const uint8_t max_channel = 125;
    nRF24_write_register(RF_CH, rf24_min(channel, max_channel));
}

/* ************************************************************************** */
uint8_t nRF24_getChannel(void){

    return nRF24_read_register(RF_CH);
}

/* ************************************************************************** */
void nRF24_setPayloadSize(uint8_t size){
    payload_size = rf24_min(size, 32);
}

/****************************************************************************/
uint8_t nRF24_getPayloadSize(void){
    return payload_size;
}

/* ************************************************************************** */
bool nRF24_isChipConnected(void){
	uint8_t setup = nRF24_read_register(SETUP_AW);
	if (setup >= 1 && setup <= 3) {
			return TRUE;
	}

	return FALSE;
}
/* ************************************************************************** */
void nRF24_powerDown(void){
    nRF24_ce(LOW); // Guarantee CE is low on powerDown
    nRF24_write_register(NRF_CONFIG, nRF24_read_register(NRF_CONFIG) & ~_BV(PWR_UP));
}

/****************************************************************************/
//Power up now. Radio will not power down unless instructed by MCU for config changes etc.
void nRF24_powerUp(void){
    uint8_t cfg = nRF24_read_register(NRF_CONFIG);

    // if not powered up then power up and wait for the radio to initialize
    if (!(cfg & _BV(PWR_UP))) {
        nRF24_write_register(NRF_CONFIG, cfg | _BV(PWR_UP));

        // For nRF24L01+ to go from power down mode to TX or RX mode it must first pass through stand-by mode.
        // There must be a delay of Tpd2stby (see Table 16.) after the nRF24L01+ leaves power down mode before
        // the CEis set high. - Tpd2stby can be up to 5ms per the 1.0 datasheet
        delay(5);
    }
}
/* ************************************************************************** */
bool nRF24_rxFifoFull(void){
    return nRF24_read_register(FIFO_STATUS) & _BV(RX_FULL);
}
/* ************************************************************************** */
void nRF24_reUseTX(void){
	nRF24_write_register(NRF_STATUS, _BV(MAX_RT));              //Clear max retry flag
	nRF24_spiTrans(REUSE_TX_PL);
  	nRF24_ce(LOW);                                          //Re-Transfer packet
	delayMicroseconds(10);
	nRF24_ce(HIGH);
}

/* ************************************************************************** */
void nRF24_setPALevel(uint8_t level){
	uint8_t setup = nRF24_read_register(RF_SETUP) & 0xF8;

	if (level > 3) {                        // If invalid level, go to max PA
			level = (RF24_PA_MAX << 1) + 1;        // +1 to support the SI24R1 chip extra bit
	} else {
			level = (level << 1) + 1;            // Else set level as requested
	}
	nRF24_write_register(RF_SETUP, setup |= level);    // Write it to the chip
}

/****************************************************************************/
uint8_t nRF24_getPALevel(void){
	return (nRF24_read_register(RF_SETUP) & (_BV(RF_PWR_LOW) | _BV(RF_PWR_HIGH))) >> 1;
}

/****************************************************************************/
uint8_t nRF24_getARC(void){
	return nRF24_read_register(OBSERVE_TX) & 0x0F;
}

/****************************************************************************/
bool nRF24_setDataRate(rf24_datarate_e speed){
	bool result = FALSE;
	uint8_t setup = nRF24_read_register(RF_SETUP);

	// HIGH and LOW '00' is 1Mbs - our default
	setup &= ~(_BV(RF_DR_LOW) | _BV(RF_DR_HIGH));

	txDelay = 250;
	if (speed == RF24_250KBPS) {
		// Must set the RF_DR_LOW to 1; RF_DR_HIGH (used to be RF_DR) is already 0
		// Making it '10'.
		setup |= _BV(RF_DR_LOW);
		txDelay = 450;
	} else {
		// Set 2Mbs, RF_DR (RF_DR_HIGH) is set 1
		// Making it '01'
		if (speed == RF24_2MBPS) {
			setup |= _BV(RF_DR_HIGH);
			txDelay = 190;
		}
	}
	nRF24_write_register(RF_SETUP, setup);

	// Verify our result
	if (nRF24_read_register(RF_SETUP) == setup) {
		result = TRUE;
	}
	return result;
}

/****************************************************************************/
rf24_datarate_e nRF24_getDataRate(void){
	rf24_datarate_e result;
	uint8_t dr = nRF24_read_register(RF_SETUP) & (_BV(RF_DR_LOW) | _BV(RF_DR_HIGH));

	// switch uses RAM (evil!)
	// Order matters in our case below
	if (dr == _BV(RF_DR_LOW)) {
		// '10' = 250KBPS
		result = RF24_250KBPS;
	} else if (dr == _BV(RF_DR_HIGH)) {
		// '01' = 2MBPS
		result = RF24_2MBPS;
	} else {
		// '00' = 1MBPS
		result = RF24_1MBPS;
	}
	return result;
}

/****************************************************************************/
void nRF24_setCRCLength(rf24_crclength_e length){
	uint8_t config = nRF24_read_register(NRF_CONFIG) & ~(_BV(CRCO) | _BV(EN_CRC));

	// switch uses RAM (evil!)
	if (length == RF24_CRC_DISABLED) {
		// Do nothing, we turned it off above.
	} else if (length == RF24_CRC_8) {
		config |= _BV(EN_CRC);
	} else {
		config |= _BV(EN_CRC);
		config |= _BV(CRCO);
	}
	nRF24_write_register(NRF_CONFIG, config);
}

/****************************************************************************/
rf24_crclength_e nRF24_getCRCLength(void){
	rf24_crclength_e result = RF24_CRC_DISABLED;

	uint8_t config = nRF24_read_register(NRF_CONFIG) & (_BV(CRCO) | _BV(EN_CRC));
	uint8_t AA = nRF24_read_register(EN_AA);

	if (config & _BV(EN_CRC) || AA) {
		if (config & _BV(CRCO)) {
			result = RF24_CRC_16;
		} else {
			result = RF24_CRC_8;
		}
	}

	return result;
}

/****************************************************************************/
void nRF24_disableCRC(void){
    uint8_t disable = nRF24_read_register(NRF_CONFIG) & ~_BV(EN_CRC);
    nRF24_write_register(NRF_CONFIG, disable);
}

/****************************************************************************/
void nRF24_setRetries(uint8_t delay, uint8_t count){
    nRF24_write_register(SETUP_RETR, (delay & 0xf) << ARD | (count & 0xf) << ARC);
}

/* ************************************************************************** */
bool nRF24_testCarrier(void){
	return (nRF24_read_register(CD) & 1);
}

/****************************************************************************/
bool nRF24_testRPD(void){
	return (nRF24_read_register(RPD) & 1);
}

/* ************************************************************************** */
static void nRF24_toggle_features(void){
  nRF24_csn(LOW);

	nRF24_spi_transfer( ACTIVATE, RF24_SPI_TIMEOUT );
   nRF24_spi_transfer( 0x73, RF24_SPI_TIMEOUT );

  nRF24_csn(HIGH);
}

/* ************************************************************************** */
void nRF24_openWritingPipe_d(uint8_t value){
	// Note that AVR 8-bit uC's store this LSB first, and the NRF24L01(+)
	// expects it LSB first too, so we're good.
	
	uint8_t data[8] = {0};
	data[0] = value;

	nRF24_write_buffer(RX_ADDR_P0, data, addr_width);
	nRF24_write_buffer(TX_ADDR, data, addr_width);

	//const uint8_t max_payload_size = 32;
	//write_register(RX_PW_P0,rf24_min(payload_size,max_payload_size));
	nRF24_write_register(RX_PW_P0, payload_size);
}

/****************************************************************************/
void nRF24_openWritingPipe(uint8_t* address){
    // Note that AVR 8-bit uC's store this LSB first, and the NRF24L01(+)
    // expects it LSB first too, so we're good.
    nRF24_write_buffer(RX_ADDR_P0, address, addr_width);
    nRF24_write_buffer(TX_ADDR, address, addr_width);

    //const uint8_t max_payload_size = 32;
    //write_register(RX_PW_P0,rf24_min(payload_size,max_payload_size));
    nRF24_write_register(RX_PW_P0, payload_size);
}

/* ************************************************************************** */
void nRF24_setAddressWidth(uint8_t a_width){
	if (a_width -= 2) {
			nRF24_write_register(SETUP_AW, a_width % 4);
			addr_width = (a_width % 4) + 2;
	} else {
			nRF24_write_register(SETUP_AW, 0);
			addr_width = 2;
	}
}

/* ************************************************************************** */
void nRF24_openReadingPipe_d(uint8_t child, uint8_t value){
	uint8_t data[8] = {0};
	data[0] = value;
	// If this is pipe 0, cache the address.  This is needed because
	// openWritingPipe() will overwrite the pipe 0 address, so
	// startListening() will have to restore it.
	if (child == 0) {
			memcpy(pipe0_reading_address, data, addr_width);
	}

	if (child <= 6) {
			// For pipes 2-5, only write the LSB
			if (child < 2) {
					nRF24_write_buffer(child_pipe[child], data, addr_width);
			} else {
					nRF24_write_buffer(child_pipe[child], data, 1);
			}

			nRF24_write_register(child_payload_size[child], payload_size);

			// Note it would be more efficient to set all of the bits for all open
			// pipes at once.  However, I thought it would make the calling code
			// more simple to do it this way.
			nRF24_write_register(EN_RXADDR, nRF24_read_register(EN_RXADDR) | _BV(child_pipe_enable[child]));
	}
}

/* ************************************************************************** */
void nRF24_openReadingPipe(uint8_t child, uint8_t* address){
	// If this is pipe 0, cache the address.  This is needed because
	// openWritingPipe() will overwrite the pipe 0 address, so
	// startListening() will have to restore it.
	if (child == 0) {
		memcpy(pipe0_reading_address, address, addr_width);
	}
	if (child <= 6) {
		// For pipes 2-5, only write the LSB
		if (child < 2) {
				nRF24_write_buffer(child_pipe[child], address, addr_width);
		} else {
				nRF24_write_buffer(child_pipe[child], address, 1);
		}
		nRF24_write_register(child_payload_size[child], payload_size);

		// Note it would be more efficient to set all of the bits for all open
		// pipes at once.  However, I thought it would make the calling code
		// more simple to do it this way.
		nRF24_write_register(EN_RXADDR, nRF24_read_register(EN_RXADDR) | _BV(child_pipe_enable[child]));
	}
}

/* ************************************************************************** */
void nRF24_startListening(void){
	nRF24_powerUp();
	nRF24_write_register(NRF_CONFIG, nRF24_read_register(NRF_CONFIG) | _BV(PRIM_RX));
	nRF24_write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT));
	nRF24_ce(HIGH);
	// Restore the pipe0 adddress, if exists
	if (pipe0_reading_address[0] > 0) {
		nRF24_write_buffer(RX_ADDR_P0, pipe0_reading_address, addr_width);
	} else {
		nRF24_closeReadingPipe(0);
	}

	// Flush buffers
	//flush_rx();
	if (nRF24_read_register(FEATURE) & _BV(EN_ACK_PAY)) {
		nRF24_flush_tx();
	}
}

/****************************************************************************/
void nRF24_stopListening(void){
	nRF24_ce(LOW);

	delayMicroseconds(txDelay);

	if (nRF24_read_register(FEATURE) & _BV(EN_ACK_PAY)) {
		delayMicroseconds(txDelay); //200
		nRF24_flush_tx();
	}
	nRF24_write_register(NRF_CONFIG, (nRF24_read_register(NRF_CONFIG)) & ~_BV(PRIM_RX));
	nRF24_write_register(EN_RXADDR, nRF24_read_register(EN_RXADDR) | _BV(child_pipe_enable[0])); // Enable RX on pipe0
}

/* ************************************************************************** */
void nRF24_closeReadingPipe(uint8_t pipe){
	nRF24_write_register(EN_RXADDR, nRF24_read_register(EN_RXADDR) & ~_BV(child_pipe_enable[pipe]));
}

/* ************************************************************************** */
bool nRF24_available(void){
    return nRF24_available_d(NULL);
}

/****************************************************************************/
bool nRF24_available_d(uint8_t* pipe_num){
	if (!(nRF24_read_register(FIFO_STATUS) & _BV(RX_EMPTY))) {
		// If the caller wants the pipe number, include that
		if (pipe_num) {
			uint8_t status = nRF24_get_status();
			*pipe_num = (status >> RX_P_NO) & 0x07;
		}
		return 1;
	}
	return 0;
}

/* ************************************************************************** */
void nRF24_startFastWrite(uint8_t* buf, uint8_t len, bool multicast, bool startTx){
	//write_payload( buf,len);
	nRF24_write_payload(buf, len, multicast ? W_TX_PAYLOAD_NO_ACK : W_TX_PAYLOAD);
	if (startTx) {
		nRF24_ce(HIGH);
	}
}

/* ************************************************************************** */
void nRF24_read(uint8_t* buf, uint8_t len){
	// Fetch the payload
	nRF24_read_payload(buf, len);

	//Clear the two possible interrupt flags with one command
	nRF24_write_register(NRF_STATUS, _BV(RX_DR) | _BV(MAX_RT) | _BV(TX_DS));
}

/* ************************************************************************** */
//Similar to the previous write, clears the interrupt flags
bool nRF24_write_multi(uint8_t* buf, uint8_t len, bool multicast){
	//Start Writing
	nRF24_startFastWrite(buf, len, multicast, TRUE);

	//Wait until complete or failed
	#if defined(FAILURE_HANDLING)
		mxc_delay_start(MXC_DELAY_MSEC(1000));
	#endif // defined(FAILURE_HANDLING)

	while (!(nRF24_get_status() & (_BV(TX_DS) | _BV(MAX_RT)))) {
		#if defined(FAILURE_HANDLING)
			if (mxc_delay_check() != E_BUSY) {
				printf("TIMEOUT! Please check the pin connections detailed in main.c and then reset the board.\n");
				errNotify();
				return 0;
			}
		}
		#endif
	}

	nRF24_ce(LOW);
	uint8_t status = nRF24_write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT));

	//Max retries exceeded
	if (status & _BV(MAX_RT)) {
		nRF24_flush_tx(); //Only going to be 1 packet int the FIFO at a time using this method, so just flush
		return 0;
	}
	//TX OK 1 or 0
	return 1;
}

/* ************************************************************************** */
bool nRF24_write(uint8_t* buf, uint8_t len){
    return nRF24_write_multi(buf, len, 0);
}

/* ************************************************************************** */
void nRF24_init(void){
	nRF24_spi_init();
//	nRF24_gpio_init();
	pipe0_reading_address[0] = 0;
	p_variant = FALSE;
	payload_size = 32;
	dynamic_payloads_enabled = FALSE;
	addr_width = 5;
	csDelay = 5;
}

/* ************************************************************************** */
uint8_t nRF24_begin(void){
    uint8_t setup = 0;
	nRF24_init();
    delay(100);

    // Reset NRF_CONFIG and enable 16-bit CRC.
    nRF24_write_register(NRF_CONFIG, 0x0C);

    // Set 1500uS (minimum for 32B payload in ESB@250KBPS) timeouts, to make testing a little easier
    // WARNING: If this is ever lowered, either 250KBS mode with AA is broken or maximum packet
    // sizes must never be used. See documentation for a more complete explanation.
    nRF24_setRetries(5, 15);

    // Reset value is MAX
    //setPALevel( RF24_PA_MAX ) ;

    // check for connected module and if this is a p nRF24l01 variant
    //
    if (nRF24_setDataRate(RF24_250KBPS)) {
        p_variant = TRUE;
    }
    setup = nRF24_read_register(RF_SETUP);
    /*if( setup == 0b00001110 )     // register default for nRF24L01P
    {
      p_variant = true ;
    }*/

    // Then set the data rate to the slowest (and most reliable) speed supported by all
    // hardware.
    nRF24_setDataRate(RF24_1MBPS);

    // Initialize CRC and request 2-byte (16bit) CRC
    //setCRCLength( RF24_CRC_16 ) ;

    // Disable dynamic payloads, to match dynamic_payloads_enabled setting - Reset value is 0
    nRF24_toggle_features();
    nRF24_write_register(FEATURE, 0);
    nRF24_write_register(DYNPD, 0);
    dynamic_payloads_enabled = FALSE;

    // Reset current status
    // Notice reset and flush is the last thing we do
    nRF24_write_register(NRF_STATUS, _BV(RX_DR) | _BV(TX_DS) | _BV(MAX_RT));

    // Set up default configuration.  Callers can always change it later.
    // This channel should be universally safe and not bleed over into adjacent
    // spectrum.
    nRF24_setChannel(76);

    // Flush buffers
    nRF24_flush_rx();
    nRF24_flush_tx();

    nRF24_powerUp(); //Power up by default when begin() is called

    // Enable PTX, do not write CE high so radio will remain in standby I mode ( 130us max to transition to RX or TX instead of 1500us from powerUp )
    // PTX should use only 22uA of power
    nRF24_write_register(NRF_CONFIG, (nRF24_read_register(NRF_CONFIG)) & ~_BV(PRIM_RX));

    // if setup is 0 or ff then there was no response from module
    return (setup != 0 && setup != 0xff);
}

/* ************************************************************************** */

NXP Rapid Iot Kit - amg_8833.c

C/C++
Sensor library is designed to work with Hovergames rapid iot mavlink code and it needed to be connected at I2C_2 port of Rapid Iot Kit.
I2C_2 port is only available at J4 of mikroBUS CON2 of RDD-DRONE-IOT board. And also external 3V3 power supply is needed to power up the sensor. Or if Rapid Iot Kit is fully charged then TP38 can be used to supply the sensor.
#include <stdio.h>
#include <stdint.h>

#include "amg_8833.h"

#include "sensors.h"
#include "board.h"

#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))

		 // The power control register
struct pctl {
            // 0x00 = Normal Mode
			// 0x01 = Sleep Mode
			// 0x20 = Stand-by mode (60 sec intermittence)
			// 0x21 = Stand-by mode (10 sec intermittence)
         uint8_t PCTL : 8;
};


//reset register
struct rst {
			//0x30 = flag reset (all clear status reg 0x04, interrupt flag and interrupt table)
			//0x3F = initial reset (brings flag reset and returns to initial setting)
			uint8_t RST : 8;
};

//frame rate register
struct fpsc {
			//0 = 10FPS
			//1 = 1FPS
			uint8_t FPS : 1;

};


		//interrupt control register
struct intc {

			// 0 = INT output reactive (Hi-Z)
			// 1 = INT output active
			uint8_t INTEN : 1;

			// 0 = Difference interrupt mode
			// 1 = absolute value interrupt mode
			uint8_t INTMOD : 1;

};

		//status register
struct stat {
			uint8_t unused : 1;
			//interrupt outbreak (val of interrupt table reg)
			uint8_t INTF : 1;

			//temperature output overflow (val of temperature reg)
			uint8_t OVF_IRS : 1;

			//thermistor temperature output overflow (value of thermistor)
			uint8_t OVF_THS : 1;


};

		//status clear register
		//write to clear overflow flag and interrupt flag
		//after writing automatically turns to 0x00
struct sclr {
			uint8_t unused : 1;
			//interrupt flag clear
			uint8_t INTCLR : 1;
			//temp output overflow flag clear
			uint8_t OVS_CLR : 1;
			//thermistor temp output overflow flag clear
			uint8_t OVT_CLR : 1;
};

		//average register
		//for setting moving average output mode
struct ave {
			uint8_t unused : 5;
			//1 = twice moving average mode
			uint8_t MAMOD : 1;
};

		//interrupt level registers
		//for setting upper / lower limit hysteresis on interrupt level

		//interrupt level upper limit setting. Interrupt output
		// and interrupt pixel table are set when value exceeds set value
struct inthl {
			uint8_t INT_LVL_H : 8;
};

struct inthh {
			uint8_t INT_LVL_H : 4;
};

		//interrupt level lower limit. Interrupt output
		//and interrupt pixel table are set when value is lower than set value
struct intll {
			uint8_t INT_LVL_L : 8;
};

struct intlh {
			uint8_t INT_LVL_L : 4;
};

		//setting of interrupt hysteresis level when interrupt is generated.
		//should not be higher than interrupt level
struct ihysl {
			uint8_t INT_HYS : 8;
};

struct ihysh {
			uint8_t INT_HYS : 4;
};

		//thermistor register
		//SIGNED MAGNITUDE FORMAT
struct tthl {
			uint8_t TEMP : 8;
};

struct tthh {
			uint8_t TEMP : 3;
			uint8_t SIGN : 1;
};

		//temperature registers 0x80 - 0xFF
		/*
		//read to indicate temperature data per 1 pixel
		//SIGNED MAGNITUDE FORMAT
		struct t01l {
			uint8_t TEMP : 8;

			uint8_t get(){
				return TEMP;
			}
		};
		struct t01l _t01l;

		struct t01h {
			uint8_t TEMP : 3;
			uint8_t SIGN : 1;

			uint8_t get(){
				return ( (SIGN << 3) | TEMP) & 0xF;
			}
		};
		struct t01h _t01h;
		*/

struct pctl _pctl;
struct rst _rst;
struct fpsc _fpsc;
struct intc _intc;
struct stat _stat;
struct sclr _sclr;
struct ave _ave;
struct inthl _inthl;
struct inthh _inthh;
struct intll _intll;
struct intlh _intlh;
struct ihysl _ihysl;
struct ihysh _ihysh;
struct tthl _tthl;
struct tthh _tthh;

static uint8_t getPCTL(void){ return _pctl.PCTL; }
static uint8_t getRST(void){	return _rst.RST; }
static uint8_t getFPSC(void){ return _fpsc.FPS & 0x01; }
static uint8_t getINTC(void){ return (_intc.INTMOD << 1 | _intc.INTEN) & 0x03; }
static uint8_t getSTAT(void){ return ( (_stat.OVF_THS << 3) | (_stat.OVF_IRS << 2) | (_stat.INTF << 1) ) & 0x07; }
static uint8_t getSCLR(void){ return ((_sclr.OVT_CLR << 3) | (_sclr.OVS_CLR << 2) | (_sclr.INTCLR << 1)) & 0x07; }
static uint8_t getAVE(void){ return (_ave.MAMOD << 5); }
static uint8_t getINTHL(void){ return _inthl.INT_LVL_H; }
static uint8_t getINTHH(void){ return _inthh.INT_LVL_H; }
static uint8_t getINTLL(void){ return _intll.INT_LVL_L; }
static uint8_t getINTLH(void){ return (_intlh.INT_LVL_L & 0xF); }
static uint8_t getIHYSL(void){ return _ihysl.INT_HYS; }
static uint8_t getIHYSH(void){ return (_ihysh.INT_HYS & 0xF); }
static uint8_t getTTHL(void){ return _tthl.TEMP; }
static uint8_t getTTHH(void){ return ( (_tthh.SIGN << 3) | _tthh.TEMP) & 0xF; }
static uint8_t min(uint8_t a, uint8_t b){ return a < b ? a : b; }


static void write8(uint8_t reg, uint8_t value);
static uint8_t read8(uint8_t reg);

static void read(uint8_t reg, uint8_t *buf, uint8_t num);
static void write(uint8_t reg, uint8_t *buf, uint8_t num);

static float signedMag12ToFloat(uint16_t val);


/**************************************************************************/
/*! 
    @brief  Setups the I2C interface and hardware
    @param  addr Optional I2C address the sensor can be found on. Default is 0x69
    @returns True if device is set up, false on any failure
*/
/**************************************************************************/
int amg88xxInit(void)
{
	//enter normal mode
	_pctl.PCTL = AMG88xx_NORMAL_MODE;
	write8(AMG88xx_PCTL, getPCTL());
	
	//software reset
	_rst.RST = AMG88xx_INITIAL_RESET;
	write8(AMG88xx_RST, getRST());
	
	//disable interrupts by default
	disableInterrupt();
	
	//set to 10 FPS
	_fpsc.FPS = AMG88xx_FPS_10;
	write8(AMG88xx_FPSC, getFPSC());

	App_WaitMsec(100);

	return 0;
}

/**************************************************************************/
/*! 
    @brief  Set the moving average mode.
    @param  mode if True is passed, output will be twice the moving average
*/
/**************************************************************************/
void setMovingAverageMode(int mode)
{
	_ave.MAMOD = mode;
	write8(AMG88xx_AVE, getAVE());
}

/**************************************************************************/
/*! 
    @brief  Set the interrupt levels. The hysteresis value defaults to .95 * high
    @param  high the value above which an interrupt will be triggered
    @param  low the value below which an interrupt will be triggered
*/
/**************************************************************************/
void setInterruptLevels(float high, float low)
{
	setInterruptLevelsHist(high, low, high * .95f);
}

/**************************************************************************/
/*! 
    @brief  Set the interrupt levels
    @param  high the value above which an interrupt will be triggered
    @param  low the value below which an interrupt will be triggered
    @param hysteresis the hysteresis value for interrupt detection
*/
/**************************************************************************/
void setInterruptLevelsHist(float high, float low, float hysteresis)
{
	int highConv = high / AMG88xx_PIXEL_TEMP_CONVERSION;
	highConv = constrain(highConv, -4095, 4095);
	_inthl.INT_LVL_H = highConv & 0xFF;
	_inthh.INT_LVL_H = (highConv & 0xF) >> 4;
	write8(AMG88xx_INTHL, getINTHL());
	write8(AMG88xx_INTHH, getINTHH());
	
	int lowConv = low / AMG88xx_PIXEL_TEMP_CONVERSION;
	lowConv = constrain(lowConv, -4095, 4095);
	_intll.INT_LVL_L = lowConv & 0xFF;
	_intlh.INT_LVL_L = (lowConv & 0xF) >> 4;
	write8(AMG88xx_INTLL, getINTLL());
	write8(AMG88xx_INTLH, getINTLH());
	
	int hysConv = hysteresis / AMG88xx_PIXEL_TEMP_CONVERSION;
	hysConv = constrain(hysConv, -4095, 4095);
	_ihysl.INT_HYS = hysConv & 0xFF;
	_ihysh.INT_HYS = (hysConv & 0xF) >> 4;
	write8(AMG88xx_IHYSL, getIHYSL());
	write8(AMG88xx_IHYSH, getIHYSH());
}

/**************************************************************************/
/*! 
    @brief  enable the interrupt pin on the device.
*/
/**************************************************************************/
void enableInterrupt()
{
	_intc.INTEN = 1;
	write8(AMG88xx_INTC, getINTC());
}

/**************************************************************************/
/*! 
    @brief  disable the interrupt pin on the device
*/
/**************************************************************************/
void disableInterrupt()
{
	_intc.INTEN = 0;
	write8(AMG88xx_INTC, getINTC());
}

/**************************************************************************/
/*! 
    @brief  Set the interrupt to either absolute value or difference mode
    @param  mode passing AMG88xx_DIFFERENCE sets the device to difference mode, AMG88xx_ABSOLUTE_VALUE sets to absolute value mode.
*/
/**************************************************************************/
void setInterruptMode(uint8_t mode)
{
	_intc.INTMOD = mode;
	write8(AMG88xx_INTC, getINTC());
}

/**************************************************************************/
/*! 
    @brief  Read the state of the triggered interrupts on the device. The full interrupt register is 8 bytes in length.
    @param  buf the pointer to where the returned data will be stored
    @param  size Optional number of bytes to read. Default is 8 bytes.
    @returns up to 8 bytes of data in buf
*/
/**************************************************************************/
void getInterrupt(uint8_t *buf, uint8_t size)
{
	uint8_t bytesToRead = min(size, (uint8_t)8);
	
	read(AMG88xx_INT_OFFSET, buf, bytesToRead);
}

/**************************************************************************/
/*! 
    @brief  Clear any triggered interrupts
*/
/**************************************************************************/
void clearInterrupt()
{
	_rst.RST = AMG88xx_FLAG_RESET;
	write8(AMG88xx_RST, getRST());
}

/**************************************************************************/
/*! 
    @brief  read the onboard thermistor
    @returns a the floating point temperature in degrees Celsius
*/
/**************************************************************************/
float readThermistor()
{
	uint8_t raw[2];
	read(AMG88xx_TTHL, raw, 2);
	uint16_t recast = ((uint16_t)raw[1] << 8) | ((uint16_t)raw[0]);

	return signedMag12ToFloat(recast) * AMG88xx_THERMISTOR_CONVERSION;
}

/**************************************************************************/
/*! 
    @brief  Read Infrared sensor values
    @param  buf the array to place the pixels in
    @param  size Optionsl number of bytes to read (up to 64). Default is 64 bytes.
    @return up to 64 bytes of pixel data in buf
*/
/**************************************************************************/
void readPixels(float *buf, uint8_t size)
{
	uint16_t recast;
	float converted;
	uint8_t bytesToRead = min((uint8_t)(size << 1), (uint8_t)(AMG88xx_PIXEL_ARRAY_SIZE << 1));
	uint8_t rawArray[bytesToRead];
	read(AMG88xx_PIXEL_OFFSET, rawArray, bytesToRead);
	
	for(int i=0; i<size; i++){
		uint8_t pos = i << 1;
		recast = ((uint16_t)rawArray[pos + 1] << 8) | ((uint16_t)rawArray[pos]);
		
		converted = signedMag12ToFloat(recast) * AMG88xx_PIXEL_TEMP_CONVERSION;
		buf[i] = converted;
	}
}


void readPixelsRaw(int16_t* buf)
{
	read(AMG88xx_PIXEL_OFFSET, (uint8_t*)buf, 128);
}

/**************************************************************************/
/*! 
    @brief  write one byte of data to the specified register
    @param  reg the register to write to
    @param  value the value to write
*/
/**************************************************************************/
static void write8(uint8_t reg, uint8_t value)
{
	write(reg, &value, 1);
}

/**************************************************************************/
/*! 
    @brief  read one byte of data from the specified register
    @param  reg the register to read
    @returns one byte of register data
*/
/**************************************************************************/
static uint8_t read8(uint8_t reg)
{
	uint8_t ret;
	read(reg, &ret, 1);
	
	return ret;
}


static void read(uint8_t reg, uint8_t *buf, uint8_t num)
{
	App_I2C2_Read(AMG88xx_ADDRESS, &reg, 1, buf, num);
}

static void write(uint8_t reg, uint8_t *buf, uint8_t num)
{
	App_I2C2_Write(AMG88xx_ADDRESS, &reg, 1);
	App_I2C2_Write(AMG88xx_ADDRESS, buf, num);
}

/**************************************************************************/
/*! 
    @brief  convert a 12-bit signed magnitude value to a floating point number
    @param  val the 12-bit signed magnitude value to be converted
    @returns the converted floating point value
*/
/**************************************************************************/
static float signedMag12ToFloat(uint16_t val)
{
	//take first 11 bits as absolute val
	uint16_t absVal = (val & 0x7FF);
	
	return (val & 0x8000) ? 0 - (float)absVal : (float)absVal ;
}

NXP Rapid Iot Kit - amg_8833.h

C Header File
Sensor library is designed to work with Hovergames rapid iot mavlink code and it needed to be connected at I2C_2 port of Rapid Iot Kit.
I2C_2 port is only available at J4 of mikroBUS CON2 of RDD-DRONE-IOT board. And also external 3V3 power supply is needed to power up the sensor. Or if Rapid Iot Kit is fully charged then TP38 can be used to supply the sensor.
#ifndef LIB_AMG_88XX_H
#define LIB_AMG_88XX_H

#include <stdint.h>

/*=========================================================================
    I2C ADDRESS/BITS
    -----------------------------------------------------------------------*/
    #define AMG88xx_ADDRESS                (0x69)
/*=========================================================================*/

/*=========================================================================
    REGISTERS
    -----------------------------------------------------------------------*/
enum
    {
    AMG88xx_PCTL = 0x00,
		AMG88xx_RST = 0x01,
		AMG88xx_FPSC = 0x02,
		AMG88xx_INTC = 0x03,
		AMG88xx_STAT = 0x04,
		AMG88xx_SCLR = 0x05,
		//0x06 reserved
		AMG88xx_AVE = 0x07,
		AMG88xx_INTHL = 0x08,
		AMG88xx_INTHH = 0x09,
		AMG88xx_INTLL = 0x0A,
		AMG88xx_INTLH = 0x0B,
		AMG88xx_IHYSL = 0x0C,
		AMG88xx_IHYSH = 0x0D,
		AMG88xx_TTHL = 0x0E,
		AMG88xx_TTHH = 0x0F,
		AMG88xx_INT_OFFSET = 0x010,
		AMG88xx_PIXEL_OFFSET = 0x80
    };
	
enum power_modes{
		AMG88xx_NORMAL_MODE = 0x00,
		AMG88xx_SLEEP_MODE = 0x01,
		AMG88xx_STAND_BY_60 = 0x20,
		AMG88xx_STAND_BY_10 = 0x21
	};
	
enum sw_resets {
		AMG88xx_FLAG_RESET = 0x30,
		AMG88xx_INITIAL_RESET = 0x3F
	};
	
enum frame_rates {
		AMG88xx_FPS_10 = 0x00,
		AMG88xx_FPS_1 = 0x01
	};
	
enum int_enables{
		AMG88xx_INT_DISABLED = 0x00,
		AMG88xx_INT_ENABLED = 0x01
	};
	
enum int_modes {
		AMG88xx_DIFFERENCE = 0x00,
		AMG88xx_ABSOLUTE_VALUE = 0x01
	};
	
/*=========================================================================*/

#define AMG88xx_PIXEL_ARRAY_SIZE 64
#define AMG88xx_PIXEL_TEMP_CONVERSION .25f
#define AMG88xx_THERMISTOR_CONVERSION .0625f

/**************************************************************************/
/*! 
    @brief  Class that stores state and functions for interacting with AMG88xx IR sensor chips
*/
/**************************************************************************/

int amg88xxInit(void);
void readPixels(float *buf, uint8_t size/* = AMG88xx_PIXEL_ARRAY_SIZE */);
void readPixelsRaw(int16_t* buf);
float readThermistor(void);
void setMovingAverageMode(int mode);
void enableInterrupt(void);
void disableInterrupt(void);
void setInterruptMode(uint8_t mode);
void getInterrupt(uint8_t *buf, uint8_t /*size = 8 */);
void clearInterrupt(void);

//this will automatically set hysteresis to 95% of the high value
void setInterruptLevels(float high, float low);

//this will manually set hysteresis
void setInterruptLevelsHist(float high, float low, float hysteresis);

#endif

NXP Rapid Iot Kit - mlx90614.h

C Header File
Sensor library is designed to work with Hovergames rapid iot mavlink code and it needed to be connected at I2C_2 port of Rapid Iot Kit.
I2C_2 port is only available at J4 of mikroBUS CON2 of RDD-DRONE-IOT board. And also external 3V3 power supply is needed to power up the sensor. Or if Rapid Iot Kit is fully charged then TP38 can be used to supply the sensor.
#ifndef MLX90614_H
#define MLX90614_H

#include <stdint.h>

#define MLX90614_I2CADDR 0x5A

// RAM
#define MLX90614_RAWIR1 0x04
#define MLX90614_RAWIR2 0x05
#define MLX90614_TA 0x06
#define MLX90614_TOBJ1 0x07
#define MLX90614_TOBJ2 0x08
// EEPROM
#define MLX90614_TOMAX 0x20
#define MLX90614_TOMIN 0x21
#define MLX90614_PWMCTRL 0x22
#define MLX90614_TARANGE 0x23
#define MLX90614_EMISS 0x24
#define MLX90614_CONFIG 0x25
#define MLX90614_ADDR 0x0E
#define MLX90614_ID1 0x3C
#define MLX90614_ID2 0x3D
#define MLX90614_ID3 0x3E
#define MLX90614_ID4 0x3F


/* initialize IR sensor */
uint32_t ir_readID(void);

double ir_readObjectTempC(void);
double ir_readAmbientTempC(void);
double ir_readObjectTempF(void);
double ir_readAmbientTempF(void);

#endif  /* MLX90614_H */

NXP Rapid Iot Kit - mlx90614.c

C/C++
Sensor library is designed to work with Hovergames rapid iot mavlink code and it needed to be connected at I2C_2 port of Rapid Iot Kit.
I2C_2 port is only available at J4 of mikroBUS CON2 of RDD-DRONE-IOT board. And also external 3V3 power supply is needed to power up the sensor. Or if Rapid Iot Kit is fully charged then TP38 can be used to supply the sensor.
#include <stdio.h>
#include "mlx90614.h"

#include "sensors.h"

static float ir_readTemp(uint8_t reg);
static uint16_t ir_read16(uint8_t addr);
static void ir_sensor_buffer_read(uint8_t* p_buffer, uint8_t read_address, uint16_t number_of_byte);


uint32_t ir_readID(void){

}

double ir_readObjectTempF(void) {
  return (ir_readTemp(MLX90614_TOBJ1) * 9 / 5) + 32;
}

double ir_readAmbientTempF(void) {
  return (ir_readTemp(MLX90614_TA) * 9 / 5) + 32;
}

double ir_readObjectTempC(void) {
  return ir_readTemp(MLX90614_TOBJ1);
}

double ir_readAmbientTempC(void) {
  return ir_readTemp(MLX90614_TA);
}

static float ir_readTemp(uint8_t reg) {
  float temp;
  
  temp = ir_read16(reg);
  temp *= .02;
  temp  -= 273.15;
  return temp;
}

/*!
    \brief      I2C read 16bit function
    \param[in]  Address
    \param[out] none
    \retval     16bit read Value 
*/
static uint16_t ir_read16(uint8_t addr) {
  uint16_t data_temp =0;
  uint8_t data[4] = {0};
  ir_sensor_buffer_read(data, addr, 2);
  data_temp = data[0]|(data[1]<<8);
  return data_temp;
}

static void ir_sensor_buffer_read(uint8_t* p_buffer, uint8_t read_address, uint16_t number_of_byte)
{
	uint8_t ret_i2c = I2C_RESULT_OK;
	ret_i2c = App_I2C2_Read(MLX90614_I2CADDR, &read_address, 1, p_buffer, number_of_byte);
}

Sipeed Longan Nano - i2c.h

C Header File
I2C library to perform read and write operation with timeout. Systick is used to calculate the timeout in msec.
/*!
    \file  i2c.h
    \brief the header file of I2C
    
    \version 2019-06-05, V1.0.0, demo for GD32VF103
*/
#ifndef I2C_H
#define I2C_H

#include "gd32vf103.h"

#define I2C0_SPEED              400000	// AMG8833 sensor
#define I2C1_SPEED              100000	// MLX90614 sensor (It doesnt work at 400k I2C clock)

#define I2C0_MASTER_ADDRESS7    0x99
#define I2C1_MASTER_ADDRESS7    0x99

/* configure the GPIO ports */
void gpio_config(uint32_t i2c_periph);
/* configure the I2C interfaces */
void i2c_config(uint32_t i2c_periph);

uint8_t i2c_timeout(uint64_t start_i2c_time, uint32_t timeout);
uint8_t i2c_read(uint32_t i2c_periph, uint8_t slave_address, uint8_t read_address, uint8_t* p_buffer, uint8_t number_of_byte, uint32_t timeout);
uint8_t i2c_write(uint32_t i2c_periph, uint8_t slave_address, uint8_t write_address, uint8_t* p_buffer, uint8_t number_of_byte, uint32_t timeout);

#endif  /* I2C_H */

Sipeed Longan Nano - i2c.c

C/C++
I2C library to perform read and write operation with timeout. Systick is used to calculate the timeout in msec.
/*!
    \file  i2c.c
    \brief I2C configuration file
    
    \version 2019-06-05, V1.0.0, demo for GD32VF103
*/

#include "gd32vf103.h"
#include "ir_sensor/i2c.h"
#include <stdio.h>

/*!
    \brief      configure the GPIO ports
    \param[in]  i2c_periph: I2C0 or I2C1
    \param[out] none
    \retval     none
*/
void gpio_config(uint32_t i2c_periph)
{
    /* enable GPIOB clock */
    rcu_periph_clock_enable(RCU_GPIOB);

    if(i2c_periph == I2C0){
        /* I2C0 GPIO port */
        /* connect PB6 to I2C0_SCL */
        /* connect PB7 to I2C0_SDA */
        gpio_init(GPIOB, GPIO_MODE_AF_OD, GPIO_OSPEED_50MHZ, GPIO_PIN_6 | GPIO_PIN_7);
    }
    if(i2c_periph == I2C1){
        /* I2C1 GPIO ports */
        /* connect PB10 to I2C1_SCL */
        /* connect PB11 to I2C1_SDA */
        gpio_init(GPIOB, GPIO_MODE_AF_OD, GPIO_OSPEED_50MHZ, GPIO_PIN_10 | GPIO_PIN_11);
    }
}

/*!
    \brief      configure the I2C0 interfaces
    \param[in]  i2c_periph: I2C0 or I2C1
    \param[out] none
    \retval     none
*/
void i2c_config(uint32_t i2c_periph)
{

    /* configure the I2C GPIO port */
    gpio_config(i2c_periph);
    if(i2c_periph == I2C0){
        /* enable I2C0 clock */
        rcu_periph_clock_enable(RCU_I2C0);
        /* configure I2C0 clock */
        i2c_clock_config(i2c_periph,I2C0_SPEED,I2C_DTCY_2);
        /* configure I2C address */
        i2c_mode_addr_config(i2c_periph,I2C_I2CMODE_ENABLE,I2C_ADDFORMAT_7BITS,I2C0_MASTER_ADDRESS7);
    }
    if(i2c_periph == I2C1){
        /* enable I2C1 clock */
        rcu_periph_clock_enable(RCU_I2C1);
        /* configure I2C1 clock */
        i2c_clock_config(i2c_periph,I2C1_SPEED,I2C_DTCY_2);
        /* configure I2C1 address */
        i2c_mode_addr_config(i2c_periph,I2C_I2CMODE_ENABLE,I2C_ADDFORMAT_7BITS,I2C1_MASTER_ADDRESS7);
    }
    /* enable I2C */
    i2c_enable(i2c_periph);
    /* enable acknowledge */
    i2c_ack_config(i2c_periph,I2C_ACK_ENABLE);
}

/*!
    \brief      I2C timeout
    \param[in]  start_i2c_time: systick timer value
    \param[in]  timeout: msec
    \param[out] none
    \retval     none
*/
uint8_t i2c_timeout(uint64_t start_i2c_time, uint32_t timeout){
    uint64_t delta_mtime;
    delta_mtime = get_timer_value() - start_i2c_time;
    if(delta_mtime <(SystemCoreClock/4000.0 *timeout))
        return 0;
    else
        return 1;
}

/*!
    \brief      I2C Read Buffer
    \param[in]  i2c_periph: I2C0 or I2C1
    \param[in]  slave_address: 7-bit I2C slave address shifted left by 1 bit
    \param[in]  read_address: 8-bit I2C slave register address
    \param[in]  p_buffer: pointer of the buffer to store the read data
    \param[in]  number_of_byte: number of byte needed to read and store in p_buffer
    \param[in]  timeout: msec
    \param[out] none
    \retval     none
*/
uint8_t i2c_read(uint32_t i2c_periph, uint8_t slave_address, uint8_t read_address, uint8_t* p_buffer, uint8_t number_of_byte, uint32_t timeout)
{
    i2c_deinit(i2c_periph);
    i2c_config(i2c_periph);
  
    uint64_t start_mtime;
    	// Don't start measuruing until we see an mtime tick
    uint64_t tmp = get_timer_value();
    do {
    start_mtime = get_timer_value();
    } while (start_mtime == tmp);

    /* wait until I2C bus is idle */
    while(i2c_flag_get(i2c_periph, I2C_FLAG_I2CBSY)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }


    if(2 == number_of_byte){
        i2c_ackpos_config(i2c_periph,I2C_ACKPOS_NEXT);
    }
    
    /* send a start condition to I2C bus */
    i2c_start_on_bus(i2c_periph);
    
    /* wait until SBSEND bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_SBSEND)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* send slave address to I2C bus */
    i2c_master_addressing(i2c_periph, slave_address, I2C_TRANSMITTER);
    
    /* wait until ADDSEND bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_ADDSEND)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* clear the ADDSEND bit */
    i2c_flag_clear(i2c_periph,I2C_FLAG_ADDSEND);
    
    /* wait until the transmit data buffer is empty */
    while(SET != i2c_flag_get( i2c_periph , I2C_FLAG_TBE)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }

    /* enable i2c_periph*/
    i2c_enable(i2c_periph);
    
    /* send the EEPROM's internal address to write to */
    i2c_data_transmit(i2c_periph, read_address);  
    
    /* wait until BTC bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_BTC)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* send a start condition to I2C bus */
    i2c_start_on_bus(i2c_periph);
    
    /* wait until SBSEND bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_SBSEND)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* send slave address to I2C bus */
    i2c_master_addressing(i2c_periph, slave_address, I2C_RECEIVER);

    if(number_of_byte < 3){
        /* disable acknowledge */
        i2c_ack_config(i2c_periph,I2C_ACK_DISABLE);
    }
    
    /* wait until ADDSEND bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_ADDSEND)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* clear the ADDSEND bit */
    i2c_flag_clear(i2c_periph,I2C_FLAG_ADDSEND);
    
    if(1 == number_of_byte){
        /* send a stop condition to I2C bus */
        i2c_stop_on_bus(i2c_periph);
    }
    
    /* while there is data to be read */
    while(number_of_byte){
        if(3 == number_of_byte){
            /* wait until BTC bit is set */
            while(!i2c_flag_get(i2c_periph, I2C_FLAG_BTC)){
              if(i2c_timeout(start_mtime, timeout))
                    return 0;
            }

            /* disable acknowledge */
            i2c_ack_config(i2c_periph,I2C_ACK_DISABLE);
        }
        if(2 == number_of_byte){
            /* wait until BTC bit is set */
            while(!i2c_flag_get(i2c_periph, I2C_FLAG_BTC)){
              if(i2c_timeout(start_mtime, timeout))
                return 0;
            }
            
            /* send a stop condition to I2C bus */
            i2c_stop_on_bus(i2c_periph);
        }
        
        /* wait until the RBNE bit is set and clear it */
        if(i2c_flag_get(i2c_periph, I2C_FLAG_RBNE)){
            /* read a byte from the EEPROM */
            *p_buffer = i2c_data_receive(i2c_periph);
            
            /* point to the next location where the byte read will be saved */
            p_buffer++; 
            
            /* decrement the read bytes counter */
            number_of_byte--;
        } 
    }
    
    /* wait until the stop condition is finished */
    while(I2C_CTL0(i2c_periph)&0x0200){
      if(i2c_timeout(start_mtime, timeout))
        return 0;
    }
    
    /* enable acknowledge */
    i2c_ack_config(i2c_periph,I2C_ACK_ENABLE);
    i2c_ackpos_config(i2c_periph,I2C_ACKPOS_CURRENT);

    return 1;
}

/*!
    \brief      I2C Read Buffer
    \param[in]  i2c_periph: I2C0 or I2C1
    \param[in]  slave_address: 7-bit I2C slave address shifted left by 1 bit
    \param[in]  write_address: 8-bit I2C slave register address
    \param[in]  p_buffer: pointer of the buffer with write data
    \param[in]  number_of_byte: number of byte needed to write from p_buffer
    \param[in]  timeout: msec
    \param[out] none
    \retval     none
*/
uint8_t i2c_write(uint32_t i2c_periph, uint8_t slave_address, uint8_t write_address, uint8_t* p_buffer, uint8_t number_of_byte, uint32_t timeout)
{
    i2c_deinit(i2c_periph);
    i2c_config(i2c_periph);
  
    uint64_t start_mtime;
    	// Don't start measuruing until we see an mtime tick
    uint64_t tmp = get_timer_value();
    do {
    start_mtime = get_timer_value();
    } while (start_mtime == tmp);

    /* wait until I2C bus is idle */
    while(i2c_flag_get(i2c_periph, I2C_FLAG_I2CBSY)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* send a start condition to I2C bus */
    i2c_start_on_bus(i2c_periph);
    
    /* wait until SBSEND bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_SBSEND)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* send slave address to I2C bus */
    i2c_master_addressing(i2c_periph, slave_address, I2C_TRANSMITTER);
    
    /* wait until ADDSEND bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_ADDSEND)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }

    
    /* clear the ADDSEND bit */
    i2c_flag_clear(i2c_periph,I2C_FLAG_ADDSEND);
    
    /* wait until the transmit data buffer is empty */
    while( SET != i2c_flag_get(i2c_periph, I2C_FLAG_TBE)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }

    /* send the EEPROM's internal address to write to : only one byte address */
    i2c_data_transmit(i2c_periph, write_address);
    
    /* wait until BTC bit is set */
    while(!i2c_flag_get(i2c_periph, I2C_FLAG_BTC)){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }
    
    /* while there is data to be written */
    while(number_of_byte--){  
        i2c_data_transmit(i2c_periph, *p_buffer);
        
        /* point to the next byte to be written */
        p_buffer++; 
        
        /* wait until BTC bit is set */
        while(!i2c_flag_get(i2c_periph, I2C_FLAG_BTC)){
            if(i2c_timeout(start_mtime, timeout))
                return 0;
        }
    }
    /* send a stop condition to I2C bus */
    i2c_stop_on_bus(i2c_periph);
    
    /* wait until the stop condition is finished */
    while(I2C_CTL0(i2c_periph)&0x0200){
        if(i2c_timeout(start_mtime, timeout))
            return 0;
    }

    return 1;
}

Sipeed Longan Nano - nRF24_hw.h

C Header File
Hardware related functions, GPIO, SPI definitions and configuration.
#include <stdio.h>
#include <string.h>
#include <stdint.h>

#include "gd32vf103.h"
#include "gd32vf103_libopt.h"
#include "systick.h"


#define HIGH	1
#define LOW		0

#define SPI_TX_BUF		32
#define SPI_RX_BUF		32

#define SPI_PRESCALAR    16

#define SPI_PORT		GPIOA
#define SPI_SCK     GPIO_PIN_5
#define SPI_MISO		GPIO_PIN_6
#define SPI_MOSI		GPIO_PIN_7

#define RF24_CSN_PORT	GPIOA
#define RF24_CSN_PIN	GPIO_PIN_3

#define RF24_CE_PORT	GPIOA
#define RF24_CE_PIN		GPIO_PIN_2

/* **** Globals **** */

void nRF24_spi_init(void);

void nRF24_ce(uint8_t level);
void nRF24_csn(uint8_t level);

uint8_t nRF24_spi_transfer(uint8_t data, uint32_t timeout);

Sipeed Longan Nano - nRF24_hw.c

C/C++
SPI0 port is used with software based Slave Select option, for nRF24L01+ interfacing.
#include "nRF24_hw.h"

/* ************************************************************************** */
void nRF24_csn(uint8_t level){
	(level) ? gpio_bit_set(RF24_CSN_PORT, RF24_CSN_PIN) : gpio_bit_reset(RF24_CSN_PORT, RF24_CSN_PIN);
}

/* ************************************************************************** */
void nRF24_ce(uint8_t level){
	(level) ? gpio_bit_set(RF24_CE_PORT, RF24_CE_PIN) : gpio_bit_reset(RF24_CE_PORT, RF24_CE_PIN);
}

/* ************************************************************************** */
void nRF24_spi_init(void){
	rcu_periph_clock_enable(RCU_AF);
    rcu_periph_clock_enable(RCU_SPI0);

    spi_parameter_struct spi_init_struct;
    /* deinitilize SPI and the parameters */
    spi_i2s_deinit(SPI0);
    spi_struct_para_init(&spi_init_struct);

    /* SPI0 parameter config */
    spi_init_struct.trans_mode           = SPI_TRANSMODE_FULLDUPLEX;
    spi_init_struct.device_mode          = SPI_MASTER;
    spi_init_struct.frame_size           = SPI_FRAMESIZE_8BIT;
    spi_init_struct.clock_polarity_phase = SPI_CK_PL_LOW_PH_1EDGE;
    spi_init_struct.nss                  = SPI_NSS_SOFT;
    spi_init_struct.prescale             = SPI_PRESCALAR;
    spi_init_struct.endian               = SPI_ENDIAN_MSB;
    spi_init(SPI0, &spi_init_struct);
	spi_crc_polynomial_set(SPI0,7);
	spi_enable(SPI0);
}

/* ************************************************************************** */
void nRF24_gpio_init(void){
    /* SPI0 GPIO config:SCK/PA5, MISO/PA6, MOSI/PA7 */
    gpio_init(SPI_PORT, GPIO_MODE_AF_PP, GPIO_OSPEED_50MHZ, SPI_SCK | SPI_MOSI);
    gpio_init(SPI_PORT, GPIO_MODE_IN_FLOATING, GPIO_OSPEED_50MHZ, SPI_MISO);
	
    /* RF24 CE and CSN GPIO config: CE/PA2, CSN/PA3 */
	gpio_init(RF24_CSN_PORT, GPIO_MODE_OUT_PP, GPIO_OSPEED_50MHZ, RF24_CSN_PIN);
	gpio_init(RF24_CE_PORT, GPIO_MODE_OUT_PP, GPIO_OSPEED_50MHZ, RF24_CE_PIN);

	nRF24_csn(HIGH);
	nRF24_ce(LOW);	
}


/* ************************************************************************** */
uint8_t nRF24_spi_transfer(uint8_t data, uint32_t timeout){
    while(RESET == spi_i2s_flag_get(SPI0, SPI_FLAG_TBE));
    spi_i2s_data_transmit(SPI0, data);
    while(RESET == spi_i2s_flag_get(SPI0, SPI_FLAG_RBNE));
    return spi_i2s_data_receive(SPI0);
}
/* ************************************************************************** */

Sipeed-Longan-Nano

NXP - Rapid Iot Kit

NXP HoverGames Mapper

Standalone thermal and environmental data mapper using static maps and live drone data.

OnSemi RSL 10 Sense Code

Credits

Mahmood ul Hassan

Mahmood ul Hassan

13 projects • 18 followers
Electronics Engineer with more than 13 years of experience in reverse engineering and test & measurement equipment designing

Comments