GOOD STS_R1D with low power and accurate distance
This commit is contained in:
parent
9377c95534
commit
2f98207a96
|
@ -106,7 +106,7 @@
|
|||
|
||||
#define MajorVer 24U
|
||||
#define MinorVer 05U
|
||||
#define SubMinorVer 22U
|
||||
#define SubMinorVer 23U
|
||||
#define FirmwareVersion 3U
|
||||
#define YUNHORN_STS_MAX_NVM_CFG_SIZE 64U
|
||||
#define YUNHORN_STS_AC_CODE_SIZE 20U
|
||||
|
|
|
@ -67,9 +67,12 @@ void MX_GPIO_Init(void)
|
|||
|LED3_Pin, GPIO_PIN_RESET);
|
||||
#endif
|
||||
/*Configure GPIO pin Output Level */
|
||||
#if defined(TOF_2)
|
||||
#if defined(TOF_1)
|
||||
HAL_GPIO_WritePin(TOF_C_XSHUT_GPIO_Port, TOF_C_XSHUT_Pin, GPIO_PIN_SET);
|
||||
#endif
|
||||
#if defined(TOF_2)
|
||||
HAL_GPIO_WritePin(TOF_L_XSHUT_GPIO_Port, TOF_L_XSHUT_Pin, GPIO_PIN_SET);
|
||||
#endif
|
||||
#if defined(STM32WL55xx)
|
||||
/*Configure GPIO pins : PBPin PBPin PBPin */
|
||||
GPIO_InitStruct.Pin = LED1_Pin|LED2_Pin|LED3_Pin;
|
||||
|
@ -115,6 +118,7 @@ void MX_GPIO_Init(void)
|
|||
GPIO_InitStruct.Pin = TOF_C_INT_Pin;
|
||||
GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
|
||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||
HAL_GPIO_Init(TOF_C_INT_GPIO_Port, &GPIO_InitStruct);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -116,9 +116,9 @@ int main(void)
|
|||
MX_LoRaWAN_Init();
|
||||
|
||||
/* USER CODE BEGIN 2 */
|
||||
HAL_UART_DeInit(&huart2);
|
||||
//HAL_UART_DeInit(&huart2);
|
||||
|
||||
vcom_DeInit();
|
||||
//vcom_DeInit();
|
||||
//HAL_Delay(3000);
|
||||
|
||||
|
||||
|
|
|
@ -81,6 +81,12 @@ const struct UTIL_LPM_Driver_s UTIL_PowerDriver =
|
|||
void PWR_EnterOffMode(void)
|
||||
{
|
||||
/* USER CODE BEGIN EnterOffMode_1 */
|
||||
PME_OFF;
|
||||
HAL_GPIO_DeInit(GPIOA,GPIO_PIN_All);
|
||||
HAL_GPIO_DeInit(GPIOB,GPIO_PIN_All);
|
||||
HAL_GPIO_DeInit(GPIOC,GPIO_PIN_All);
|
||||
HAL_SuspendTick();
|
||||
HAL_PWR_EnterSTANDBYMode();
|
||||
|
||||
/* USER CODE END EnterOffMode_1 */
|
||||
}
|
||||
|
@ -88,7 +94,8 @@ void PWR_EnterOffMode(void)
|
|||
void PWR_ExitOffMode(void)
|
||||
{
|
||||
/* USER CODE BEGIN ExitOffMode_1 */
|
||||
|
||||
HAL_ResumeTick();
|
||||
return;
|
||||
/* USER CODE END ExitOffMode_1 */
|
||||
}
|
||||
|
||||
|
@ -129,12 +136,12 @@ void PWR_ExitStopMode(void)
|
|||
SRAM ctrls, DMAx, DMAMux, AES, RNG, HSEM */
|
||||
|
||||
/* Resume not retained USARTx and DMA */
|
||||
vcom_Resume(); //DON'T REMOVE THIS, KKEP LOW POWER
|
||||
//vcom_Resume(); //DON'T REMOVE THIS, KKEP LOW POWER
|
||||
/* USER CODE BEGIN ExitStopMode_2 */
|
||||
MX_GPIO_Init();
|
||||
MX_DMA_Init();
|
||||
MX_I2C2_Init();
|
||||
PME_ON;
|
||||
//PME_ON;
|
||||
/* USER CODE END ExitStopMode_2 */
|
||||
}
|
||||
|
||||
|
|
|
@ -120,7 +120,7 @@ void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
|
|||
//GPIO_InitStruct.Alternate = GPIO_AF7_USART2;
|
||||
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||
|
||||
|
||||
#if 0
|
||||
/* USART2 DMA Init */
|
||||
/* USART2_TX Init */
|
||||
hdma_usart2_tx.Instance = DMA1_Channel7;
|
||||
|
@ -136,7 +136,7 @@ void HAL_UART_MspInit(UART_HandleTypeDef* uartHandle)
|
|||
{
|
||||
Error_Handler();
|
||||
}
|
||||
|
||||
#endif
|
||||
#ifdef STM32WL55xx
|
||||
if (HAL_DMA_ConfigChannelAttributes(&hdma_usart2_tx, DMA_CHANNEL_NPRIV) != HAL_OK)
|
||||
{
|
||||
|
|
|
@ -808,7 +808,7 @@ static void SendTxData(void)
|
|||
|
||||
//UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_YunhornSTSEventP6), CFG_SEQ_Prio_0);
|
||||
#if defined(YUNHORN_STS_R0_ENABLED)||defined(YUNHORN_STS_R5_ENABLED)
|
||||
UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_YunhornSTSEventP4), CFG_SEQ_Prio_0);
|
||||
//UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_YunhornSTSEventP4), CFG_SEQ_Prio_0);
|
||||
|
||||
STS_R0_SENSOR_Read(&r0_data);
|
||||
//r0_data.battery_mV = batteryLevelmV;
|
||||
|
@ -916,6 +916,7 @@ static void OnTxTimerEvent(void *context)
|
|||
|
||||
/* USER CODE END OnTxTimerEvent_1 */
|
||||
//upload_message_timer =1U;
|
||||
UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_YunhornSTSEventP4), CFG_SEQ_Prio_0);
|
||||
UTIL_SEQ_SetTask((1 << CFG_SEQ_Task_LoRaSendOnTxTimerOrButtonEvent), CFG_SEQ_Prio_0);
|
||||
|
||||
/*Wait for next tx slot*/
|
||||
|
@ -1455,7 +1456,7 @@ void USER_APP_AUTO_RESPONDER_Parse(char *tlv_buf, size_t tlv_buf_size)
|
|||
|
||||
} else if ((char)tlv_buf[CFG_CMD3] == 'S') { // Self Function Testing "YZS"
|
||||
i=0;
|
||||
memset(outbuf,sizeof(outbuf),0x30);
|
||||
memset(outbuf,0x0,sizeof(outbuf));
|
||||
|
||||
STS_SENSOR_Function_Test_Process();
|
||||
|
||||
|
@ -1484,7 +1485,7 @@ void USER_APP_AUTO_RESPONDER_Parse(char *tlv_buf, size_t tlv_buf_size)
|
|||
STS_SENSOR_Distance_Test_Process();
|
||||
|
||||
i=0;
|
||||
memset(outbuf,sizeof(outbuf),0x30);
|
||||
memset(outbuf,0x0,sizeof(outbuf));
|
||||
outbuf[i++] = (uint8_t)'D';
|
||||
outbuf[i++] = (uint8_t)sts_mtmcode1;
|
||||
outbuf[i++] = (uint8_t)sts_mtmcode2;
|
||||
|
@ -1557,7 +1558,7 @@ void USER_APP_AUTO_RESPONDER_Parse(char *tlv_buf, size_t tlv_buf_size)
|
|||
uint8_t cfg_in_nvm[YUNHORN_STS_MAX_NVM_CFG_SIZE]="";
|
||||
OnRestoreSTSCFGContextRequest((uint8_t *)cfg_in_nvm);
|
||||
i=0;
|
||||
memset(outbuf,sizeof(outbuf),0x30);
|
||||
memset(outbuf,0x0,sizeof(outbuf));
|
||||
|
||||
outbuf[i++] = (uint8_t) 'C';
|
||||
outbuf[i++] = (uint8_t) cfg_in_nvm[NVM_MTM1]; //MTM Code
|
||||
|
@ -2165,7 +2166,7 @@ void STS_SENSOR_Function_Test_Process(void)
|
|||
|
||||
#endif
|
||||
}
|
||||
memset((void*)outbuf,sizeof(outbuf),0x30);
|
||||
memset((void*)outbuf,0x0,sizeof(outbuf));
|
||||
memcpy((void*)outbuf, tstbuf, i);
|
||||
|
||||
STS_SENSOR_Upload_Message(LORAWAN_USER_APP_CTRL_REPLY_PORT, i, outbuf);
|
||||
|
|
|
@ -32,6 +32,11 @@
|
|||
<nature>org.eclipse.cdt.managedbuilder.core.ScannerConfigNature</nature>
|
||||
</natures>
|
||||
<linkedResources>
|
||||
<link>
|
||||
<name>Doc/as923_jp_decoder.js</name>
|
||||
<type>1</type>
|
||||
<locationURI>copy_PARENT/as923_jp_decoder.js</locationURI>
|
||||
</link>
|
||||
<link>
|
||||
<name>Doc/readme.txt</name>
|
||||
<type>1</type>
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
/** @ingroup VL53L0X_config
|
||||
* @{*/
|
||||
|
||||
#define MAX_TOF_COUNT 3
|
||||
#define MAX_TOF_COUNT 2
|
||||
|
||||
#ifndef VL53L0X_HAVE_UART
|
||||
/**
|
||||
|
@ -134,7 +134,7 @@ extern void XNUCLEO53L1A1_USART2_UART_Init(void);
|
|||
*/
|
||||
#define VL53L0X_GPIO1_C_OPTION 1
|
||||
#endif
|
||||
|
||||
#if 0
|
||||
/* ############ FOR SHARED GPIO1 INTR TO MCU ###### */
|
||||
#define VL53L0X_GPIO1_C_GPIO_PORT GPIOA
|
||||
#define VL53L0X_GPIO1_C_CLK_ENABLE __GPIOA_CLK_ENABLE
|
||||
|
@ -151,7 +151,23 @@ extern void XNUCLEO53L1A1_USART2_UART_Init(void);
|
|||
#define VL53L0X_GPIO1_R_GPIO_PIN GPIO_PIN_10
|
||||
#define VL53L0X_GPIO1_R_INTx EXTI15_10_IRQn
|
||||
/* ############ FOR SHARED GPIO1 INTR TO MCU ###### */
|
||||
#endif
|
||||
/* ############ FOR SHARED GPIO1 INTR TO MCU ###### */
|
||||
#define VL53L0X_GPIO1_C_GPIO_PORT GPIOB
|
||||
#define VL53L0X_GPIO1_C_CLK_ENABLE __GPIOB_CLK_ENABLE
|
||||
#define VL53L0X_GPIO1_C_GPIO_PIN GPIO_PIN_3
|
||||
#define VL53L0X_GPIO1_C_INTx EXTI3_IRQn
|
||||
|
||||
#define VL53L0X_GPIO1_L_GPIO_PORT GPIOB
|
||||
#define VL53L0X_GPIO1_L_CLK_ENABLE __GPIOB_CLK_ENABLE
|
||||
#define VL53L0X_GPIO1_L_GPIO_PIN GPIO_PIN_3
|
||||
#define VL53L0X_GPIO1_L_INTx EXTI3_IRQn
|
||||
|
||||
#define VL53L0X_GPIO1_R_GPIO_PORT GPIOB
|
||||
#define VL53L0X_GPIO1_R_CLK_ENABLE __GPIOB_CLK_ENABLE
|
||||
#define VL53L0X_GPIO1_R_GPIO_PIN GPIO_PIN_3
|
||||
#define VL53L0X_GPIO1_R_INTx EXTI3_IRQn
|
||||
/* ############ FOR SHARED GPIO1 INTR TO MCU ###### */
|
||||
/** @} */ /* defgroup L53L1A1_GPIO1_MAP */
|
||||
|
||||
#ifndef XNUCLEO53L1A1_TRACE
|
||||
|
|
|
@ -130,7 +130,7 @@ void STS_R0_SENSOR_Read(STS_R0_SensorDataTypeDef *r0_data)
|
|||
|
||||
r0_data->distance_mm = (uint16_t)sts_tof_distance_data[0];
|
||||
r0_data->distance1_mm = (uint16_t)sts_tof_distance_data[1];
|
||||
r0_data->distance2_mm = (uint16_t)sts_tof_distance_data[2];
|
||||
// r0_data->distance2_mm = (uint16_t)sts_tof_distance_data[2];
|
||||
#ifdef ROCTEC_R5
|
||||
r0_data->distance1_mm = sts_tof_distance_data[0]+sts_tof_distance_data[1]+sts_tof_distance_data[2];
|
||||
#endif
|
||||
|
|
|
@ -85,7 +85,7 @@ int nDevMask=0;
|
|||
|
||||
int nSensorPresent;
|
||||
|
||||
volatile int sts_tof_distance_data[MAX_TOF_COUNT]={0,0,0};
|
||||
volatile int sts_tof_distance_data[MAX_TOF_COUNT]={0x0};
|
||||
extern volatile uint8_t sensor_data_ready;
|
||||
|
||||
VL53L0X_Dev_t VL53L0XDevs[]={
|
||||
|
@ -135,7 +135,7 @@ int sts_tof_vl53l0x_DetectSensors(void)
|
|||
|
||||
for (i=0; i < MAX_TOF_COUNT; i++) {
|
||||
XWL55_WLE5_53L0X_ResetId(i,0);
|
||||
//XWL55_WLE5_53L0X_SetIntrStateId(0,i);
|
||||
XWL55_WLE5_53L0X_SetIntrStateId(1,i);
|
||||
}
|
||||
|
||||
/* detect all sensors (even on-board)*/
|
||||
|
@ -343,6 +343,8 @@ void sts_tof_vl53l0x_Sensor_SetNewRange(VL53L0X_Dev_t *pDev, VL53L0X_RangingMeas
|
|||
/* USER CODE END 0 */
|
||||
void STS_TOF250_Range_Process(void)
|
||||
{
|
||||
#ifdef TOF_3
|
||||
|
||||
#define I2C_TIME_OUT_BASE 10
|
||||
#define I2C_TIME_OUT_BYTE 1
|
||||
int status;
|
||||
|
@ -350,8 +352,10 @@ void STS_TOF250_Range_Process(void)
|
|||
int i2c_time_out = I2C_TIME_OUT_BASE + count*I2C_TIME_OUT_BYTE;
|
||||
|
||||
sensor_data_ready = 0 ;
|
||||
|
||||
sts_tof_distance_data[0] = 0;
|
||||
sts_tof_distance_data[1] = 0;
|
||||
|
||||
sts_tof_distance_data[2] = 0;
|
||||
|
||||
status = HAL_I2C_Master_Receive(&hi2c2, TOF250_I2C_ADDR, pdata, count, i2c_time_out);
|
||||
|
@ -362,11 +366,13 @@ void STS_TOF250_Range_Process(void)
|
|||
APP_LOG(TS_OFF, VLEVEL_H, "\r\n## Measured Range: \r\nTOF #0 = %4u mm, \r\nTOF #1 = %4u mm, \r\nTOF #2 = %4u mm\r\n",
|
||||
(int)sts_tof_distance_data[0],(int)sts_tof_distance_data[1],(int)sts_tof_distance_data[2]);
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
void STS_TOF_VL53L0X_Range_Process(void)
|
||||
{
|
||||
int status=0, i;
|
||||
RangingConfig_e RangingConfig = LONG_RANGE; //HIGH_ACCURACY; //LONG_RANGE;
|
||||
RangingConfig_e RangingConfig = HIGH_ACCURACY; //HIGH_ACCURACY; //LONG_RANGE;
|
||||
XWL55_WLE5_53L0X_Init();
|
||||
if ((nDevMask ==0) || (nSensorPresent ==0))
|
||||
{
|
||||
|
@ -375,7 +381,10 @@ void STS_TOF_VL53L0X_Range_Process(void)
|
|||
}
|
||||
sts_tof_distance_data[0] = 0;
|
||||
sts_tof_distance_data[1] = 0;
|
||||
|
||||
#ifdef TOF_3
|
||||
sts_tof_distance_data[2] = 0;
|
||||
#endif
|
||||
|
||||
if (nSensorPresent > 0)
|
||||
{
|
||||
|
@ -409,12 +418,12 @@ void STS_TOF_VL53L0X_Range_Process(void)
|
|||
// ########## 1) return status ==0,
|
||||
// ########## 2) and ranging status for valid ranging value !!!!!!!!!!!!!!!!!
|
||||
}
|
||||
HAL_Delay(1);
|
||||
HAL_Delay(10);
|
||||
} while ((RangingMeasurementData.RangeStatus != 0)&&(rep <10));
|
||||
//sts_tof_distance_data[i] = (RangingMeasurementData.RangeStatus!=0)?STS_MAX_L0_RANGE:VL53L0XDevs[i].LeakyRange;
|
||||
}
|
||||
|
||||
HAL_Delay(5);
|
||||
HAL_Delay(30);
|
||||
} // for i < MAX_TOF_COUNT
|
||||
|
||||
if (sensor_data_ready != 0) {
|
||||
|
|
|
@ -0,0 +1,126 @@
|
|||
Decode decodes an array of bytes into an object.
|
||||
- fPort contains the LoRaWAN fPort number
|
||||
- bytes is an array of bytes, e.g. [225, 230, 255, 0]
|
||||
- variables contains the device variables e.g. {calibration 3.5 } (both the key value are of type string)
|
||||
The function must return an object, e.g. {temperature 22.5 }
|
||||
function Decode(fPort, bytes, variables) {
|
||||
O5 Door contact sensor
|
||||
if (fPort === 4) {
|
||||
return [
|
||||
{
|
||||
led_state bytes[0] === 0 Off On,
|
||||
mtm_code_1 bytes[1],
|
||||
mtm_code_2 bytes[2],
|
||||
hw_code bytes[3],
|
||||
battery_level bytes[4] + %,
|
||||
size_value bytes[5],
|
||||
HALL_1_state bytes[6] === 1 Door_Open Door_Close,
|
||||
HALL_2_state bytes[7] === 1 Door_Open Door_Close,
|
||||
}
|
||||
];
|
||||
}
|
||||
heart - beat of O5
|
||||
else if (fPort === 5) {
|
||||
return [
|
||||
{
|
||||
led_state(bytes[0] & 0x7f) === 0 Off On,
|
||||
battery_level bytes[4] + %,
|
||||
}
|
||||
];
|
||||
}
|
||||
R4 soapsanitizer sensor
|
||||
else if (fPort === 7) {
|
||||
return [
|
||||
{
|
||||
led_state bytes[0] === 0 Off On,
|
||||
mtm_code_1 bytes[1],
|
||||
mtm_code_2 bytes[2],
|
||||
hw_code bytes[3],
|
||||
battery_level bytes[4] + %,
|
||||
size_value bytes[5],
|
||||
measure_tech bytes[6] === 0 Capacitive Other,
|
||||
liquid_level_event bytes[7] === 0 Liquid Detected No Liquid,
|
||||
}
|
||||
];
|
||||
}
|
||||
R4 soapsanitizer heart - beat
|
||||
else if (fPort === 8) {
|
||||
return [
|
||||
{
|
||||
led_state(bytes[0] & 0x7f) === 0 Off On,
|
||||
battery_level bytes[1] + %,
|
||||
}
|
||||
];
|
||||
}
|
||||
R1D dual roll toilet paper sensor
|
||||
else if (fPort === 57) {
|
||||
return [
|
||||
{
|
||||
led_state bytes[0] === 0 Off On,
|
||||
mtm_code_1 bytes[1],
|
||||
mtm_code_2 bytes[2],
|
||||
hw_code bytes[3],
|
||||
battery_level bytes[4] + %,
|
||||
size_value bytes[5],
|
||||
distance_1_mm bytes[6] 8 bytes[7],
|
||||
distance_2_mm bytes[8] 8 bytes[9],
|
||||
distance_unit mm,
|
||||
}
|
||||
];
|
||||
}
|
||||
R1D, Heart - beat
|
||||
else if (fPort === 58) {
|
||||
return [
|
||||
{
|
||||
led_state(bytes[0] & 0x7f) === 0 Off On,
|
||||
battery_level bytes[4] + %,
|
||||
}
|
||||
];
|
||||
}
|
||||
R5 waste bin sensor
|
||||
else if (fPort === 11) {
|
||||
return [
|
||||
{
|
||||
led_state bytes[0] === 0 Off On,
|
||||
mtm_code_1 bytes[1],
|
||||
mtm_code_2 bytes[2],
|
||||
hw_code bytes[3],
|
||||
battery_level bytes[4] + %,
|
||||
size_value bytes[5],
|
||||
distance_1_mm(bytes[6] 8 bytes[7]),
|
||||
distance_2_mmbytes[8]256 + bytes[9],
|
||||
distance_3_mmbytes[10]256 + bytes[11],
|
||||
distance_unit mm,
|
||||
}
|
||||
];
|
||||
}
|
||||
R5, Heart - beat
|
||||
else if (fPort === 12) {
|
||||
return [
|
||||
{
|
||||
led_state(bytes[0] & 0x7f) === 0 Off On,
|
||||
battery_level bytes[4] + %,
|
||||
}
|
||||
];
|
||||
}
|
||||
UPLINK, RFAC
|
||||
else if (fPort === 1) {
|
||||
var data = {};
|
||||
data.length = bytes.length;
|
||||
if (bytes[0] === 0x59) {
|
||||
if (bytes[1] === 0x44) {
|
||||
data.Uplink_interval = (bytes[2] - 0x30) 60 + (bytes[3] - 0x30);
|
||||
data.Uplink_interval_unit = String.fromCharCode(bytes[4]);
|
||||
}
|
||||
else if (bytes[1] === 0x53) {
|
||||
data.Heart_Beat_interval = (bytes[2] - 0x30) 60 + (bytes[3] - 0x30);
|
||||
data.Heart_Beat_interval_unit = String.fromCharCode(bytes[4]);
|
||||
}
|
||||
}
|
||||
else if ((bytes[0] === 0x41) && (bytes[1] === 0x43)) {
|
||||
data.RFAC = OK;
|
||||
}
|
||||
|
||||
return { Yunhorn_SmarToilets_data data };
|
||||
}
|
||||
}
|
Loading…
Reference in New Issue