From de909e938404458aaf22f904f91784fb4f572e87 Mon Sep 17 00:00:00 2001 From: lin little <1325573574@qq.com> Date: Tue, 4 Jun 2024 14:13:39 +0800 Subject: [PATCH] Update SN50v3-LB v1.3 ---v1.3 1.Added Mode 11 TMP117 temperature sensor. 2.Fixed the issue that some DS18B20 cannot be recognized. ---v1.2 1.Add work mode 10 of PWM input capture and output mode. --- Drivers/sensor/TMP117_I2C.c | 388 ++++++++++++++++++ Drivers/sensor/TMP117_I2C.h | 108 +++++ Drivers/sensor/bsp.c | 152 ++++++- Drivers/sensor/bsp.h | 7 + Drivers/sensor/ds18b20.c | 6 +- Drivers/sensor/pwm.c | 166 ++++++++ Drivers/sensor/pwm.h | 91 ++++ .../DRAGINO-LRWAN-AT/inc/command.h | 1 + .../DRAGINO-LRWAN-AT/inc/lora_config.h | 13 + .../DRAGINO-LRWAN-AT/inc/version.h | 2 +- .../DRAGINO-LRWAN-AT/project.uvoptx | 86 ++-- .../DRAGINO-LRWAN-AT/project.uvprojx | 23 +- .../DRAGINO-LRWAN-AT/src/command.c | 55 ++- .../DRAGINO-LRWAN-AT/src/lora_app.c | 14 +- .../Applications/DRAGINO-LRWAN-AT/src/main.c | 75 +++- .../DRAGINO-LRWAN-AT/src/tremo_it.c | 21 + 16 files changed, 1161 insertions(+), 47 deletions(-) create mode 100644 Drivers/sensor/TMP117_I2C.c create mode 100644 Drivers/sensor/TMP117_I2C.h create mode 100644 Drivers/sensor/pwm.c create mode 100644 Drivers/sensor/pwm.h diff --git a/Drivers/sensor/TMP117_I2C.c b/Drivers/sensor/TMP117_I2C.c new file mode 100644 index 0000000..c9fe876 --- /dev/null +++ b/Drivers/sensor/TMP117_I2C.c @@ -0,0 +1,388 @@ +/** + ****************************************************************************** + * @file + * @author Dragino + * @version + * @date + * @brief Main program body + ****************************************************************************** + * @attention + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + +/* Includes ------------------------------------------------------------------*/ +#include +#include "tremo_rcc.h" +#include "tremo_gpio.h" +#include "TMP117_I2C.h" +#include "tremo_delay.h" + +#define GPIO_PORT_TMP117_I2C GPIOA +#define TMP117_I2C_SCL_PIN GPIO_PIN_14 +#define TMP117_I2C_SDA_PIN GPIO_PIN_15 + +#define TMP117_I2C_SCL_1 gpio_write(GPIO_PORT_TMP117_I2C, TMP117_I2C_SCL_PIN, 1) +#define TMP117_I2C_SCL_0 gpio_write(GPIO_PORT_TMP117_I2C, TMP117_I2C_SCL_PIN, 0) + +#define TMP117_I2C_SDA_1 gpio_write(GPIO_PORT_TMP117_I2C, TMP117_I2C_SDA_PIN, 1) /* SDA = 1 */ +#define TMP117_I2C_SDA_0 gpio_write(GPIO_PORT_TMP117_I2C, TMP117_I2C_SDA_PIN, 0) /* SDA = 0 */ + +#define TMP117_I2C_SDA_READ() gpio_read(GPIO_PORT_TMP117_I2C, TMP117_I2C_SDA_PIN) + +extern bool tmp117_connect_status; + +void TMP117_I2C_GPIO_MODE_Config(void) +{ + rcc_enable_peripheral_clk(RCC_PERIPHERAL_GPIOC, true); + + gpio_init(GPIO_PORT_TMP117_I2C, TMP117_I2C_SCL_PIN, GPIO_MODE_OUTPUT_OD_HIZ); + gpio_init(GPIO_PORT_TMP117_I2C, TMP117_I2C_SDA_PIN, GPIO_MODE_OUTPUT_OD_HIZ); +} + +uint8_t TMP117_I2C_Write_Byte(uint8_t addr,uint8_t data) +{ + TMP117_I2C_Start(); + TMP117_I2C_SendByte((addr<<1)|0); + if(TMP117_I2C_WaitAck()) + { + TMP117_I2C_Stop(); + return 1; + } + + TMP117_I2C_SendByte(data); + if(TMP117_I2C_WaitAck()) + { + TMP117_I2C_Stop(); + return 1; + } + TMP117_I2C_Stop(); + return 0; +} + +uint8_t TMP117_I2C_Read_Byte(uint8_t addr) +{ + uint8_t res; + + TMP117_I2C_Start(); + TMP117_I2C_SendByte((addr<<1)|1); + TMP117_I2C_WaitAck(); + res=TMP117_I2C_ReadByte(0); + TMP117_I2C_Stop(); + return res; +} + +uint8_t TMP117_I2C_Write_Len(uint8_t addr,uint8_t reg,uint8_t len,uint8_t *buf) +{ + uint8_t i; + TMP117_I2C_Start(); + TMP117_I2C_SendByte((addr<<1)|0); + if(TMP117_I2C_WaitAck()) + { + TMP117_I2C_Stop(); + return 1; + } + TMP117_I2C_SendByte(reg); + TMP117_I2C_WaitAck(); + for(i=0;i250) + { + TMP117_I2C_Stop(); + return 1; + } + } + + TMP117_I2C_SCL_0; + TMP117_I2C_Delay(); + return 0; +} +void TMP117_I2C_SendByte(uint8_t Byte) +{ + uint8_t i; + TMP117_I2C_SDA_OUT(); + TMP117_I2C_SCL_0; + for (i = 0; i < 8; i++) + { + if (Byte & 0x80) + { + TMP117_I2C_SDA_1; + } + else + { + TMP117_I2C_SDA_0; + } + TMP117_I2C_Delay(); + TMP117_I2C_SCL_1; + TMP117_I2C_Delay(); + TMP117_I2C_Delay(); + TMP117_I2C_SCL_0; +// TMP117_I2C_SDA_1; + Byte <<= 1; + TMP117_I2C_Delay(); + } +} +uint8_t TMP117_I2C_ReadByte(unsigned char ack) +{ + uint8_t i; + uint8_t value; + TMP117_I2C_SDA_IN(); + value = 0; + for (i = 0; i < 8; i++) + { + value <<= 1; + TMP117_I2C_SCL_0; + TMP117_I2C_Delay(); + TMP117_I2C_Delay(); + TMP117_I2C_SCL_1; + + if (TMP117_I2C_SDA_READ()) + { + value++; + } + TMP117_I2C_Delay(); + } + + if (!ack) + { + TMP117_I2C_NAck(); + } + else + { + TMP117_I2C_Ack(); + } + + return value; +} + +void TMP117_I2C_Ack(void) +{ + TMP117_I2C_SCL_0; + TMP117_I2C_SDA_OUT(); + TMP117_I2C_SDA_0; + TMP117_I2C_Delay(); + TMP117_I2C_SCL_1; + TMP117_I2C_Delay(); + TMP117_I2C_SCL_0; +} + +void TMP117_I2C_NAck(void) +{ + TMP117_I2C_SCL_0; + TMP117_I2C_SDA_OUT(); + TMP117_I2C_SDA_1; + TMP117_I2C_Delay(); + TMP117_I2C_SCL_1; + TMP117_I2C_Delay(); + TMP117_I2C_SCL_0; +} + +uint16_t TMP117_Set_Config(void) +{ + uint8_t data[2] = {0x0C, 0x20}; + uint8_t read_status=0,check_number=0; + + TMP117_I2C_GPIO_MODE_Config(); + + do + { + read_status=1; + check_number++; + if(TMP117_I2C_Write_Len(0x48,0x01,2,data)==1) + { + read_status=0; + + delay_ms(20); + } + }while(read_status==0&&check_number<4); + + return 0; +} + +float get_tmp117_temp(void) +{ + short AD_code; + float current_temp; + uint8_t data[2] = {0x0C, 0x20}; + uint8_t read_status=0,check_number=0; + + do + { + read_status=1; + check_number++; + if(TMP117_I2C_Write_Len(0x48,0x01,2,data)==1) + { + read_status=0; + + delay_ms(20); + } + }while(read_status==0&&check_number<4); + + if(read_status==1) + { + delay_ms(130); + check_number=0; + do + { + read_status=1; + check_number++; + if(TMP117_I2C_Read_Len(0x48,0x00,2,data)==1) + { + read_status=0; + + delay_ms(20); + } + }while(read_status==0&&check_number<4); + } + + if(read_status==1) + { + tmp117_connect_status=1; + AD_code=(data[0]<<8)|data[1]; + + if(AD_code <0) + { + current_temp=-(~AD_code+1)*0.0078125; + } + else + current_temp=AD_code*0.0078125; + + if(current_temp>150) + { + tmp117_connect_status=0; + current_temp=150; + } + else if(current_temp<-55) + { + tmp117_connect_status=0; + current_temp=-55; + } + } + else + { + current_temp=327.67; + tmp117_connect_status=0; + } + + return current_temp; +} + +void TMP117_soft_reset(void) +{ + uint8_t data[2] = {0x0C, 0x22}; + uint8_t read_status=0,check_number=0; + + do + { + read_status=1; + check_number++; + if(TMP117_I2C_Write_Len(0x48,0x01,2,data)==1) + { + read_status=0; + + delay_ms(20); + } + }while(read_status==0&&check_number<4); + + delay_ms(20); +} + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Drivers/sensor/TMP117_I2C.h b/Drivers/sensor/TMP117_I2C.h new file mode 100644 index 0000000..727ceea --- /dev/null +++ b/Drivers/sensor/TMP117_I2C.h @@ -0,0 +1,108 @@ +/* + / _____) _ | | +( (____ _____ ____ _| |_ _____ ____| |__ + \____ \| ___ | (_ _) ___ |/ ___) _ \ + _____) ) ____| | | || |_| ____( (___| | | | +(______/|_____)_|_|_| \__)_____)\____)_| |_| + (C)2013 Semtech + +Description: contains all hardware driver + +License: Revised BSD License, see LICENSE.TXT file include in the project + +Maintainer: Miguel Luis and Gregory Cristian +*/ + /****************************************************************************** + * @file TMP117_I2C.h + * @author MCD Application Team + * @version V1.1.1 + * @date 01-June-2017 + * @brief contains all hardware driver + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __TMP117_I2C_H__ +#define __TMP117_I2C_H__ + +#ifdef __cplusplus + extern "C" { +#endif +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ +#include +#include +/* Exported constants --------------------------------------------------------*/ +/* External variables --------------------------------------------------------*/ +/* Exported macros -----------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/** + * @brief + * + * @note + * @retval None + */ +void TMP117_I2C_GPIO_MODE_Config(void); +void TMP117_I2C_delay(void); +void TMP117_I2C_Start(void); +void TMP117_I2C_Stop(void); +uint8_t TMP117_I2C_WaitAck(void); +void TMP117_I2C_NAck(void); +void TMP117_I2C_Ack(void); +void TMP117_I2C_SendByte(uint8_t _ucByte); +uint8_t TMP117_I2C_ReadByte(unsigned char ack); +uint8_t TMP117_I2C_Read_Len(uint8_t addr,uint8_t reg,uint8_t len,uint8_t *buf); +void TMP117_I2C_SDA_IN(void); +void TMP117_I2C_SDA_OUT(void); +uint8_t TMP117_I2C_Write_Byte(uint8_t addr,uint8_t data); +uint8_t TMP117_I2C_Read_Byte(uint8_t addr); +uint8_t TMP117_I2C_Write_Len(uint8_t addr,uint8_t reg,uint8_t len,uint8_t *buf); + +uint16_t TMP117_Set_Config(void); +float get_tmp117_temp(void); +void TMP117_soft_reset(void); + +#ifdef __cplusplus +} +#endif + +#endif /* __TMP117_I2C_H__ */ + +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/Drivers/sensor/bsp.c b/Drivers/sensor/bsp.c index 8cd908d..9b56015 100644 --- a/Drivers/sensor/bsp.c +++ b/Drivers/sensor/bsp.c @@ -14,6 +14,8 @@ #include "weight.h" #include "tfsensor.h" #include "ult.h" +#include "pwm.h" +#include "TMP117_I2C.h" /* Private typedef -----------------------------------------------------------*/ /* Private define ------------------------------------------------------------*/ @@ -27,6 +29,8 @@ #define VBAT_FACTOR 3.06f +bool tmp117_connect_status; +uint8_t icnumber=0; bool bh1750flags=0; uint8_t mode2_flag=0; static uint8_t flags=0; @@ -34,6 +38,9 @@ extern uint8_t workmode; extern uint8_t inmode,inmode2,inmode3; extern uint16_t power_5v_time; extern uint32_t count1,count2; +extern uint8_t pwm_timer; +extern uint16_t IC1[4],IC2[4]; +static float tmp117_temp_record=10; void BLE_power_Init(void) { @@ -164,6 +171,16 @@ void BSP_sensor_Init( void ) GPIO_EXTI4_IoInit(inmode2); GPIO_EXTI15_IoInit(inmode3); } + else if(workmode==11) + { + TMP117_I2C_GPIO_MODE_Config(); + get_tmp117_temp(); + if(tmp117_connect_status==1) + { + LOG_PRINTF(LL_DEBUG,"\n\rUse Sensor is TMP117\r\n"); + delay_ms(30); + } + } if((workmode!=3)||(workmode!=8)) { @@ -317,7 +334,7 @@ void BSP_sensor_Read( sensor_t *sensor_data , uint8_t message ,uint8_t mod_temp) sensor_data->count_pa8=count1; if(message==1) { - LOG_PRINTF(LL_DEBUG,"PA8 count:%u\r\n",(unsigned int)count1); + LOG_PRINTF(LL_DEBUG,"PA8_count:%u\r\n",(unsigned int)count1); delay_ms(20); } } @@ -352,18 +369,112 @@ void BSP_sensor_Read( sensor_t *sensor_data , uint8_t message ,uint8_t mod_temp) sensor_data->count_pa8=count1; if(message==1) { - LOG_PRINTF(LL_DEBUG,"PA8 count:%u\r\n",(unsigned int)count1); - LOG_PRINTF(LL_DEBUG,"PA4 count:%u\r\n",(unsigned int)count2); + LOG_PRINTF(LL_DEBUG,"PA8_count:%u\r\n",(unsigned int)count1); + LOG_PRINTF(LL_DEBUG,"PA4_count:%u\r\n",(unsigned int)count2); delay_ms(40); } } + else if(workmode==10) + { + sensor_data->temp1=DS18B20_Read(1,message); + POWER_open_time(power_5v_time); + sensor_data->ADC_4=ADC_Read(1,message); + sensor_data->in1=Digital_input_Read(3,message); + sensor_data->exit_pa8=Digital_input_Read(2,message); + + icnumber=0; + for(uint8_t y=0;y<4;y++) + { + IC1[y]=0; + IC2[y]=0; + } + gptimer_pwm_input_capture(pwm_timer); + if(pwm_timer==0) + { + delay_ms(500); + } + else + { + delay_ms(1500); + } + gptimer_pwm_Iodeinit(); + + if(middle_value(IC1)!=0) + { + sensor_data->pwm_freq = middle_value(IC1)+1; + } + else + { + sensor_data->pwm_freq = 0; + } + + if(middle_value(IC2)!=0) + { + sensor_data->pwm_duty = middle_value(IC2)+1; + } + else + { + sensor_data->pwm_duty = 0; + } + + if(message==1) + { + if(pwm_timer==0) + { + LOG_PRINTF(LL_DEBUG,"PWM_pulse_period: %d us\r\n",sensor_data->pwm_freq); + LOG_PRINTF(LL_DEBUG,"PWM_high_level_time: %d us\r\n",sensor_data->pwm_duty); + } + else + { + LOG_PRINTF(LL_DEBUG,"PWM_pulse_period: %d ms\r\n",sensor_data->pwm_freq); + LOG_PRINTF(LL_DEBUG,"PWM_high_level_time: %d ms\r\n",sensor_data->pwm_duty); + } + delay_ms(40); + } + } + else if(mod_temp==11) + { + sensor_data->temp1=DS18B20_Read(1,message); + TMP117_I2C_GPIO_MODE_Config(); + sensor_data->temp_tmp117=get_tmp117_temp(); + + if(sensor_data->temp_tmp117-tmp117_temp_record>20 || sensor_data->temp_tmp117-tmp117_temp_record<-20) + { + TMP117_soft_reset(); + sensor_data->temp_tmp117=get_tmp117_temp(); + } + + if(sensor_data->temp_tmp117!=327.67) + { + tmp117_temp_record=sensor_data->temp_tmp117; + } + + if(message==1) + { + if(sensor_data->temp_tmp117!=327.67) + { + LOG_PRINTF(LL_DEBUG,"TMP117_temp=%.2f\n\r",sensor_data->temp_tmp117); + } + else + { + LOG_PRINTF(LL_DEBUG,"TMP117_temp=NULL\n\r"); + } + } + POWER_open_time(power_5v_time); + sensor_data->ADC_4=ADC_Read(1,message); + sensor_data->in1=Digital_input_Read(3,message); + sensor_data->exit_pa8=Digital_input_Read(2,message); + } POWER_IoDeInit(); } uint16_t battery_voltage_measurement(void) { uint16_t bat_mv; - + + #if defined LB_LS + bat_mv=6*adc_in1_measurement(ADC_SOLAR_LEVEL_PORT,ADC_SOLAR_LEVEL_PIN,GPIO_SOLAR_BAT_CHANNEL); + #else gpio_set_iomux(ADC_BAT_OUTPUT_PORT, ADC_BAT_OUTPUT_PIN, 0); gpio_init(ADC_BAT_OUTPUT_PORT, ADC_BAT_OUTPUT_PIN, GPIO_MODE_OUTPUT_PP_LOW); @@ -373,7 +484,7 @@ uint16_t battery_voltage_measurement(void) gpio_set_iomux(ADC_BAT_OUTPUT_PORT, ADC_BAT_OUTPUT_PIN, 0); gpio_init(ADC_BAT_OUTPUT_PORT, ADC_BAT_OUTPUT_PIN, GPIO_MODE_ANALOG); - + #endif return bat_mv; } @@ -499,4 +610,35 @@ bool Digital_input_Read(uint8_t temp,uint8_t message) } return pin_status; } + +uint16_t middle_value(uint16_t value[]) +{ + uint16_t a,b,c,temp; + a = value[1]; + b = value[2]; + c = value[3]; + + if (a > b) + { + temp = a; + a = b; + b = temp; + } + + if (a > c) + { + temp = a; + a = c; + c = temp; + } + + if (b > c) + { + temp = b; + b = c; + c = temp; + } + + return b; +} /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/Drivers/sensor/bsp.h b/Drivers/sensor/bsp.h index b8534ce..e0b3964 100644 --- a/Drivers/sensor/bsp.h +++ b/Drivers/sensor/bsp.h @@ -94,6 +94,8 @@ typedef struct{ float temp_sht; float hum_sht; + + float temp_tmp117; uint16_t illuminance; @@ -109,6 +111,10 @@ typedef struct{ uint32_t count_pa8; + uint16_t pwm_freq; + + uint16_t pwm_duty; + /**more may be added*/ } sensor_t; @@ -129,6 +135,7 @@ float DS18B20_Read(uint8_t temp,uint8_t message); uint16_t ADC_Read(uint8_t temp,uint8_t message); bool Digital_input_Read(uint8_t temp,uint8_t message); uint16_t battery_voltage_measurement(void); +uint16_t middle_value(uint16_t value[]); /** * @brief sensor read. * diff --git a/Drivers/sensor/ds18b20.c b/Drivers/sensor/ds18b20.c index b8254b6..14ec2a1 100644 --- a/Drivers/sensor/ds18b20.c +++ b/Drivers/sensor/ds18b20.c @@ -89,17 +89,17 @@ void DS18B20_Mode_Out_PP(uint8_t num) if(num==1) { DOUT1_CLK_ENABLE(); - gpio_init(DOUT1_PORT, DOUT1_PIN, GPIO_MODE_OUTPUT_PP_HIGH); + gpio_init(DOUT1_PORT, DOUT1_PIN, GPIO_MODE_OUTPUT_PP_LOW); } else if(num==2) { DOUT2_CLK_ENABLE(); - gpio_init(DOUT2_PORT, DOUT2_PIN, GPIO_MODE_OUTPUT_PP_HIGH); + gpio_init(DOUT2_PORT, DOUT2_PIN, GPIO_MODE_OUTPUT_PP_LOW); } else if(num==3) { DOUT3_CLK_ENABLE(); - gpio_init(DOUT3_PORT, DOUT3_PIN, GPIO_MODE_OUTPUT_PP_HIGH); + gpio_init(DOUT3_PORT, DOUT3_PIN, GPIO_MODE_OUTPUT_PP_LOW); } } diff --git a/Drivers/sensor/pwm.c b/Drivers/sensor/pwm.c new file mode 100644 index 0000000..3278d2e --- /dev/null +++ b/Drivers/sensor/pwm.c @@ -0,0 +1,166 @@ + /****************************************************************************** + * @file pwm.c + * @author MCD Application Team + * @version V1.1.0 + * @date 17-April-2019 + * @brief manages the sensors on the application + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + + /* Includes ------------------------------------------------------------------*/ +#include "string.h" +#include "lora_config.h" +#include "pwm.h" +#include "tremo_timer.h" +#include "tremo_iwdg.h" +#include "tremo_delay.h" + +extern uint16_t IC1Value,IC2Value; + +void gptimer_pwm_output(uint16_t time,uint32_t freq_hz,uint8_t duty) +{ + uint16_t freq_temp=0; + uint16_t prese_temp=0; + uint32_t pulse_temp=0; + + if(((1000000/freq_hz)-1)<=65000) + { + prese_temp=23; //1us + freq_temp=(1000000/freq_hz)-1; + pulse_temp=(freq_temp+1)*duty/100; + } + else + { + prese_temp=23999; //1ms + freq_temp=(1000/freq_hz)-1; + pulse_temp=(freq_temp+1)*duty/100; + } + + PWM_RCC_ENABLE(); + PWM_CLK_ENABLE(); + gpio_set_iomux(PWM_PORT, PWM_PIN, 6); // TIMER1 CH0 + + timer_init_t timerx_init; + timer_oc_init_t oc_init; + + memset(&oc_init, 0, sizeof(oc_init)); + oc_init.oc_mode.oc0m_mode = TIMER_OC0M_PWM1; + oc_init.pulse = pulse_temp; + oc_init.high_level = true; + oc_init.oc_fast = false; + + timerx_init.prescaler = prese_temp; + timerx_init.counter_mode = TIMER_COUNTERMODE_UP; + timerx_init.period = freq_temp; + timerx_init.clock_division = TIMER_CKD_FPCLK_DIV1; + timerx_init.autoreload_preload = false; + + timer_config_pwm(TIMER1, &oc_init, &timerx_init, 0); + TIMER_ENABLE(); + + for(uint16_t i=0;i<=(uint16_t)(time/100);i++) + { + delay_ms(100); + if((i%99==0)&&(i!=0)) + { + iwdg_reload(); + } + } + + gptimer_pwm_Iodeinit(); +} + +void gptimer_pwm_input_capture(uint8_t pwmmd) +{ + uint16_t prese_temp=0; + uint16_t freq_temp=0; + + if(pwmmd==0) + { + prese_temp = 23; //1us + freq_temp = 50999; //51ms count reload + } + else + { + prese_temp = 23999; //1ms + freq_temp = 1099; //1100ms count reload + } + + IC1Value=0; + IC2Value=0; + PWM_RCC_ENABLE(); + PWM_CLK_ENABLE(); + gpio_set_iomux(PWM_PORT, PWM_PIN, 6); // TIMER1 CH0 + + timer_init_t timerx_init; + timerx_init.prescaler = prese_temp; + timerx_init.counter_mode = TIMER_COUNTERMODE_UP; + timerx_init.period = freq_temp; + timerx_init.clock_division = TIMER_CKD_FPCLK_DIV1; + timerx_init.autoreload_preload = false; + timer_init(TIMER1, &timerx_init); + + timer_config_ti(TIMER1, (uint32_t)TIMER_CC0P_RISING, TIMER_CC0S_INPUT_SAME, TIMER_IC0F_0, 0); + timer_config_ti(TIMER1, (uint32_t)TIMER_CC1P_FALLING, TIMER_CC1S_INPUT_NEAR, TIMER_IC1F_0, 1); + + timer_config_interrupt(TIMER1, TIMER_DIER_CC0IE, ENABLE); + timer_clear_status(TIMER1, TIMER_SR_CC0IF); + timer_config_ts(TIMER1, TIMER_TS_TI0FP0); + + TIMER1->SMCR &= (uint32_t) ~(uint32_t)0x07; + TIMER1->SMCR |= (uint32_t)TIMER_SMS_RESET; + + TIMER1->SMCR &= (uint32_t) ~(uint32_t)0x80; + TIMER1->SMCR |= (uint32_t)TIMER_MSM_SYNC; + + TIMER_ENABLE(); + NVIC_EnableIRQ(TIMER1_IRQn); + NVIC_SetPriority(TIMER1_IRQn, 2); +} + +void gptimer_pwm_Iodeinit(void) +{ + PWM_RCC_DISABLE(); + TIMER_DISABLE(); + gpio_set_iomux(PWM_PORT, PWM_PIN, 0); + gpio_init(PWM_PORT, PWM_PIN, GPIO_MODE_ANALOG); + timer_clear_status(TIMER1, TIMER_SR_CC0IF); + NVIC_DisableIRQ(TIMER1_IRQn); +} diff --git a/Drivers/sensor/pwm.h b/Drivers/sensor/pwm.h new file mode 100644 index 0000000..7a79cf7 --- /dev/null +++ b/Drivers/sensor/pwm.h @@ -0,0 +1,91 @@ +/* + / _____) _ | | +( (____ _____ ____ _| |_ _____ ____| |__ + \____ \| ___ | (_ _) ___ |/ ___) _ \ + _____) ) ____| | | || |_| ____( (___| | | | +(______/|_____)_|_|_| \__)_____)\____)_| |_| + (C)2013 Semtech + +Description: contains all hardware driver + +License: Revised BSD License, see LICENSE.TXT file include in the project + +Maintainer: Miguel Luis and Gregory Cristian +*/ + /****************************************************************************** + * @file pwm.h + * @author MCD Application Team + * @version V1.1.0 + * @date 17-April-2019 + * @brief contains all hardware driver + ****************************************************************************** + * @attention + * + *

© Copyright (c) 2017 STMicroelectronics International N.V. + * All rights reserved.

+ * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted, provided that the following conditions are met: + * + * 1. Redistribution of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. Neither the name of STMicroelectronics nor the names of other + * contributors to this software may be used to endorse or promote products + * derived from this software without specific written permission. + * 4. This software, including modifications and/or derivative works of this + * software, must execute solely and exclusively on microcontroller or + * microprocessor devices manufactured by or for STMicroelectronics. + * 5. Redistribution and use of this software other than as permitted under + * this license is void and will automatically terminate your rights under + * this license. + * + * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A + * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY + * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT + * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, + * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF + * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING + * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, + * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************** + */ + +/* Define to prevent recursive inclusion -------------------------------------*/ +#ifndef __PWM_H +#define __PWM_H + +#ifdef __cplusplus + extern "C" { +#endif +/* Includes ------------------------------------------------------------------*/ +/* Exported types ------------------------------------------------------------*/ + +/* Exported constants --------------------------------------------------------*/ +/* External variables --------------------------------------------------------*/ +/* Exported macros -----------------------------------------------------------*/ +/* Exported functions ------------------------------------------------------- */ +/** + * @brief + * + * @note + * @retval None + */ + +void gptimer_pwm_output(uint16_t time,uint32_t freq_hz,uint8_t duty); +void gptimer_pwm_input_capture(uint8_t pwmmd); +void gptimer_pwm_Iodeinit(void); + +#ifdef __cplusplus +} +#endif + +#endif + diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/inc/command.h b/Projects/Applications/DRAGINO-LRWAN-AT/inc/command.h index e119e04..09d1220 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/inc/command.h +++ b/Projects/Applications/DRAGINO-LRWAN-AT/inc/command.h @@ -75,6 +75,7 @@ #define AT_WEIGAP "+WEIGAP" #define AT_5VT "+5VT" #define AT_SETCNT "+SETCNT" +#define AT_PWMSET "+PWMSET" #define AT_SLEEP "+SLEEP" #define AT_CFG "+CFG" #define AT_UUID "+UUID" diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/inc/lora_config.h b/Projects/Applications/DRAGINO-LRWAN-AT/inc/lora_config.h index ccc8d1e..329ffe9 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/inc/lora_config.h +++ b/Projects/Applications/DRAGINO-LRWAN-AT/inc/lora_config.h @@ -21,6 +21,10 @@ extern "C" { #define ADC_BAT_OUTPUT_PORT GPIOA #define ADC_BAT_OUTPUT_PIN GPIO_PIN_12 +#define ADC_SOLAR_LEVEL_PORT GPIOA +#define ADC_SOLAR_LEVEL_PIN GPIO_PIN_5 +#define GPIO_SOLAR_BAT_CHANNEL 3 + /* --------------------------- LED_pin definition -------------------------------*/ #define LED_CLK_ENABLE() rcc_enable_peripheral_clk(RCC_PERIPHERAL_GPIOB, true) #define LED_RGB_PORT GPIOB @@ -115,6 +119,15 @@ extern "C" { #define ULT_Echo_PORT GPIOA #define ULT_Echo_PIN GPIO_PIN_15 +/* --------------------------- PWM definition -------------------------------*/ +#define PWM_CLK_ENABLE() rcc_enable_peripheral_clk(RCC_PERIPHERAL_GPIOA, true) +#define PWM_RCC_ENABLE() rcc_enable_peripheral_clk(RCC_PERIPHERAL_TIMER1, true) +#define PWM_RCC_DISABLE() rcc_enable_peripheral_clk(RCC_PERIPHERAL_TIMER1, false) +#define TIMER_ENABLE() timer_cmd(TIMER1, true) +#define TIMER_DISABLE() timer_cmd(TIMER1, false) +#define PWM_PORT GPIOA +#define PWM_PIN GPIO_PIN_15 + /* --------------------------- DX-BT24_pin definition -------------------------------*/ #define DX_BT24_CLK_ENABLE() rcc_enable_peripheral_clk(RCC_PERIPHERAL_GPIOD, true) #define DX_BT24_PORT GPIOD diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/inc/version.h b/Projects/Applications/DRAGINO-LRWAN-AT/inc/version.h index f588a9a..609ed21 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/inc/version.h +++ b/Projects/Applications/DRAGINO-LRWAN-AT/inc/version.h @@ -68,7 +68,7 @@ Maintainer: Miguel Luis, Gregory Cristian and Wael Guibene /* Includes ------------------------------------------------------------------*/ -#define AT_VERSION_STRING "v1.1" +#define AT_VERSION_STRING "v1.3" #define AT_LoRaWan_VERSION_STRING "DR-LWS-007" /* Exported types ------------------------------------------------------------*/ diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/project.uvoptx b/Projects/Applications/DRAGINO-LRWAN-AT/project.uvoptx index f4cfbef..9ff49d4 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/project.uvoptx +++ b/Projects/Applications/DRAGINO-LRWAN-AT/project.uvoptx @@ -103,7 +103,7 @@ 1 0 0 - 6 + 4 @@ -685,6 +685,30 @@ 0 0 + + 3 + 35 + 1 + 0 + 0 + 0 + ..\..\..\Drivers\sensor\pwm.c + pwm.c + 0 + 0 + + + 3 + 36 + 1 + 0 + 0 + 0 + ..\..\..\Drivers\sensor\TMP117_I2C.c + TMP117_I2C.c + 0 + 0 + @@ -695,7 +719,7 @@ 0 4 - 35 + 37 1 0 0 @@ -707,7 +731,7 @@ 4 - 36 + 38 1 0 0 @@ -719,7 +743,7 @@ 4 - 37 + 39 1 0 0 @@ -731,7 +755,7 @@ 4 - 38 + 40 1 0 0 @@ -751,7 +775,7 @@ 0 5 - 39 + 41 1 0 0 @@ -763,7 +787,7 @@ 5 - 40 + 42 1 0 0 @@ -775,7 +799,7 @@ 5 - 41 + 43 1 0 0 @@ -795,7 +819,7 @@ 0 6 - 42 + 44 1 0 0 @@ -807,7 +831,7 @@ 6 - 43 + 45 1 0 0 @@ -827,7 +851,7 @@ 0 7 - 44 + 46 1 0 0 @@ -839,7 +863,7 @@ 7 - 45 + 47 1 0 0 @@ -851,7 +875,7 @@ 7 - 46 + 48 1 0 0 @@ -863,7 +887,7 @@ 7 - 47 + 49 1 0 0 @@ -883,7 +907,7 @@ 0 8 - 48 + 50 1 0 0 @@ -895,7 +919,7 @@ 8 - 49 + 51 1 0 0 @@ -907,7 +931,7 @@ 8 - 50 + 52 1 0 0 @@ -919,7 +943,7 @@ 8 - 51 + 53 1 0 0 @@ -931,7 +955,7 @@ 8 - 52 + 54 1 0 0 @@ -943,7 +967,7 @@ 8 - 53 + 55 1 0 0 @@ -955,7 +979,7 @@ 8 - 54 + 56 1 0 0 @@ -967,7 +991,7 @@ 8 - 55 + 57 1 0 0 @@ -979,7 +1003,7 @@ 8 - 56 + 58 1 0 0 @@ -991,7 +1015,7 @@ 8 - 57 + 59 1 0 0 @@ -1003,7 +1027,7 @@ 8 - 58 + 60 1 0 0 @@ -1015,7 +1039,7 @@ 8 - 59 + 61 1 0 0 @@ -1027,7 +1051,7 @@ 8 - 60 + 62 1 0 0 @@ -1039,7 +1063,7 @@ 8 - 61 + 63 1 0 0 @@ -1059,7 +1083,7 @@ 0 9 - 62 + 64 1 0 0 @@ -1071,7 +1095,7 @@ 9 - 63 + 65 1 0 0 @@ -1083,7 +1107,7 @@ 9 - 64 + 66 1 0 0 diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/project.uvprojx b/Projects/Applications/DRAGINO-LRWAN-AT/project.uvprojx index 4838c20..36a9517 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/project.uvprojx +++ b/Projects/Applications/DRAGINO-LRWAN-AT/project.uvprojx @@ -15,7 +15,7 @@ ARMCM4_FP ARM - ARM.CMSIS.5.4.0 + ARM.CMSIS.5.9.0 http://www.keil.com/pack/ IRAM(0x20000000,0x10000) IROM(0x00000000,0x40000) CPUTYPE("Cortex-M4") FPU2 CLOCK(24000000) ESEL ELITTLE @@ -168,6 +168,8 @@ 0 2 0 + 0 + 0 0 0 @@ -455,6 +457,16 @@ 1 ..\..\..\Drivers\sensor\ult.c + + pwm.c + 1 + ..\..\..\Drivers\sensor\pwm.c + + + TMP117_I2C.c + 1 + ..\..\..\Drivers\sensor\TMP117_I2C.c + @@ -647,4 +659,13 @@ + + + + project + 1 + + + + diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/src/command.c b/Projects/Applications/DRAGINO-LRWAN-AT/src/command.c index 188ffd1..76ac8dc 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/src/command.c +++ b/Projects/Applications/DRAGINO-LRWAN-AT/src/command.c @@ -25,6 +25,7 @@ #include "tremo_iwdg.h" #include "bsp.h" #include "weight.h" +#include "pwm.h" #define ARGC_LIMIT 16 #define ATCMD_SIZE (242 * 2 + 18) @@ -96,6 +97,7 @@ extern uint8_t inmode,inmode2,inmode3; extern uint8_t workmode; extern uint32_t count1,count2; extern float GapValue; +extern uint8_t pwm_timer; extern bool joined_finish; extern bool FDR_status; @@ -178,6 +180,7 @@ static int at_weigre_func(int opt, int argc, char *argv[]); static int at_weigap_func(int opt, int argc, char *argv[]); static int at_5vtime_func(int opt, int argc, char *argv[]); static int at_setcount_func(int opt, int argc, char *argv[]); +static int at_pwmset_func(int opt, int argc, char *argv[]); static int at_sleep_func(int opt, int argc, char *argv[]); static int at_cfg_func(int opt, int argc, char *argv[]); static int at_uuid_func(int opt, int argc, char *argv[]); @@ -245,6 +248,7 @@ static at_cmd_t g_at_table[] = { {AT_WEIGAP, at_weigap_func}, {AT_5VT, at_5vtime_func}, {AT_SETCNT, at_setcount_func}, + {AT_PWMSET, at_pwmset_func}, {AT_SLEEP, at_sleep_func}, {AT_CFG, at_cfg_func}, {AT_UUID, at_uuid_func}, @@ -2541,7 +2545,7 @@ static int at_mod_func(int opt, int argc, char *argv[]) value = strtol((const char *)argv[0], NULL, 0); - if((value>=1)&&(value<=9)) + if((value>=1)&&(value<=11)) { workmode=value; LOG_PRINTF(LL_DEBUG,"Attention:Take effect after ATZ\r\n"); @@ -2551,7 +2555,7 @@ static int at_mod_func(int opt, int argc, char *argv[]) } else { - LOG_PRINTF(LL_DEBUG,"Mode of range is 1 to 9\r\n"); + LOG_PRINTF(LL_DEBUG,"Mode of range is 1 to 11\r\n"); ret = LWAN_PARAM_ERROR; } break; @@ -2848,6 +2852,49 @@ static int at_setcount_func(int opt, int argc, char *argv[]) return ret; } +static int at_pwmset_func(int opt, int argc, char *argv[]) +{ + int ret = LWAN_PARAM_ERROR; + uint8_t temp=0; + + switch(opt) { + case QUERY_CMD: { + ret = LWAN_SUCCESS; + snprintf((char *)atcmd, ATCMD_SIZE, "%d\r\n", pwm_timer); + + break; + } + + case SET_CMD: { + if(argc < 1) break; + + temp = strtol((const char *)argv[0], NULL, 0); + + if(temp<=1) + { + pwm_timer=temp; + ret = LWAN_SUCCESS; + write_config_in_flash_status=1; + atcmd[0] = '\0'; + } + else + { + ret = LWAN_PARAM_ERROR; + } + break; + } + + case DESC_CMD: { + ret = LWAN_SUCCESS; + snprintf((char *)atcmd, ATCMD_SIZE, "Get or Set the counting unit of the timer(0:1 microsecond,1:1 millisecond)\r\n"); + break; + } + default: break; + } + + return ret; +} + static int at_sleep_func(int opt, int argc, char *argv[]) { int ret = LWAN_PARAM_ERROR; @@ -2889,6 +2936,10 @@ static int at_sleep_func(int opt, int argc, char *argv[]) gpio_config_stop3_wakeup(GPIO_EXTI8_PORT, GPIO_EXTI8_PIN ,false,GPIO_LEVEL_HIGH); gpio_init(GPIO_EXTI15_PORT, GPIO_EXTI15_PIN, GPIO_MODE_ANALOG); gpio_config_stop3_wakeup(GPIO_EXTI15_PORT, GPIO_EXTI15_PIN ,false,GPIO_LEVEL_HIGH); + if(workmode==10) + { + gptimer_pwm_Iodeinit(); + } joined_finish=0; sleep_status=1; diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/src/lora_app.c b/Projects/Applications/DRAGINO-LRWAN-AT/src/lora_app.c index e4644ba..48d93ac 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/src/lora_app.c +++ b/Projects/Applications/DRAGINO-LRWAN-AT/src/lora_app.c @@ -109,13 +109,14 @@ product_id #define Firm_FQ 255 #endif -uint8_t product_id=3; +uint8_t product_id=0x1C; uint8_t fire_version=0; uint8_t current_fre_band=0; uint8_t product_id_read_in_flash=0; uint8_t fre_band_read_in_flash=0; uint8_t firmware_ver_read_in_flash=0; uint8_t workmode; +uint8_t pwm_timer; uint16_t power_5v_time; char *band_string=""; bool FDR_status=0; @@ -460,9 +461,12 @@ void LORA_Init (LoRaMainCallback_t *callbacks, LoRaParam_t* LoRaParam ) device_UUID_error_status=1; LOG_PRINTF(LL_DEBUG,"Invalid credentials,the device goes into low power mode\r\n"); } - + + #if defined LB_LS + LOG_PRINTF(LL_DEBUG,"\n\rDragino SN50_v3-LS Device\n\r"); + #else LOG_PRINTF(LL_DEBUG,"\n\rDragino SN50_v3-LB Device\n\r"); - + #endif LOG_PRINTF(LL_DEBUG,"Image Version: "AT_VERSION_STRING"\n\r"); LOG_PRINTF(LL_DEBUG,"LoRaWan Stack: "AT_LoRaWan_VERSION_STRING"\n\r"); LOG_PRINTF(LL_DEBUG,"Frequency Band: "); @@ -1249,6 +1253,8 @@ void Flash_Store_Config(void) store_config_in_flash[76]=(int)(GapValue*10)>>8; store_config_in_flash[77]=(int)(GapValue*10); + store_config_in_flash[78]=pwm_timer; + __disable_irq(); flash_erase_page(FLASH_USER_START_ADDR_CONFIG); delay_ms(5); @@ -1415,6 +1421,8 @@ void Flash_Read_Config(void) inmode3=read_config_in_flash[73]; GapValue=(float)((read_config_in_flash[74]<<24 | read_config_in_flash[75]<<16 | read_config_in_flash[76]<<8 | read_config_in_flash[77])/10.0); + + pwm_timer=read_config_in_flash[78];; } uint8_t string_touint(void) diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/src/main.c b/Projects/Applications/DRAGINO-LRWAN-AT/src/main.c index 0299040..708885c 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/src/main.c +++ b/Projects/Applications/DRAGINO-LRWAN-AT/src/main.c @@ -25,6 +25,7 @@ #include "lora_config.h" #include "LoRaMac.h" #include "weight.h" +#include "pwm.h" #define BCD_TO_HEX2(bcd) ((((bcd)>>4)*10)+((bcd)&0x0F)) #define LORAWAN_ADR_STATE LORAWAN_ADR_ON @@ -105,6 +106,7 @@ uint8_t LinkADR_NbTrans_retransmission_nbtrials=0; uint8_t unconfirmed_uplink_change_to_confirmed_uplink_status=0; uint16_t unconfirmed_uplink_change_to_confirmed_uplink_timeout=0; +extern uint8_t pwm_timer; extern uint8_t product_id; extern uint8_t fire_version; extern uint8_t current_fre_band; @@ -895,6 +897,43 @@ static void Send( void ) AppData.Buff[i++] = (uint8_t)((bsp_sensor_data_buff.count_pa4)>>8); AppData.Buff[i++] = (uint8_t)(bsp_sensor_data_buff.count_pa4); } + else if(workmode==10) + { + AppData.Buff[i++] =(bsp_sensor_data_buff.bat_mv>>8); + AppData.Buff[i++] = bsp_sensor_data_buff.bat_mv & 0xFF; + + AppData.Buff[i++]=(int)(bsp_sensor_data_buff.temp1*10)>>8; + AppData.Buff[i++]=(int)(bsp_sensor_data_buff.temp1*10); + + AppData.Buff[i++] =(int)(bsp_sensor_data_buff.ADC_4)>>8; + AppData.Buff[i++] =(int)(bsp_sensor_data_buff.ADC_4); + + AppData.Buff[i++]=(bsp_sensor_data_buff.exit_pa8<<7)|0x24|((pwm_timer&0x01)<<1)|(exit_temp&0x01); + + AppData.Buff[i++]= (bsp_sensor_data_buff.pwm_freq)>>8; + AppData.Buff[i++]= bsp_sensor_data_buff.pwm_freq; + + AppData.Buff[i++]= (bsp_sensor_data_buff.pwm_duty)>>8; + AppData.Buff[i++]= bsp_sensor_data_buff.pwm_duty; + } + else if(workmode==11) + { + AppData.Buff[i++] =(bsp_sensor_data_buff.bat_mv>>8); + AppData.Buff[i++] = bsp_sensor_data_buff.bat_mv & 0xFF; + + AppData.Buff[i++]=(int)(bsp_sensor_data_buff.temp1*10)>>8; + AppData.Buff[i++]=(int)(bsp_sensor_data_buff.temp1*10); + + AppData.Buff[i++] =(int)(bsp_sensor_data_buff.ADC_4)>>8; + AppData.Buff[i++] =(int)(bsp_sensor_data_buff.ADC_4); + + AppData.Buff[i++]=(bsp_sensor_data_buff.exit_pa8<<7)|0x28|(bsp_sensor_data_buff.in1<<1)|(exit_temp&0x01); + + AppData.Buff[i++] =(int)(bsp_sensor_data_buff.temp_tmp117*100)>>8; + AppData.Buff[i++] =(int)(bsp_sensor_data_buff.temp_tmp117*100); + AppData.Buff[i++] = 0x00; + AppData.Buff[i++] = 0x00; + } AppData.BuffSize = i; payloadlens=i; @@ -1246,7 +1285,7 @@ static void LORA_RxData( lora_AppData_t *AppData ) { if( AppData->BuffSize == 2 ) { - if((AppData->Buff[1]>=0x01)&&(AppData->Buff[1]<=0x09)) //---->AT+MOD + if((AppData->Buff[1]>=0x01)&&(AppData->Buff[1]<=0x0B)) //---->AT+MOD { workmode=AppData->Buff[1]; downlink_config_store_in_flash=1; @@ -1256,6 +1295,36 @@ static void LORA_RxData( lora_AppData_t *AppData ) } break; } + + case 0x0B: + { + if(workmode==10) + { + if(AppData->BuffSize == 7) + { + uint32_t frq = AppData->Buff[1]<<16 | AppData->Buff[2]<<8 | AppData->Buff[3]; + uint8_t dct = AppData->Buff[4]; + uint16_t delay_time = AppData->Buff[5]<<8 | AppData->Buff[6]; + if(frq!=0) + { + gptimer_pwm_output(delay_time,frq,dct); + rxpr_flags=1; + } + } + } + break; + } + + case 0x0C: + { + if( AppData->BuffSize == 2 ) //AT+PWMSET + { + pwm_timer= AppData->Buff[1]; + downlink_config_store_in_flash=1; + rxpr_flags=1; + } + break; + } case 0x20: { @@ -1953,6 +2022,10 @@ void user_key_event(void) gpio_config_stop3_wakeup(GPIO_EXTI8_PORT, GPIO_EXTI8_PIN ,false,GPIO_LEVEL_HIGH); gpio_init(GPIO_EXTI15_PORT, GPIO_EXTI15_PIN, GPIO_MODE_ANALOG); gpio_config_stop3_wakeup(GPIO_EXTI15_PORT, GPIO_EXTI15_PIN ,false,GPIO_LEVEL_HIGH); + if(workmode==10) + { + gptimer_pwm_Iodeinit(); + } joined_finish=0; user_key_duration=0; diff --git a/Projects/Applications/DRAGINO-LRWAN-AT/src/tremo_it.c b/Projects/Applications/DRAGINO-LRWAN-AT/src/tremo_it.c index 05dbf56..1247b54 100644 --- a/Projects/Applications/DRAGINO-LRWAN-AT/src/tremo_it.c +++ b/Projects/Applications/DRAGINO-LRWAN-AT/src/tremo_it.c @@ -4,8 +4,12 @@ #include "lora_config.h" #include "tremo_uart.h" #include "tfsensor.h" +#include "tremo_timer.h" +uint16_t IC1[4],IC2[4]; +uint16_t IC1Value=0,IC2Value=0; uint8_t RxBuffer[1]; +extern uint8_t icnumber; extern bool exti_flag,exti2_flag,exti3_flag; extern uint8_t user_key_exti_flag; extern bool join_network; @@ -172,6 +176,23 @@ void DMA1_IRQHandler(void) dma1_IRQHandler(); } +void TIMER1_IRQHandler(void) +{ + bool state; + timer_get_status(TIMER1, TIMER_SR_CC0IF, &state); + if (state) + { + timer_clear_status(TIMER1, TIMER_SR_CC0IF); + IC1Value = TIMER1->CCR0; + IC2Value = TIMER1->CCR1; + if(icnumber<4) + { + IC1[icnumber]=IC1Value; + IC2[icnumber]=IC2Value; + icnumber++; + } + } +} /******************************************************************************/ /* Tremo Peripherals Interrupt Handlers */ /* Add here the Interrupt Handler for the used peripheral(s) (PPP), for the */