18 #include "clock_config.h" 20 #include "fsl_debug_console.h" 23 #include "fsl_common.h" 24 #include "freemaster.h" 25 #include "freemaster_serial_uart.h" 29 #include "Driver_I2C.h" 34 #include "issdk_hal.h" 35 #include "gpio_driver.h" 42 #define FXLS8974_NUM_REGISTERS (FXLS8974_SELF_TEST_CONFIG2 + 1) 43 #define FF_A_FFMT_THS (0x08) 44 #define A_FFMT_COUNT (0x18) 45 #define PL_COUNT (0x15) 46 #define ASLP_COUNTER (0x07) 47 #define ACCEL_2G_SENS (0.000976) 48 #define ACCEL_4G_SENS (0.001953) 49 #define ACCEL_8G_SENS (0.003906) 50 #define ACCEL_16G_SENS (0.007813) 52 #define RAW_ACCEL_DATA_SIZE (6U) 53 #define MAX8BITSTORAGE (255U) 54 #define FXLS8974_DATA_SIZE 6 239 static FMSTR_U8 recBuffer[1024*10];
245 static unsigned char pipe3_rxb[512];
246 static unsigned char pipe3_txb[0x1000];
250 int16_t
XSTP[2]={0,0},
YSTP[2]={0,0},
ZSTP[2]={0,0},
XSTN[2]={0,0},
YSTN[2]={0,0},
ZSTN[2]={0,0};
261 static void init_freemaster_uart(
void);
393 FMSTR_TSA_TABLE_END()
395 FMSTR_TSA_TABLE_LIST_BEGIN()
396 FMSTR_TSA_TABLE(main_table)
397 FMSTR_TSA_TABLE_LIST_END()
410 recBuffCfg.name =
"FXLS8974 3-Axis Accelerometer Data";
443 init_freemaster_uart();
447 if (ARM_DRIVER_OK != status)
453 status = I2Cdrv->PowerControl(ARM_POWER_FULL);
454 if (ARM_DRIVER_OK != status)
460 status = I2Cdrv->Control(ARM_I2C_BUS_SPEED, ARM_I2C_BUS_SPEED_FAST);
461 if (ARM_DRIVER_OK != status)
491 FMSTR_HPIPE hpipe = FMSTR_PipeOpen(3, NULL, (FMSTR_ADDR)pipe3_rxb,
sizeof(pipe3_rxb), (FMSTR_ADDR)pipe3_txb,
sizeof(pipe3_txb),
492 FMSTR_PIPE_TYPE_ANSI_TERMINAL,
"streaming");
582 if (ARM_DRIVER_OK != status)
601 rawData.
accel[0] = (int16_t)(((int16_t)(((int16_t)registers.
reg_addr[3] << 8) | registers.
reg_addr[2])));
602 rawData.
accel[1] = (int16_t)(((int16_t)(((int16_t)registers.
reg_addr[5] << 8) | registers.
reg_addr[4])));
603 rawData.
accel[2] = (int16_t)(((int16_t)(((int16_t)registers.
reg_addr[7] << 8) | registers.
reg_addr[6])));
620 else if ((regdata & FXLS8974_SENS_CONFIG1_FSR_MASK) == 4)
624 else if ((regdata & FXLS8974_SENS_CONFIG1_FSR_MASK) == 6)
634 registers.
accel[0] = (float) (rawData.
accel[0] * sensitivity);
635 registers.
accel[1] = (float) (rawData.
accel[1] * sensitivity);
636 registers.
accel[2] = (float) (rawData.
accel[2] * sensitivity);
816 offnoiseptr->
offx = 0.0;
817 offnoiseptr->
offy = 0.0;
818 offnoiseptr->
offz = 0.0;
819 offnoiseptr->
rmsx = 0.0;
820 offnoiseptr->
rmsy = 0.0;
821 offnoiseptr->
rmsz = 0.0;
831 static uint16_t cntr=0;
835 static float xx[
N], yy[
N], zz[
N];
836 static float xm[
N], ym[
N], zm[
N];
837 static float xsq[
N], ysq[
N], zsq[
N];
839 static float sumx=0.0;
840 static float sumy=0.0;
841 static float sumz=0.0;
851 am[0]=rawData->
accel[0]*sens;
852 am[1]=rawData->
accel[1]*sens;
853 am[2]=rawData->
accel[2]*sens;
873 offnoiseptr->
offx=0-sumx;
874 offnoiseptr->
offy=0-sumy;
875 offnoiseptr->
offz=1-sumz;
884 xsq[j]=(float)pow(xm[j],2);
885 ysq[j]=(float)pow(ym[j],2);
886 zsq[j]=(float)pow(zm[j],2);
896 offnoiseptr->
rmsx=(float)pow(stdx,0.5);
897 offnoiseptr->
rmsy=(float)pow(stdy,0.5);
898 offnoiseptr->
rmsz=(float)pow(stdz,0.5);
905 sumx = sumy = sumz = 0;
906 stdx = stdy = stdz = 0;
948 if (ARM_DRIVER_OK != status)
954 for(counter=0;counter<1;counter++)
967 if (ARM_DRIVER_OK != status)
978 if (ARM_DRIVER_OK != status)
1018 static void init_freemaster_uart(
void)
1020 uart_config_t config;
1031 UART_GetDefaultConfig(&config);
1032 config.baudRate_Bps = 115200U;
1033 config.enableTx =
false;
1034 config.enableRx =
false;
1039 FMSTR_SerialSetBaseAddress((UART_Type*)BOARD_DEBUG_UART_BASEADDR);
1041 #if FMSTR_SHORT_INTR || FMSTR_LONG_INTR 1048 #if FMSTR_SHORT_INTR || FMSTR_LONG_INTR 1066 #if defined __CORTEX_M && (__CORTEX_M == 4U)
FMSTR_REC_BUFF recBuffCfg
#define FXLS8974_SENS_CONFIG1_ST_POL_MASK
#define FXLS8974_INT_EN_DRDY_EN_MASK
const registerreadlist_t cFXLS8974_int_src[]
Prepare the register read for INT Status Register.
int32_t apply_register_read(fxls8974_i2c_sensorhandle_t fxls8974Driver, uint8_t offset, uint8_t *value)
Function to apply FXLS8974 register read operation.
const registerwritelist_t cFxls8974ConfigNormal[]
Defines the register write list to configure FXLS8974 in Interrupt mode.
This structure defines the Write command List.
#define FXLS8974_SENS_CONFIG1_FSR_MASK
int32_t FXLS8974_I2C_Configure(fxls8974_i2c_sensorhandle_t *pSensorHandle, const registerwritelist_t *pRegWriteList)
The interface function to configure he sensor.
#define FXLS8974_DATA_SIZE
int32_t FXLS8974_I2C_Initialize(fxls8974_i2c_sensorhandle_t *pSensorHandle, ARM_DRIVER_I2C *pBus, uint8_t index, uint16_t sAddress, uint8_t *whoami)
The interface function to initialize the sensor.
#define FXLS8974_SENS_CONFIG1_ST_AXIS_SEL_DISABLED
status_t SMC_SetPowerModeVlpr(void *arg)
Configures the system to VLPR power mode. API name used from Kinetis family to maintain compatibility...
#define FXLS8974_SENS_CONFIG1_ST_AXIS_SEL_EN_X
const registerwritelist_t cFxls8974STYN[]
Register settings for Self-Test in Y Axis (Negative polarity).
int32_t Register_I2C_Write(ARM_DRIVER_I2C *pCommDrv, registerDeviceInfo_t *devInfo, uint16_t slaveAddress, uint8_t offset, uint8_t value, uint8_t mask, bool repeatedStart)
The interface function to write a sensor register.
void BOARD_DELAY_ms(uint32_t delay_ms)
Function to insert delays.
volatile bool bFxls8974IntFlag
#define FXLS8974_INT_EN_DRDY_EN_EN
#define FXLS8974_SENS_CONFIG2_ANIC_TEMP_EN
enum fxls8974_operation_type fxls8974_operation_type_t
This structure defines the fxls8974 host operation type.
#define BOARD_DEBUG_UART_CLK_FREQ
const registerreadlist_t FXLS8974_ALL_REG_READ[]
FXLS8974 register list to read all registers.
const registerreadlist_t cFXLS8974_whoami[]
fxls8974_offset_noise_t offnoise_data
Access structure of the GPIO Driver.
This defines the sensor specific information for I2C.
void selftest_init(fxls8974_selftest_t *selftest)
Function to initialize FXLS8974 self test metadata.
This structure defines the fxls8974 all registers metadata.
#define FXLS8974_SENS_CONFIG1_FSR_16G
#define __END_WRITE_DATA__
#define FXLS8974_SENS_CONFIG1_ST_POL_POSITIVE
typedef int32_t(DATA_FORMAT_Append_t))(void *pData
The interface function to append the data on the formated stream.
#define FXLS8974_NUM_REGISTERS
#define I2C_S_SIGNAL_EVENT
#define FXLS8974_I2C_ADDR
void offset_noise_init(fxls8974_offset_noise_t *offnoiseptr)
Function to initialize offset noise measurement.
This structure defines variables to compute self-test output change (STOC) and self-test offset (STOF...
uint8_t reg_addr[FXLS8974_NUM_REGISTERS]
const registerwritelist_t cFxls8974STXN[]
Register settings for Self-Test in X Axis (Negative polarity).
#define BOARD_BootClockRUN
void(* registeridlefunction_t)(void *userParam)
This is the register idle function type.
int32_t apply_register_readall(fxls8974_i2c_sensorhandle_t fxls8974Driver)
Function to apply FXLS8974 register read-all operation.
int32_t FXLS8974_I2C_ReadData(fxls8974_i2c_sensorhandle_t *pSensorHandle, const registerreadlist_t *pReadList, uint8_t *pBuffer)
The interface function to read the sensor data.
void fxls8974_isr_callback(void *pUserData)
ISR for FXLS8974 interrupt source event.
#define FXLS8974_SENS_CONFIG1_ST_AXIS_SEL_EN_Z
GENERIC_DRIVER_GPIO Driver_GPIO_KSDK
GENERIC_DRIVER_GPIO * pGpioDriver
int32_t update_dropdown_selection(fxls8974_allregs_t *registers, uint8_t caller)
Function to update dropdown selection.
uint32_t BOARD_SystickElapsedTime_us(int32_t *pStart)
Function to compute the Elapsed Time.
This structure defines the fxls8974 raw data buffer.
int main(void)
Main function.
const registerreadlist_t cFXLS8974_fs_src[]
Prepare the register read for FullScale range Register.
#define BOARD_UART_IRQ_HANDLER
This structure defines the fxls8974 offset and noise calculation parameters.
#define FXLS8974_SENS_CONFIG1_FSR_4G
#define FXLS8974_SENS_CONFIG3_WAKE_ODR_12_5HZ
const registerwritelist_t cFxls8974STYP[]
Register settings for Self-Test in Y Axis (Positive polarity).
#define __END_READ_DATA__
fxls8974_operation_type
This structure defines the fxls8974 host operation type.
#define FXLS8974_SENS_CONFIG2_ANIC_TEMP_MASK
#define FXLS8974_SENS_CONFIG3_WAKE_ODR_MASK
void accel_off_noise(fxls8974_acceldata_t *rawData, fxls8974_offset_noise_t *offnoiseptr, float sens)
Function to measure accelerometer offset noise.
fxls8974_allregs_t registers
fxls8974_i2c_sensorhandle_t fxls8974Driver
uint8_t complete_selftest
#define BOARD_DEBUG_UART_BASEADDR
int32_t perform_selftest(fxls8974_i2c_sensorhandle_t fxls8974Driver, fxls8974_selftest_t *selftest)
Function to perform FXLS8974 self test.
void FXLS8974_I2C_SetIdleTask(fxls8974_i2c_sensorhandle_t *pSensorHandle, registeridlefunction_t idleTask, void *userParam)
: The interface function to set the I2C Idle Task.
FMSTR_TSA_TABLE_BEGIN(main_table)
Target Side Addressable (TSA) table created for this application.
const registerreadlist_t cFxls8974OutputNormal[]
Address of Raw Accel Data in Normal Mode.
#define FXLS8974_SENS_CONFIG1_ST_AXIS_SEL_EN_Y
uint8_t complete_accel_offnoise
void(* toggle_pin)(pinID_t aPinId)
int32_t apply_register_write(fxls8974_i2c_sensorhandle_t fxls8974Driver, uint8_t offset, uint8_t value)
Function to apply FXLS8974 register write operation.
void BOARD_SystickEnable(void)
Function to enable systicks framework.
status_t SMC_SetPowerModeWait(void *arg)
Configures the system to WAIT power mode. API name used from Kinetis family to maintain compatibility...
void(* pin_init)(pinID_t aPinId, gpio_direction_t dir, void *apPinConfig, gpio_isr_handler_t aIsrHandler, void *apUserData)
This structure defines the Read command List.
const registerwritelist_t cFxls8974STZP[]
Register settings for Self-Test in Z Axis (Positive polarity).
const registerwritelist_t cFxls8974STXP[]
Register settings for Self-Test in X Axis (Positive polarity).
#define FXLS8974_SENS_CONFIG1_ST_AXIS_SEL_MASK
gpioHandleKSDK_t GREEN_LED
uint8_t trigger_accel_offnoise
The fxls8974_drv.h file describes the FXLS8974CF driver interface and structures. ...
#define I2C_S_DEVICE_INDEX
uint8_t readall_value[FXLS8974_NUM_REGISTERS]
void BOARD_InitDebugConsole(void)
void BOARD_InitPins(void)
Configures pin routing and optionally pin electrical features.
const registerwritelist_t cFxls8974STZN[]
Register settings for Self-Test in Z Axis (Negative polarity).
registerDeviceInfo_t deviceInfo
This structure defines the fxls8962 raw data buffer.
fxls8974_selftest_t selftest
fxls8974_acceldata_t rawData
uint8_t byte_data[sizeof(sensor_data)]
#define FXLS8974_SENS_CONFIG1_ST_POL_NEGATIVE