18 #include "clock_config.h" 20 #include "fsl_debug_console.h" 23 #include "fsl_common.h" 24 #include "freemaster.h" 25 #include "usb_device_config.h" 26 #include "freemaster_usb.h" 30 #include "Driver_I2C.h" 35 #include "issdk_hal.h" 36 #include "gpio_driver.h" 43 #define FXLS896x_NUM_REGISTERS (FXLS896x_SELF_TEST_CONFIG2 + 1) 44 #define FF_A_FFMT_THS (0x08) 45 #define A_FFMT_COUNT (0x18) 46 #define PL_COUNT (0x15) 47 #define ASLP_COUNTER (0x07) 48 #define ACCEL_2G_SENS (0.000976) 49 #define ACCEL_4G_SENS (0.001953) 50 #define ACCEL_8G_SENS (0.003906) 51 #define ACCEL_16G_SENS (0.007813) 53 #define RAW_ACCEL_DATA_SIZE (6U) 54 #define MAX8BITSTORAGE (255U) 55 #define FXLS896x_DATA_SIZE 6 160 uint8_t read_trigger;
162 uint8_t readall_size;
163 uint8_t readall_trigger;
165 uint8_t trigger_accel_offnoise;
166 uint8_t trigger_selftest;
171 uint8_t dataready_cntr;
189 uint8_t complete_accel_offnoise;
201 uint8_t complete_selftest;
240 static FMSTR_U8 recBuffer[1024*10];
246 static unsigned char pipe3_rxb[512];
247 static unsigned char pipe3_txb[0x1000];
251 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};
388 FMSTR_TSA_TABLE_END()
390 FMSTR_TSA_TABLE_LIST_BEGIN()
391 FMSTR_TSA_TABLE(main_table)
392 FMSTR_TSA_TABLE_LIST_END()
405 recBuffCfg.name =
"FXLS896x 3-Axis Accelerometer Data";
440 SystemCoreClockUpdate();
441 CLOCK_EnableUsbfs0Clock(kCLOCK_UsbSrcIrc48M, 48000000U);
444 FMSTR_ExampleUsbInit();
448 if (ARM_DRIVER_OK != status)
454 status = I2Cdrv->PowerControl(ARM_POWER_FULL);
455 if (ARM_DRIVER_OK != status)
461 status = I2Cdrv->Control(ARM_I2C_BUS_SPEED, ARM_I2C_BUS_SPEED_FAST);
462 if (ARM_DRIVER_OK != status)
492 FMSTR_HPIPE hpipe = FMSTR_PipeOpen(3, NULL, (FMSTR_ADDR)pipe3_rxb,
sizeof(pipe3_rxb), (FMSTR_ADDR)pipe3_txb,
sizeof(pipe3_txb),
493 FMSTR_PIPE_TYPE_ANSI_TERMINAL,
"streaming");
583 if (ARM_DRIVER_OK != status)
602 rawData.
accel[0] = (int16_t)(((int16_t)(((int16_t)registers.
reg_addr[3] << 8) | registers.
reg_addr[2])));
603 rawData.
accel[1] = (int16_t)(((int16_t)(((int16_t)registers.
reg_addr[5] << 8) | registers.
reg_addr[4])));
604 rawData.
accel[2] = (int16_t)(((int16_t)(((int16_t)registers.
reg_addr[7] << 8) | registers.
reg_addr[6])));
621 else if ((regdata & FXLS896x_SENS_CONFIG1_FSR_MASK) == 4)
625 else if ((regdata & FXLS896x_SENS_CONFIG1_FSR_MASK) == 6)
635 registers.
accel[0] = (float) (rawData.
accel[0] * sensitivity);
636 registers.
accel[1] = (float) (rawData.
accel[1] * sensitivity);
637 registers.
accel[2] = (float) (rawData.
accel[2] * sensitivity);
817 offnoiseptr->
offx = 0.0;
818 offnoiseptr->
offy = 0.0;
819 offnoiseptr->
offz = 0.0;
820 offnoiseptr->
rmsx = 0.0;
821 offnoiseptr->
rmsy = 0.0;
822 offnoiseptr->
rmsz = 0.0;
832 static uint16_t cntr=0;
836 static float xx[
N], yy[
N], zz[
N];
837 static float xm[
N], ym[
N], zm[
N];
838 static float xsq[
N], ysq[
N], zsq[
N];
840 static float sumx=0.0;
841 static float sumy=0.0;
842 static float sumz=0.0;
852 am[0]=rawData->
accel[0]*sens;
853 am[1]=rawData->
accel[1]*sens;
854 am[2]=rawData->
accel[2]*sens;
874 offnoiseptr->
offx=0-sumx;
875 offnoiseptr->
offy=0-sumy;
876 offnoiseptr->
offz=1-sumz;
885 xsq[j]=(float)pow(xm[j],2);
886 ysq[j]=(float)pow(ym[j],2);
887 zsq[j]=(float)pow(zm[j],2);
897 offnoiseptr->
rmsx=(float)pow(stdx,0.5);
898 offnoiseptr->
rmsy=(float)pow(stdy,0.5);
899 offnoiseptr->
rmsz=(float)pow(stdz,0.5);
906 sumx = sumy = sumz = 0;
907 stdx = stdy = stdz = 0;
949 if (ARM_DRIVER_OK != status)
955 for(counter=0;counter<1;counter++)
968 if (ARM_DRIVER_OK != status)
979 if (ARM_DRIVER_OK != status)
The fxls896x_drv.h file describes the FXLS8964/67AF driver interface and structures.
#define FXLS896x_SENS_CONFIG2_ANIC_TEMP_EN
This structure defines the Write command List.
#define FXLS896x_SENS_CONFIG1_FSR_4G
#define FXLS896x_SENS_CONFIG3_WAKE_ODR_12_5HZ
const registerwritelist_t cFxls896xSTYP[]
Register settings for Self-Test in Y Axis (Positive polarity).
#define FXLS896x_I2C_ADDR
const registerwritelist_t cFxls896xSTXP[]
Register settings for Self-Test in X Axis (Positive polarity).
status_t SMC_SetPowerModeVlpr(void *arg)
Configures the system to VLPR power mode. API name used from Kinetis family to maintain compatibility...
#define FXLS896x_DATA_SIZE
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.
This structure defines the fxls896x all registers metadata.
#define FXLS896x_SENS_CONFIG1_ST_POL_POSITIVE
void BOARD_DELAY_ms(uint32_t delay_ms)
Function to insert delays.
int32_t apply_register_write(fxls896x_i2c_sensorhandle_t fxls896xDriver, uint8_t offset, uint8_t value)
Function to apply FXLS896x register write operation.
uint8_t complete_accel_offnoise
fxls896x_offset_noise_t offnoise_data
int32_t FXLS896x_I2C_Initialize(fxls896x_i2c_sensorhandle_t *pSensorHandle, ARM_DRIVER_I2C *pBus, uint8_t index, uint16_t sAddress, uint8_t *whoami)
The interface function to initialize the sensor.
Access structure of the GPIO Driver.
registerDeviceInfo_t deviceInfo
const registerreadlist_t cFXLS896x_fs_src[]
Prepare the register read for FullScale range Register.
uint8_t complete_selftest
int32_t apply_register_readall(fxls896x_i2c_sensorhandle_t fxls896xDriver)
Function to apply FXLS896x register read-all operation.
#define FXLS896x_SENS_CONFIG1_ST_AXIS_SEL_MASK
fxls896x_acceldata_t rawData
#define FXLS896x_SENS_CONFIG1_FSR_16G
int32_t perform_selftest(fxls896x_i2c_sensorhandle_t fxls896xDriver, fxls896x_selftest_t *selftest)
Function to perform FXLS896x self test.
This structure defines variables to compute self-test output change (STOC) and self-test offset (STOF...
#define __END_WRITE_DATA__
typedef int32_t(DATA_FORMAT_Append_t))(void *pData
The interface function to append the data on the formated stream.
const registerreadlist_t FXLS896x_ALL_REG_READ[]
FXLS896x register list to read all registers.
FMSTR_TSA_TABLE_BEGIN(main_table)
Target Side Addressable (TSA) table created for this application.
fxls896x_selftest_t selftest
This structure defines the fxls896x raw data buffer.
#define FXLS896x_SENS_CONFIG1_ST_POL_MASK
#define I2C_S_SIGNAL_EVENT
void fxls896x_isr_callback(void *pUserData)
ISR for FXLS896x interrupt source event.
#define FXLS896x_SENS_CONFIG1_ST_AXIS_SEL_EN_Z
const registerwritelist_t cFxls896xSTXN[]
Register settings for Self-Test in X Axis (Negative polarity).
const registerreadlist_t cFxls896xOutputNormal[]
Address of Raw Accel Data in Normal Mode.
#define FXLS896x_SENS_CONFIG1_ST_POL_NEGATIVE
const registerreadlist_t cFXLS896x_int_src[]
Prepare the register read for INT Status Register.
#define BOARD_BootClockRUN
This structure defines the fxls896x offset and noise calculation parameters.
const registerwritelist_t cFxls896xSTZP[]
Register settings for Self-Test in Z Axis (Positive polarity).
void(* registeridlefunction_t)(void *userParam)
This is the register idle function type.
#define FXLS896x_SENS_CONFIG1_FSR_MASK
void accel_off_noise(fxls896x_acceldata_t *rawData, fxls896x_offset_noise_t *offnoiseptr, float sens)
Function to measure accelerometer offset noise.
fxls896x_operation_type
This structure defines the fxls8962 host operation type.
GENERIC_DRIVER_GPIO Driver_GPIO_KSDK
GENERIC_DRIVER_GPIO * pGpioDriver
#define FXLS896x_INT_EN_DRDY_EN_MASK
This defines the sensor specific information for I2C.
uint32_t BOARD_SystickElapsedTime_us(int32_t *pStart)
Function to compute the Elapsed Time.
#define FXLS896x_SENS_CONFIG1_ST_AXIS_SEL_EN_Y
int32_t FXLS896x_I2C_Configure(fxls896x_i2c_sensorhandle_t *pSensorHandle, const registerwritelist_t *pRegWriteList)
The interface function to configure he sensor.
#define __END_READ_DATA__
int main(void)
Main function.
int32_t FXLS896x_I2C_ReadData(fxls896x_i2c_sensorhandle_t *pSensorHandle, const registerreadlist_t *pReadList, uint8_t *pBuffer)
The interface function to read the sensor data.
const registerwritelist_t cFxls896xSTYN[]
Register settings for Self-Test in Y Axis (Negative polarity).
#define FXLS896x_SENS_CONFIG2_ANIC_TEMP_MASK
void selftest_init(fxls896x_selftest_t *selftest)
Function to initialize FXLS896x self test metadata.
int32_t apply_register_read(fxls896x_i2c_sensorhandle_t fxls896xDriver, uint8_t offset, uint8_t *value)
Function to apply FXLS896x register read operation.
fxls896x_i2c_sensorhandle_t fxls896xDriver
void FXLS896x_I2C_SetIdleTask(fxls896x_i2c_sensorhandle_t *pSensorHandle, registeridlefunction_t idleTask, void *userParam)
: The interface function to set the I2C Idle Task.
const registerreadlist_t cFXLS896x_whoami[]
void(* toggle_pin)(pinID_t aPinId)
int32_t update_dropdown_selection(fxls896x_allregs_t *registers, uint8_t caller)
Function to update dropdown selection.
#define FXLS896x_NUM_REGISTERS
uint8_t reg_addr[FXLS896x_NUM_REGISTERS]
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 offset_noise_init(fxls896x_offset_noise_t *offnoiseptr)
Function to initialize offset noise measurement.
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.
FMSTR_REC_BUFF recBuffCfg
gpioHandleKSDK_t GREEN_LED
#define I2C_S_DEVICE_INDEX
volatile bool bFxls896xIntFlag
const registerwritelist_t cFxls896xConfigNormal[]
Defines the register write list to configure FXLS896x in Interrupt mode.
fxls896x_allregs_t registers
void BOARD_InitDebugConsole(void)
#define FXLS896x_SENS_CONFIG1_ST_AXIS_SEL_DISABLED
enum fxls896x_operation_type fxls896x_operation_type_t
This structure defines the fxls896x host operation type.
void BOARD_InitPins(void)
Configures pin routing and optionally pin electrical features.
#define FXLS896x_SENS_CONFIG1_ST_AXIS_SEL_EN_X
uint8_t trigger_accel_offnoise
const registerwritelist_t cFxls896xSTZN[]
Register settings for Self-Test in Z Axis (Negative polarity).
#define FXLS896x_INT_EN_DRDY_EN_EN
#define FXLS896x_SENS_CONFIG3_WAKE_ODR_MASK
uint8_t readall_value[FXLS896x_NUM_REGISTERS]
This structure defines the fxls8962 raw data buffer.
uint8_t byte_data[sizeof(sensor_data)]