Hardware components | ||||||
| × | 1 | ||||
| × | 1 | ||||
| × | 1 | ||||
| × | 1 | ||||
| × | 2 | ||||
| × | 1 | ||||
| × | 1 | ||||
| × | 1 | ||||
Software apps and online services | ||||||
| ||||||
Hand tools and fabrication machines | ||||||
| ||||||
|
In this project, we aim to create an interactive paper robot using Hexabitz modules. The robot will be equipped with a servo motor and a motion sensor, enabling it to move its arms and wave in response to any movement detected by the sensor. By combining the versatility of Hexabitz with the simplicity of paper, we hope to create a fun and engaging DIY project that showcases the potential of modular robotics. Whether you're a beginner or an experienced maker, this project is sure to provide a rewarding challenge and a unique addition to your robotics collection. So let's get started and bring this interactive paper robot to life!
Tools:The DIY interactive paper robot with Hexabitz is a project aimed at designing a paper robot for children using servo motors and motion sensors. The robot is capable of moving its arms and waving whenever any movement is detected in front of the sensor.
This project combines creativity, engineering, and technology to create an interactive and engaging experience for children. By using simple materials like paper and basic electronic components, we can build a fun and educational toy that encourages children to explore the world of robotics.
The main components used in this project are servo motor, which allow the robot's arms to move in different directions, and a motion sensor that detects any movement in its vicinity.
The DIY interactive paper robot not only introduces children to basic robotics concepts but also encourages them to think creatively and problem-solve. They can customize their robots by decorating them with colors, patterns, or even adding additional features like LED lights or sound effects.
Through this project, children will learn about basic electronics, coding, and how different components work together to create a functional robot. It provides an opportunity for hands-on learning and fosters curiosity and imagination.
Temperature, Humidity, Light, Color and Motion Sensor Hub:
H0AR9x is sensor hub module with STM32G0 MCU and a variety of sensors:
- Weather: TI HDC1080DMBT digital temperature and relative humidity sensor.
- Light: Broadcom (Avago) APDS-9950 proximity, ambient light and RGB color sensor.
- Motion: Panasonic EKMC1601111 proximity infrared motion detector (PIR).
Use this module as an indoors weather station, room monitoring node or put on board aerial or ground robotics platform to gather surrounding data. Connect with other Hexabitz modules to log sensor measurements, stream data wirelessly or control external devices based on sensor readings.
3.3V/1A DC-DC Power Supply (H03R0x):
H03R0x is a compact DC-DC buck power supply with a 3.3V/1A DC output and 5-40V DC input. The output voltage is provided through Hexabitz SMD edge-pad connectors (3.3V on top and GND on bottom). The -T module version comes with a 5.08 mm terminal block connector for input voltage, while the -J comes with a DC power jack. Use this module to power all your Hexabitz creations (and other hardware) from a DC source (battery, AC/DC wall adapter, etc.).
5V DC-DC Boost Power Supply (H32R1x):
H32R1x is a compact DC-DC boost power supply module that takes 3.3V from module array ports and boosts it up to 5V/0.5A output voltage on the terminal block connector. You can use this module to generate 5V from your Hexabitz array 3.3V backbone voltage.
STLINK-V3MODS Programmer (H40Rx):
H40Rx is a programmer module which contains STLINK-V3MODS stand-alone debugging and programming mini probe for STM32 micro-controllers (Hexabitz modules and other MCUs).
It supports the SWD (Serial Wire Debugging) interface for the communication with any STM32 micro-controller located on an application board.
It also provides bridge interfaces to several communication protocols, allowing for instance the programming of the target through boot-loader.
Β· We prepare the project components and plan our array design by aligning modules side-by-side.
Β· Then we solder the modules together using Hexabitz Fixture.
CheerBot Template: If you need to print CheerBot templates, you can download them here: https://www.okdo.com/p/okdo-microbit-build-a-paper-robot-kit
- Check out this article for writing code with STM32CubeIDE.
- Check out this article for Utilize Modules Ports as Independent Controller Ports Outside of BOS System.
H0AR9x Firmware H0AR9.h code:
First, reduce the number of ports in the.h file. This can be achieved by replacing the original number of ports with one less, and commenting out the last port along with its related USART port and UART Init prototype. For example, if the original number of ports is 6, it should be reduced to 5 by commenting out (//#define _P6), (//#define _Usart6 1), and (//extern void MX_USART6_UART_Init(void);).
H0AR9x Firmware H0AR9.c code:
Second, comment the MX_USART6_UART_Init() port inside the Module_Peripheral_Init() function in the.c file, also commenting this port inside GetPort function.
H0AR9x Firmware H0AR9_gpio.c code:
Third, add the instructions for configuring the pin you are going to use in H0AR9_gpio.c file.
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(GPIOB,&GPIO_InitStruct);
H0AR9x Firmware main.c code:
First, we define the motion variable:
uint16_t prox;
and then defined the other variable used in the code.
int q;
And in the repeated closed loop, we made sure that MCU periodically checks the prox
value of the sensor using the API from module factsheet.
SampleDistance(&prox);
And if the motion achieves the required condition (i.e. if we wave in front of the PIR motion sensor), the servo motor is turned on at certain angles to move the robot's arms.
if (q > 15)
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET);
Delay_ms(1.5);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_RESET);
Delay_ms(20);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET);
Delay_ms(0.5);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_RESET);
Delay_ms(10);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET);
Delay_ms(2.5);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_RESET);
Delay_ms(50);
- Check out this project for : How is a Servo Controlled.
Note: For this project, make sure you're using the standard 180Β° servo.
In conclusion, the DIY interactive paper robot with Hexabitz is an exciting project that combines art, technology, and education. It offers an engaging way for children to learn about robotics while having fun building their own unique robots. Let's dive into this project and unleash our creativity!
References:/*
BitzOS (BOS) V0.2.9 - Copyright (C) 2017-2023 Hexabitz
All rights reserved
File Name : main.c
Description : Main program body.
*/
/* Includes ------------------------------------------------------------------*/
#include "BOS.h"
uint16_t prox;
int q;
/* Private function prototypes -----------------------------------------------*/
// char *user_data = "The application is running\r\n"; //demo data for transmission-
/* Main function ------------------------------------------------------------*/
int main(void){
Module_Init(); //Initialize Module & BitzOS
//MX_USART5_UART_Init();
//Don't place your code here.
for(;;){}
}
/*---float H0AR9_temperature;
float H0AR9_humidity;--------------------------------------------------------*/
/* User Task */
void UserTask(void *argument){
while(1){
SampleDistance(&prox);
q =prox;
if (q > 15)
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET);
Delay_ms(1.5);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_RESET);
Delay_ms(20);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET);
Delay_ms(0.5);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_RESET);
Delay_ms(10);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_SET);
Delay_ms(2.5);
HAL_GPIO_WritePin(GPIOB, GPIO_PIN_8, GPIO_PIN_RESET);
Delay_ms(50);
}
}
/*-----------------------------------------------------------*/
/*
BitzOS (BOS) V0.2.9 - Copyright (C) 2017-2023 Hexabitz
All rights reserved
File Name : H0AR9.h
Description : Header file for module H0AR9.
(Description_of_module)
(Description of Special module peripheral configuration):
>>
>>
>>
*/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef H0AR9_H
#define H0AR9_H
/* Includes ------------------------------------------------------------------*/
#include "BOS.h"
#include "H0AR9_MemoryMap.h"
#include "H0AR9_uart.h"
#include "H0AR9_gpio.h"
#include "H0AR9_dma.h"
#include "H0AR9_inputs.h"
#include "H0AR9_eeprom.h"
#include "H0AR9_i2c.h"
/* Exported definitions -------------------------------------------------------*/
#define modulePN _H0AR9
/* Port-related definitions */
#define NumOfPorts 6
#define P_PROG P2 /* ST factory bootloader UART */
/* Define available ports */
#define _P1
#define _P2
#define _P3
#define _P4
#define _P5
//#define _P6
/* Define available USARTs */
#define _Usart1 1
#define _Usart2 1
#define _Usart3 1
#define _Usart4 1
#define _Usart5 1
//#define _Usart6 1
/* Port-UART mapping */
#define P1uart &huart4
#define P2uart &huart2
#define P3uart &huart3
#define P4uart &huart1
#define P5uart &huart5
//#define P6uart &huart6
/* Port Definitions */
#define USART1_TX_PIN GPIO_PIN_9
#define USART1_RX_PIN GPIO_PIN_10
#define USART1_TX_PORT GPIOA
#define USART1_RX_PORT GPIOA
#define USART1_AF GPIO_AF1_USART1
#define USART2_TX_PIN GPIO_PIN_2
#define USART2_RX_PIN GPIO_PIN_3
#define USART2_TX_PORT GPIOA
#define USART2_RX_PORT GPIOA
#define USART2_AF GPIO_AF1_USART2
#define USART3_TX_PIN GPIO_PIN_10
#define USART3_RX_PIN GPIO_PIN_11
#define USART3_TX_PORT GPIOB
#define USART3_RX_PORT GPIOB
#define USART3_AF GPIO_AF4_USART3
#define USART4_TX_PIN GPIO_PIN_0
#define USART4_RX_PIN GPIO_PIN_1
#define USART4_TX_PORT GPIOA
#define USART4_RX_PORT GPIOA
#define USART4_AF GPIO_AF4_USART4
#define USART5_TX_PIN GPIO_PIN_3
#define USART5_RX_PIN GPIO_PIN_2
#define USART5_TX_PORT GPIOD
#define USART5_RX_PORT GPIOD
#define USART5_AF GPIO_AF3_USART5
#define USART6_TX_PIN GPIO_PIN_8
#define USART6_RX_PIN GPIO_PIN_9
#define USART6_TX_PORT GPIOB
#define USART6_RX_PORT GPIOB
#define USART6_AF GPIO_AF8_USART6
/* Module-specific Definitions */
#define NUM_MODULE_PARAMS 7
#define STOP_MEASUREMENT_RANGING 0
#define START_MEASUREMENT_RANGING 1
/* Module EEPROM Variables */
// Module Addressing Space 500 - 599
#define _EE_MODULE 500
/* Module_Status Type Definition */
typedef enum
{
H0AR9_OK = 0,
H0AR9_ERR_UnknownMessage,
H0AR9_ERR_RGB,
H0AR9_ERR_PROXIMITY,
H0AR9_ERR_TEMPRATURE,
H0AR9_ERR_HUMIDITY,
H0AR9_ERR_PIR,
H0AR9_ERR_BUSY,
H0AR9_ERR_TIMEOUT,
H0AR9_ERR_IO,
H0AR9_ERR_TERMINATED,
H0AR9_ERR_WrongParams,
H0AR9_ERROR = 25
} Module_Status;
/* Indicator LED */
#define _IND_LED_PORT GPIOB
#define _IND_LED_PIN GPIO_PIN_14
/* Export UART variables */
extern UART_HandleTypeDef huart1;
extern UART_HandleTypeDef huart2;
extern UART_HandleTypeDef huart3;
extern UART_HandleTypeDef huart4;
extern UART_HandleTypeDef huart5;
extern UART_HandleTypeDef huart6;
/* Define UART Init prototypes */
extern void MX_USART1_UART_Init(void);
extern void MX_USART2_UART_Init(void);
extern void MX_USART3_UART_Init(void);
extern void MX_USART4_UART_Init(void);
extern void MX_USART5_UART_Init(void);
//extern void MX_USART6_UART_Init(void);
extern void SystemClock_Config(void);
extern void ExecuteMonitor(void);
/* -----------------------------------------------------------------------
| APIs | |
/* -----------------------------------------------------------------------
*/
uint16_t Read_Word(uint8_t reg);
void Error_Handler(void);
void initialValue(void);
void APDS9950_init(void);
void WriteRegData(uint8_t reg, uint8_t data);
void stopStreamMems(void);
void SamplePIR(bool *pir);
void SampleColor(uint16_t *Red, uint16_t *Green, uint16_t *Blue);
void SampleDistance(uint16_t *Proximity);
void SampleTemperature(float *temperature);
void SampleHumidity(float *humidity);
void SampleColorBuf(float *buffer);
void SampleDistanceBuff(float *buffer);
void SampleTemperatureBuf(float *buffer);
void SampleHumidityBuf(float *buffer);
void SamplePIRBuf(float *buffer);
void SampleColorToPort(uint8_t port,uint8_t module);
void SampleDistanceToPort(uint8_t port,uint8_t module);
void SampleTemperatureToPort(uint8_t port,uint8_t module);
void SampleHumidityToPort(uint8_t port,uint8_t module);
void SamplePIRToPort(uint8_t port,uint8_t module);
void SampleColorToString(char *cstring, size_t maxLen);
void SampleDistanceToString(char *cstring, size_t maxLen);
void SampleTemperatureToString(char *cstring, size_t maxLen);
void SampleHumidityToString(char *cstring, size_t maxLen);
void SamplePIRToString(char *cstring, size_t maxLen);
Module_Status StreamColorToBuffer(float *buffer, uint32_t period, uint32_t timeout);
Module_Status StreamDistanceToBuffer(float *buffer, uint32_t period, uint32_t timeout);
Module_Status StreamTemperatureToBuffer(float *buffer, uint32_t period, uint32_t timeout);
Module_Status StreamHumidityToBuffer(float *buffer, uint32_t period, uint32_t timeout);
Module_Status StreamPIRToBuffer(float *buffer, uint32_t period, uint32_t timeout);
Module_Status StreamColorToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout);
Module_Status StreamDistanceToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout);
Module_Status StreamTemperatureToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout);
Module_Status StreamHumidityToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout);
Module_Status StreamPIRToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout);
Module_Status StreamColorToCLI(uint32_t period, uint32_t timeout);
Module_Status StreamDistanceToCLI(uint32_t period, uint32_t timeout);
Module_Status StreamTemperatureToCLI(uint32_t period, uint32_t timeout);
Module_Status StreamHumidityToCLI(uint32_t period, uint32_t timeout);
Module_Status StreamPIRToCLI(uint32_t period, uint32_t timeout);
void SetupPortForRemoteBootloaderUpdate(uint8_t port);
void remoteBootloaderUpdate(uint8_t src,uint8_t dst,uint8_t inport,uint8_t outport);
/* -----------------------------------------------------------------------
| Commands | |
/* -----------------------------------------------------------------------
*/
#endif /* H0AR9_H */
/************************ (C) COPYRIGHT HEXABITZ *****END OF FILE****/
/*
BitzOS (BOS) V0.2.9 - Copyright (C) 2017-2023 Hexabitz
All rights reserved
File Name : H0AR9.c
Description : Source code for module H0AR9.
(Description_of_module)
(Description of Special module peripheral configuration):
>>
>>
>>
*/
/* Includes ------------------------------------------------------------------*/
#include "BOS.h"
#include "stdio.h"
#include "stdlib.h"
#include "string.h"
#include "H0AR9_inputs.h"
/* Define UART variables */
UART_HandleTypeDef huart1;
UART_HandleTypeDef huart2;
UART_HandleTypeDef huart3;
UART_HandleTypeDef huart4;
UART_HandleTypeDef huart5;
UART_HandleTypeDef huart6;
/* Exported variables */
extern FLASH_ProcessTypeDef pFlash;
extern uint8_t numOfRecordedSnippets;
extern I2C_HandleTypeDef hi2c2;
/* Module exported parameters ------------------------------------------------*/
uint8_t H0AR9_PIR;
uint16_t H0AR9_RGBred;
uint16_t H0AR9_RGBgreen;
uint16_t H0AR9_RGBblue;
uint16_t H0AR9_proximity;
float H0AR9_temperature;
float H0AR9_humidity;
module_param_t modParam[NUM_MODULE_PARAMS] = {{.paramPtr=&H0AR9_RGBred, .paramFormat=FMT_UINT16, .paramName="RGBred"},
{.paramPtr=&H0AR9_RGBgreen, .paramFormat=FMT_UINT16, .paramName="RGBgreen"},
{.paramPtr=&H0AR9_RGBblue, .paramFormat=FMT_UINT16, .paramName="RGBblue"},
{.paramPtr=&H0AR9_proximity, .paramFormat=FMT_UINT16, .paramName="proximity"},
{.paramPtr=&H0AR9_temperature, .paramFormat=FMT_FLOAT, .paramName="temperature"},
{.paramPtr=&H0AR9_humidity, .paramFormat=FMT_FLOAT, .paramName="humidity"},
{.paramPtr=&H0AR9_PIR, .paramFormat=FMT_UINT8, .paramName="PIR"},
};
#define MIN_MEMS_PERIOD_MS 100
#define MAX_MEMS_TIMEOUT_MS 0xFFFFFFFF
float H0AR9_temperature;
/* Private variables ---------------------------------------------------------*/
typedef void (*SampleMemsToPort)(uint8_t, uint8_t);
typedef void (*SampleMemsToString)(char *, size_t);
typedef void (*SampleMemsToBuffer)(float *buffer);
//temprature and humidity sensor addresses
static const uint8_t tempHumAdd = (0x40)<<1; // Use 7-bit address
static const uint8_t tempReg = 0x00;
static const uint8_t humidityReg = 0x01;
/*Define private variables*/
static bool stopStream = false;
extern I2C_HandleTypeDef hi2c2;
uint8_t buf[10];
uint8_t CONTROL, Enable, ATIME, WTIME, PPULSE;
uint8_t redReg, greenReg, blueReg, distanceReg;
uint16_t RED_data, GREEN_data, BLUE_data, Prox_data;
uint16_t val;
uint8_t pir;
uint8_t CONTROL, Enable, ATIME, WTIME, PPULSE;
uint16_t Red __attribute__((section(".mySection")));
uint16_t Green __attribute__((section(".mySection")));
uint16_t Blue __attribute__((section(".mySection")));
uint16_t distance1 __attribute__((section(".mySection")));
float temp __attribute__((section(".mySection")));
float hum __attribute__((section(".mySection")));
uint8_t Sample __attribute__((section(".mySection")));
/* Private function prototypes -----------------------------------------------*/
static Module_Status StreamMemsToBuf( float *buffer, uint32_t period, uint32_t timeout, SampleMemsToBuffer function);
static Module_Status StreamMemsToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout, SampleMemsToPort function);
static Module_Status StreamMemsToCLI(uint32_t period, uint32_t timeout, SampleMemsToString function);
static Module_Status PollingSleepCLISafe(uint32_t period);
void FLASH_Page_Eras(uint32_t Addr );
void ExecuteMonitor(void);
/* Create CLI commands --------------------------------------------------------*/
static portBASE_TYPE SampleSensorCommand(int8_t *pcWriteBuffer, size_t xWriteBufferLen, const int8_t *pcCommandString);
static portBASE_TYPE StreamSensorCommand(int8_t *pcWriteBuffer, size_t xWriteBufferLen, const int8_t *pcCommandString);
static portBASE_TYPE StopStreamCommand(int8_t *pcWriteBuffer, size_t xWriteBufferLen, const int8_t *pcCommandString);
/* CLI command structure : sample */
const CLI_Command_Definition_t SampleCommandDefinition = {
(const int8_t *) "sample",
(const int8_t *) "sample:\r\n Syntax: sample [color]/[distance]/[temp]/[humidity]/[pir].\r\n\r\n",
SampleSensorCommand,
1
};
/* CLI command structure : stream */
const CLI_Command_Definition_t StreamCommandDefinition = {
(const int8_t *) "stream",
(const int8_t *) "stream:\r\n Syntax: stream [color]/[distance]/[temp]/[humidity]/[pir] (period in ms) (time in ms) [port] [module].\r\n\r\n",
StreamSensorCommand,
-1
};
/* CLI command structure : stop */
const CLI_Command_Definition_t StopCommandDefinition = {
(const int8_t *) "stop",
(const int8_t *) "stop:\r\n Syntax: stop\r\n \
\tStop the current streaming of MEMS values. r\n\r\n",
StopStreamCommand,
0
};
/*-----------------------------------------------------------*/
/* -----------------------------------------------------------------------
| Private Functions |
-----------------------------------------------------------------------
*/
/**
* @brief System Clock Configuration
* The system Clock is configured as follow :
* System Clock source = PLL (HSE)
* SYSCLK(Hz) = 48000000
* HCLK(Hz) = 48000000
* AHB Prescaler = 1
* APB1 Prescaler = 1
* HSE Frequency(Hz) = 8000000
* PREDIV = 1
* PLLMUL = 6
* Flash Latency(WS) = 1
* @param None
* @retval None
*/
void SystemClock_Config(void){
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
/** Configure the main internal regulator output voltage
*/
HAL_PWREx_ControlVoltageScaling(PWR_REGULATOR_VOLTAGE_SCALE1);
/** Initializes the RCC Oscillators according to the specified parameters
* in the RCC_OscInitTypeDef structure.
*/
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI|RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.LSIState = RCC_LSI_ON;
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = RCC_PLLM_DIV1;
RCC_OscInitStruct.PLL.PLLN = 12;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2;
RCC_OscInitStruct.PLL.PLLQ = RCC_PLLQ_DIV2;
RCC_OscInitStruct.PLL.PLLR = RCC_PLLR_DIV2;
HAL_RCC_OscConfig(&RCC_OscInitStruct);
/** Initializes the CPU, AHB and APB buses clocks
*/
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|RCC_CLOCKTYPE_PCLK1;
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2);
/** Initializes the peripherals clocks
*/
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_RTC|RCC_PERIPHCLK_USART2;
PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
PeriphClkInit.RTCClockSelection = RCC_RTCCLKSOURCE_LSI;
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_I2C2;
PeriphClkInit.I2c2ClockSelection = RCC_I2C2CLKSOURCE_PCLK1;
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit);
HAL_NVIC_SetPriority(SysTick_IRQn,0,0);
}
/*-----------------------------------------------------------*/
/* --- Save array topology and Command Snippets in Flash RO ---
*/
uint8_t SaveToRO(void){
BOS_Status result =BOS_OK;
HAL_StatusTypeDef FlashStatus =HAL_OK;
uint16_t add =8;
uint16_t temp =0;
uint8_t snipBuffer[sizeof(snippet_t) + 1] ={0};
HAL_FLASH_Unlock();
/* Erase RO area */
FLASH_PageErase(FLASH_BANK_1,RO_START_ADDRESS);
FlashStatus =FLASH_WaitForLastOperation((uint32_t ) HAL_FLASH_TIMEOUT_VALUE);
FLASH_PageErase(FLASH_BANK_1,RO_MID_ADDRESS);
//TOBECHECKED
FlashStatus =FLASH_WaitForLastOperation((uint32_t ) HAL_FLASH_TIMEOUT_VALUE);
if(FlashStatus != HAL_OK){
return pFlash.ErrorCode;
}
else{
/* Operation is completed, disable the PER Bit */
CLEAR_BIT(FLASH->CR,FLASH_CR_PER);
}
/* Save number of modules and myID */
if(myID){
temp =(uint16_t )(N << 8) + myID;
//HAL_FLASH_Program(FLASH_TYPEPROGRAM_HALFWORD,RO_START_ADDRESS,temp);
HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD,RO_START_ADDRESS,temp);
//TOBECHECKED
FlashStatus =FLASH_WaitForLastOperation((uint32_t ) HAL_FLASH_TIMEOUT_VALUE);
if(FlashStatus != HAL_OK){
return pFlash.ErrorCode;
}
else{
/* If the program operation is completed, disable the PG Bit */
CLEAR_BIT(FLASH->CR,FLASH_CR_PG);
}
/* Save topology */
for(uint8_t i =1; i <= N; i++){
for(uint8_t j =0; j <= MaxNumOfPorts; j++){
if(array[i - 1][0]){
HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD,RO_START_ADDRESS + add,array[i - 1][j]);
//HALFWORD //TOBECHECKED
FlashStatus =FLASH_WaitForLastOperation((uint32_t ) HAL_FLASH_TIMEOUT_VALUE);
if(FlashStatus != HAL_OK){
return pFlash.ErrorCode;
}
else{
/* If the program operation is completed, disable the PG Bit */
CLEAR_BIT(FLASH->CR,FLASH_CR_PG);
add +=8;
}
}
}
}
}
// Save Command Snippets
int currentAdd = RO_MID_ADDRESS;
for(uint8_t s =0; s < numOfRecordedSnippets; s++){
if(snippets[s].cond.conditionType){
snipBuffer[0] =0xFE; // A marker to separate Snippets
memcpy((uint32_t* )&snipBuffer[1],(uint8_t* )&snippets[s],sizeof(snippet_t));
// Copy the snippet struct buffer (20 x numOfRecordedSnippets). Note this is assuming sizeof(snippet_t) is even.
for(uint8_t j =0; j < (sizeof(snippet_t)/4); j++){
HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD,currentAdd,*(uint64_t* )&snipBuffer[j*8]);
//HALFWORD
//TOBECHECKED
FlashStatus =FLASH_WaitForLastOperation((uint32_t ) HAL_FLASH_TIMEOUT_VALUE);
if(FlashStatus != HAL_OK){
return pFlash.ErrorCode;
}
else{
/* If the program operation is completed, disable the PG Bit */
CLEAR_BIT(FLASH->CR,FLASH_CR_PG);
currentAdd +=8;
}
}
// Copy the snippet commands buffer. Always an even number. Note the string termination char might be skipped
for(uint8_t j =0; j < ((strlen(snippets[s].cmd) + 1)/4); j++){
HAL_FLASH_Program(FLASH_TYPEPROGRAM_DOUBLEWORD,currentAdd,*(uint64_t* )(snippets[s].cmd + j*4 ));
//HALFWORD
//TOBECHECKED
FlashStatus =FLASH_WaitForLastOperation((uint32_t ) HAL_FLASH_TIMEOUT_VALUE);
if(FlashStatus != HAL_OK){
return pFlash.ErrorCode;
}
else{
/* If the program operation is completed, disable the PG Bit */
CLEAR_BIT(FLASH->CR,FLASH_CR_PG);
currentAdd +=8;
}
}
}
}
HAL_FLASH_Lock();
return result;
}
/* --- Clear array topology in SRAM and Flash RO ---
*/
uint8_t ClearROtopology(void){
// Clear the array
memset(array,0,sizeof(array));
N =1;
myID =0;
return SaveToRO();
}
/*-----------------------------------------------------------*/
/* --- Trigger ST factory bootloader update for a remote module.
*/
void remoteBootloaderUpdate(uint8_t src,uint8_t dst,uint8_t inport,uint8_t outport){
uint8_t myOutport =0, lastModule =0;
int8_t *pcOutputString;
/* 1. Get route to destination module */
myOutport =FindRoute(myID,dst);
if(outport && dst == myID){ /* This is a 'via port' update and I'm the last module */
myOutport =outport;
lastModule =myID;
}
else if(outport == 0){ /* This is a remote update */
if(NumberOfHops(dst)== 1)
lastModule = myID;
else
lastModule = route[NumberOfHops(dst)-1]; /* previous module = route[Number of hops - 1] */
}
/* 2. If this is the source of the message, show status on the CLI */
if(src == myID){
/* Obtain the address of the output buffer. Note there is no mutual
exclusion on this buffer as it is assumed only one command console
interface will be used at any one time. */
pcOutputString =FreeRTOS_CLIGetOutputBuffer();
if(outport == 0) // This is a remote module update
sprintf((char* )pcOutputString,pcRemoteBootloaderUpdateMessage,dst);
else
// This is a 'via port' remote update
sprintf((char* )pcOutputString,pcRemoteBootloaderUpdateViaPortMessage,dst,outport);
strcat((char* )pcOutputString,pcRemoteBootloaderUpdateWarningMessage);
writePxITMutex(inport,(char* )pcOutputString,strlen((char* )pcOutputString),cmd50ms);
Delay_ms(100);
}
/* 3. Setup my inport and outport for bootloader update */
SetupPortForRemoteBootloaderUpdate(inport);
SetupPortForRemoteBootloaderUpdate(myOutport);
/* 5. Build a DMA stream between my inport and outport */
StartScastDMAStream(inport,myID,myOutport,myID,BIDIRECTIONAL,0xFFFFFFFF,0xFFFFFFFF,false);
}
/*-----------------------------------------------------------*/
/* --- Setup a port for remote ST factory bootloader update:
- Set baudrate to 57600
- Enable even parity
- Set datasize to 9 bits
*/
void SetupPortForRemoteBootloaderUpdate(uint8_t port){
UART_HandleTypeDef *huart =GetUart(port);
huart->Init.BaudRate =57600;
huart->Init.Parity = UART_PARITY_EVEN;
huart->Init.WordLength = UART_WORDLENGTH_9B;
HAL_UART_Init(huart);
/* The CLI port RXNE interrupt might be disabled so enable here again to be sure */
__HAL_UART_ENABLE_IT(huart,UART_IT_RXNE);
}
/* --- H0AR9 module initialization.
*/
void Module_Peripheral_Init(void){
/* Array ports */
MX_USART1_UART_Init();
MX_USART2_UART_Init();
MX_USART3_UART_Init();
MX_USART4_UART_Init();
MX_USART5_UART_Init();
//MX_USART6_UART_Init();
/* initialize GPIO for module */
SENSORS_GPIO_Init();
/* initialize I2C for module */
MX_I2C_Init();
/* initialize color&proximity sensor */
APDS9950_init();
/* Create module special task (if needed) */
}
/*-----------------------------------------------------------*/
/* --- H0AR9 message processing task.
*/
Module_Status Module_MessagingTask(uint16_t code, uint8_t port, uint8_t src, uint8_t dst, uint8_t shift)
{
Module_Status result = H0AR9_OK;
uint32_t period = 0, timeout = 0;
switch (code)
{
case CODE_H0AR9_SAMPLE_COLOR:
{
SampleColorToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift]);
break;
}
case CODE_H0AR9_SAMPLE_DISTANCE:
{
SampleDistanceToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift]);
break;
}
case CODE_H0AR9_SAMPLE_TEMP:
{
SampleTemperatureToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift]);
break;
}
case CODE_H0AR9_SAMPLE_HUMIDITY:
{
SampleHumidityToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift]);
break;
}
case CODE_H0AR9_SAMPLE_PIR:
{
SamplePIRToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift]);
break;
}
case CODE_H0AR9_STREAM_COLOR:
{
period = ((uint32_t) cMessage[port - 1][2 + shift] ) + ((uint32_t) cMessage[port - 1][3 + shift] << 8) + ((uint32_t) cMessage[port - 1][4 + shift] << 16) + ((uint32_t)cMessage[port - 1][5 + shift] << 24);
timeout = ((uint32_t) cMessage[port - 1][6 + shift] ) + ((uint32_t) cMessage[port - 1][7 + shift] << 8) + ((uint32_t) cMessage[port - 1][8 + shift] << 16) + ((uint32_t)cMessage[port - 1][9 + shift] << 24);
StreamColorToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift], period, timeout);
break;
}
case CODE_H0AR9_STREAM_DISTANCE:
{
period = ((uint32_t) cMessage[port - 1][2 + shift] ) + ((uint32_t) cMessage[port - 1][3 + shift] << 8) + ((uint32_t) cMessage[port - 1][4 + shift] << 16) + ((uint32_t)cMessage[port - 1][5 + shift] <<24);
timeout = ((uint32_t) cMessage[port - 1][6 + shift] ) + ((uint32_t) cMessage[port - 1][7 + shift] << 8) + ((uint32_t) cMessage[port - 1][8 + shift] << 16) + ((uint32_t)cMessage[port - 1][9 + shift]<<24);
StreamDistanceToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift], period, timeout);
break;
}
case CODE_H0AR9_STREAM_TEMP:
{
period = ((uint32_t) cMessage[port - 1][2 + shift] ) + ((uint32_t) cMessage[port - 1][3 + shift] << 8) + ((uint32_t) cMessage[port - 1][4 + shift] << 16) + ((uint32_t)cMessage[port - 1][5 + shift]<<24);
timeout = ((uint32_t) cMessage[port - 1][6 + shift] ) + ((uint32_t) cMessage[port - 1][7 + shift] << 8) + ((uint32_t) cMessage[port - 1][8 + shift] << 16) + ((uint32_t)cMessage[port - 1][9 + shift]<<24);
StreamTemperatureToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift], period, timeout);
break;
}
case CODE_H0AR9_STREAM_HUMIDITY:
{
period = ((uint32_t) cMessage[port - 1][2 + shift] ) + ((uint32_t) cMessage[port - 1][3 + shift] << 8) + ((uint32_t) cMessage[port - 1][4 + shift] << 16) + ((uint32_t)cMessage[port - 1][5 + shift]<<24);
timeout = ((uint32_t) cMessage[port - 1][6 + shift] ) + ((uint32_t) cMessage[port - 1][7 + shift] << 8) + ((uint32_t) cMessage[port - 1][8 + shift] << 16) + ((uint32_t)cMessage[port - 1][9 + shift]<<24);
StreamHumidityToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift], period, timeout);
break;
}
case CODE_H0AR9_STREAM_PIR:
{
period = ((uint32_t) cMessage[port - 1][2 + shift] ) + ((uint32_t) cMessage[port - 1][3 + shift] << 8) + ((uint32_t) cMessage[port - 1][4 + shift] << 16) + ((uint32_t)cMessage[port - 1][5 + shift] <<24);
timeout = ((uint32_t) cMessage[port - 1][6 + shift] ) + ((uint32_t) cMessage[port - 1][7 + shift] << 8) + ((uint32_t) cMessage[port - 1][8 + shift] << 16) + ((uint32_t)cMessage[port - 1][9 + shift] <<24);
StreamPIRToPort(cMessage[port-1][1+shift] ,cMessage[port-1][shift], period, timeout);
break;
}
case CODE_H0AR9_STREAM_STOP:
{
stopStreamMems();
result = H0AR9_OK;
break;
}
default:
result = H0AR9_ERR_UnknownMessage;
break;
}
return result;
}
/* --- Get the port for a given UART.
*/
uint8_t GetPort(UART_HandleTypeDef *huart){
if(huart->Instance == USART4)
return P1;
else if(huart->Instance == USART2)
return P2;
else if(huart->Instance == USART3)
return P3;
else if(huart->Instance == USART1)
return P4;
else if(huart->Instance == USART5)
return P5;
//else if(huart->Instance == USART6)
//return P6;
return 0;
}
/*------------------------------------------------------------*/
//initialize APDS9950 sensor
void APDS9950_init(void)
{
//registers addresses
CONTROL = 0x0F;
Enable = 0x00;
ATIME = 0x01;
WTIME = 0x03;
PPULSE = 0x0E;
redReg = 0x16;
greenReg = 0x18;
blueReg = 0x1A;
distanceReg = 0x1C;
WriteRegData (Enable,0x00);
WriteRegData (ATIME,0x00);
WriteRegData (WTIME,0xff);
WriteRegData (PPULSE,0x01);
WriteRegData (CONTROL, 0x20);
WriteRegData (Enable, 0x0F);
}
/*-----------------------------------------------------------*/
void initialValue(void)
{
Red=0;
Green=0;
Blue=0;
distance1=0;
temp=0;
hum=0;
Sample=0;
}
/*-----------------------------------------------------------*/
/* --- Register this module CLI Commands
*/
void RegisterModuleCLICommands(void){
FreeRTOS_CLIRegisterCommand( &SampleCommandDefinition );
FreeRTOS_CLIRegisterCommand( &StreamCommandDefinition );
FreeRTOS_CLIRegisterCommand( &StopCommandDefinition);
}
/*-----------------------------------------------------------*/
/* Module special task function (if needed) */
//void Module_Special_Task(void *argument){
//
// /* Infinite loop */
// uint8_t cases; // Test variable.
// for(;;){
// /* */
// switch(cases){
//
//
// default:
// osDelay(10);
// break;
// }
//
// taskYIELD();
// }
//
//}
/*-----------------------------------------------------------*/
/*-----------------------------------------------------------*/
static Module_Status StreamMemsToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout, SampleMemsToPort function)
{
Module_Status status = H0AR9_OK;
if (period < MIN_MEMS_PERIOD_MS)
return H0AR9_ERR_WrongParams;
if (port == 0)
return H0AR9_ERR_WrongParams;
if (port == PcPort) // Check if CLI is not enabled at that port!
return H0AR9_ERR_BUSY;
if (period > timeout)
timeout = period;
long numTimes = timeout / period;
stopStream = false;
while ((numTimes-- > 0) || (timeout >= MAX_MEMS_TIMEOUT_MS)) {
function(port, module);
vTaskDelay(pdMS_TO_TICKS(period));
if (stopStream) {
status = H0AR9_ERR_TERMINATED;
break;
}
}
return status;
}
/*-----------------------------------------------------------*/
static Module_Status StreamMemsToBuf( float *buffer, uint32_t period, uint32_t timeout, SampleMemsToBuffer function)
{
Module_Status status = H0AR9_OK;
if (period < MIN_MEMS_PERIOD_MS)
return H0AR9_ERR_WrongParams;
// TODO: Check if CLI is enable or not
if (period > timeout)
timeout = period;
long numTimes = timeout / period;
stopStream = false;
while ((numTimes-- > 0) || (timeout >= MAX_MEMS_TIMEOUT_MS)) {
function(buffer);
vTaskDelay(pdMS_TO_TICKS(period));
if (stopStream) {
status = H0AR9_ERR_TERMINATED;
break;
}
}
return status;
}
/*-----------------------------------------------------------*/
static Module_Status StreamMemsToCLI(uint32_t period, uint32_t timeout, SampleMemsToString function)
{
Module_Status status = H0AR9_OK;
int8_t *pcOutputString = NULL;
if (period < MIN_MEMS_PERIOD_MS)
return H0AR9_ERR_WrongParams;
// TODO: Check if CLI is enable or not
if (period > timeout)
timeout = period;
long numTimes = timeout / period;
stopStream = false;
while ((numTimes-- > 0) || (timeout >= MAX_MEMS_TIMEOUT_MS)) {
pcOutputString = FreeRTOS_CLIGetOutputBuffer();
function((char *)pcOutputString, 100);
writePxMutex(PcPort, (char *)pcOutputString, strlen((char *)pcOutputString), cmd500ms, HAL_MAX_DELAY);
if (PollingSleepCLISafe(period) != H0AR9_OK)
break;
}
memset((char *) pcOutputString, 0, configCOMMAND_INT_MAX_OUTPUT_SIZE);
sprintf((char *)pcOutputString, "\r\n");
return status;
}
/*-----------------------------------------------------------*/
/* --- Save array topology and Command Snippets in Flash RO ---
*/
static Module_Status PollingSleepCLISafe(uint32_t period)
{
const unsigned DELTA_SLEEP_MS = 100; // milliseconds
long numDeltaDelay = period / DELTA_SLEEP_MS;
unsigned lastDelayMS = period % DELTA_SLEEP_MS;
while (numDeltaDelay-- > 0) {
vTaskDelay(pdMS_TO_TICKS(DELTA_SLEEP_MS));
// Look for ENTER key to stop the stream
for (uint8_t chr=0 ; chr<MSG_RX_BUF_SIZE ; chr++)
{
if (UARTRxBuf[PcPort-1][chr] == '\r') {
UARTRxBuf[PcPort-1][chr] = 0;
return H0AR9_ERR_TERMINATED;
}
}
if (stopStream)
return H0AR9_ERR_TERMINATED;
}
vTaskDelay(pdMS_TO_TICKS(lastDelayMS));
return H0AR9_OK;
}
/* -----------------------------------------------------------------------
| APIs | |
/* -----------------------------------------------------------------------
*/
void SampleColorToPort(uint8_t port,uint8_t module)
{
float buffer[3]; // Three Samples RED, GREEN, BLUE
static uint8_t temp[12];
SampleColorBuf(buffer);
temp[0] =*((__IO uint8_t* )(&buffer[0]) + 3);
temp[1] =*((__IO uint8_t* )(&buffer[0]) + 2);
temp[2] =*((__IO uint8_t* )(&buffer[0]) + 1);
temp[3] =*((__IO uint8_t* )(&buffer[0]) + 0);
temp[4] =*((__IO uint8_t* )(&buffer[1]) + 3);
temp[5] =*((__IO uint8_t* )(&buffer[1]) + 2);
temp[6] =*((__IO uint8_t* )(&buffer[1]) + 1);
temp[7] =*((__IO uint8_t* )(&buffer[1]) + 0);
temp[8] =*((__IO uint8_t* )(&buffer[2]) + 3);
temp[9] =*((__IO uint8_t* )(&buffer[2]) + 2);
temp[10] =*((__IO uint8_t* )(&buffer[2]) + 1);
temp[11] =*((__IO uint8_t* )(&buffer[2]) + 0);
writePxITMutex(port,(char* )&temp[0],12 * sizeof(uint8_t),10);
}
/*-----------------------------------------------------------*/
void SampleDistanceToPort(uint8_t port,uint8_t module)
{
float buffer[1]; // Three Samples X, Y, Z
static uint8_t temp[4];
SampleDistanceBuff(buffer);
temp[0] =*((__IO uint8_t* )(&buffer[0]) + 3);
temp[1] =*((__IO uint8_t* )(&buffer[0]) + 2);
temp[2] =*((__IO uint8_t* )(&buffer[0]) + 1);
temp[3] =*((__IO uint8_t* )(&buffer[0]) + 0);
writePxITMutex(port,(char* )&temp[0],4 * sizeof(uint8_t),10);
}
/*-----------------------------------------------------------*/
void SampleTemperatureToPort(uint8_t port,uint8_t module)
{
float buffer[1];
static uint8_t temp[4];
SampleTemperatureBuf(buffer);
if(module == myID){
temp[0] =*((__IO uint8_t* )(&buffer[0]) + 3);
temp[1] =*((__IO uint8_t* )(&buffer[0]) + 2);
temp[2] =*((__IO uint8_t* )(&buffer[0]) + 1);
temp[3] =*((__IO uint8_t* )(&buffer[0]) + 0);
writePxITMutex(port,(char* )&temp[0],4 * sizeof(uint8_t),10);
}
else{
messageParams[0] =port;
messageParams[1] =*((__IO uint8_t* )(&buffer[0]) + 3);
messageParams[2] =*((__IO uint8_t* )(&buffer[0]) + 2);
messageParams[3] =*((__IO uint8_t* )(&buffer[0]) + 1);
messageParams[4] =*((__IO uint8_t* )(&buffer[0]) + 0);
SendMessageToModule(module,CODE_PORT_FORWARD,sizeof(float)+1);
}
}
/*-----------------------------------------------------------*/
void SampleHumidityToPort(uint8_t port,uint8_t module)
{
float buffer[1];
static uint8_t temp[4];
SampleHumidityBuf(buffer);
temp[0] =*((__IO uint8_t* )(&buffer[0]) + 3);
temp[1] =*((__IO uint8_t* )(&buffer[0]) + 2);
temp[2] =*((__IO uint8_t* )(&buffer[0]) + 1);
temp[3] =*((__IO uint8_t* )(&buffer[0]) + 0);
writePxITMutex(port,(char* )&temp[0],4 * sizeof(uint8_t),10);
}
/*-----------------------------------------------------------*/
void SamplePIRToPort(uint8_t port,uint8_t module)
{
float buffer;
bool temp;
SamplePIRBuf(&buffer);
if(module == myID){
temp = buffer;
writePxITMutex(port,(char* )&temp,sizeof(bool),10);
}
else{
messageParams[0] =port;
messageParams[1] =buffer;
SendMessageToModule(module,CODE_PORT_FORWARD,sizeof(char)+1);
}
}
/*-----------------------------------------------------------*/
void SampleColorBuf(float *buffer)
{
uint16_t rgb[3];
SampleColor(rgb,rgb+1,rgb+2);
buffer[0]=rgb[0];
buffer[1]=rgb[1];
buffer[2]=rgb[2];
}
/*-----------------------------------------------------------*/
void SampleDistanceBuff(float *buffer)
{
uint16_t distance;
SampleDistance(&distance);
*buffer = distance;
}
/*-----------------------------------------------------------*/
void SampleTemperatureBuf(float *buffer)
{
SampleTemperature(buffer);
}
/*-----------------------------------------------------------*/
void SampleHumidityBuf(float *buffer)
{
SampleHumidity(buffer);
}
/*-----------------------------------------------------------*/
void SamplePIRBuf(float *buffer)
{
bool pir;
SamplePIR(&pir);
*buffer = pir;
}
/*-----------------------------------------------------------*/
void SampleColorToString(char *cstring, size_t maxLen)
{
uint16_t red = 0, green = 0, blue = 0;
SampleColor(&red, &green, &blue);
Red=red;
Green=green;
Blue=blue;
snprintf(cstring, maxLen, "Red: %d, Green: %d, Blue: %d\r\n", red, green, blue);
}
/*-----------------------------------------------------------*/
void SampleDistanceToString(char *cstring, size_t maxLen)
{
uint16_t distance = 0;
SampleDistance(&distance);
distance1=distance;
snprintf(cstring, maxLen, "Distance: %d\r\n", distance);
}
/*-----------------------------------------------------------*/
void SampleTemperatureToString(char *cstring, size_t maxLen)
{
float temprature = 0;
SampleTemperature(&temprature);
temp=temprature;
char Number[5]={0};
uint16_t x;
volatile uint32_t temp1=1;
uint16_t x0,x1,x2;
temp1=temp;
x0 = (uint8_t) (temp*10 - temp1*10);
x1 = (uint8_t) (temp1%10);
x2 = (uint8_t) (temp1/10%10);
if(x2 == 0) {Number[0] = 0x20;} else {Number[0] = x2 +0x30;}
Number[1] = x1 +0x30;
Number[2] = '.';
Number[3] = x0 +0x30;
Number[4] = 0;
// x=*((long long*)&temp);
// temp=atoff(Number);
snprintf(cstring, maxLen, "Temperature: %.4s\r\n", Number);
}
/*-----------------------------------------------------------*/
void SampleHumidityToString(char *cstring, size_t maxLen)
{
float humidity = 0;
SampleHumidity(&humidity);
hum=humidity;
char Number[5]={0};
uint16_t x;
volatile uint32_t temp1=1;
uint16_t x0,x1,x2;
temp1=hum;
x0 = (uint8_t) (hum*10 - temp1*10);
x1 = (uint8_t) (temp1%10);
x2 = (uint8_t) (temp1/10%10);
if(x2 == 0) {Number[0] = 0x20;} else {Number[0] = x2 +0x30;}
Number[1] = x1 +0x30;
Number[2] = '.';
Number[3] = x0 +0x30;
Number[4] = 0;
snprintf(cstring, maxLen, "Humidity: %.4s\r\n", Number);
}
/*-----------------------------------------------------------*/
void SamplePIRToString(char *cstring, size_t maxLen)
{
bool sample;
SamplePIR(&sample);
Sample=sample;
snprintf(cstring, maxLen, "PIR: %d\r\n", sample);
}
/*-----------------------------------------------------------*/
void SampleTemperature(float *temperature)
{
buf[0] = tempReg;
HAL_I2C_Master_Transmit(&hi2c2, tempHumAdd, buf, 1, HAL_MAX_DELAY);
HAL_Delay(20);
HAL_I2C_Master_Receive(&hi2c2, tempHumAdd, buf, 2, HAL_MAX_DELAY);
val = buf[0] << 8 | buf[1];
*temperature=((float)val/65536)*165.0-40.0;
}
/*-----------------------------------------------------------*/
void SampleColor(uint16_t *Red, uint16_t *Green, uint16_t *Blue)
{
*Red = Read_Word(redReg);
*Green = Read_Word(greenReg);
*Blue = Read_Word(blueReg);
}
/*-----------------------------------------------------------*/
void SampleDistance(uint16_t *distance)
{
*distance = Read_Word(distanceReg)/6.39;
}
/*-----------------------------------------------------------*/
void SampleHumidity(float *humidity)
{
buf[0] = humidityReg;
HAL_I2C_Master_Transmit(&hi2c2, tempHumAdd, buf, 1, HAL_MAX_DELAY);
HAL_Delay(20);
HAL_I2C_Master_Receive(&hi2c2, tempHumAdd, buf, 2, HAL_MAX_DELAY);
val = buf[0] << 8 | buf[1];
*humidity = (((float)val*100)/65536);
}
/*-----------------------------------------------------------*/
void SamplePIR(bool *pir)
{
*pir=HAL_GPIO_ReadPin(GPIOB, GPIO_PIN_6);/* USER CODE END WHILE */
Delay_ms(2000);
}
/*-----------------------------------------------------------*/
Module_Status StreamColorToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout)
{
return StreamMemsToPort(port, module, period, timeout, SampleColorToPort);
}
/*-----------------------------------------------------------*/
Module_Status StreamDistanceToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout)
{
return StreamMemsToPort(port, module, period, timeout, SampleDistanceToPort);
}
/*-----------------------------------------------------------*/
Module_Status StreamTemperatureToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout)
{
return StreamMemsToPort(port, module, period, timeout, SampleTemperatureToPort);
}
/*-----------------------------------------------------------*/
Module_Status StreamHumidityToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout)
{
return StreamMemsToPort(port, module, period, timeout, SampleHumidityToPort);
}
/*-----------------------------------------------------------*/
Module_Status StreamPIRToPort(uint8_t port, uint8_t module, uint32_t period, uint32_t timeout)
{
return StreamMemsToPort(port, module, period, timeout, SamplePIRToPort);
}
/*-----------------------------------------------------------*/
Module_Status StreamColorToBuffer(float *buffer, uint32_t period, uint32_t timeout)
{
return StreamMemsToBuf(buffer, period, timeout, SampleColorBuf);
}
...
This file has been truncated, please download it to see its full contents.
/*
BitzOS (BOS) V0.2.9 - Copyright (C) 2017-2023 Hexabitz
All rights reserved
File Name : H0AR9_gpio.c
Description : Source code provides code for the configuration of all used GPIO pins .
*/
/* Includes ------------------------------------------------------------------*/
#include "BOS.h"
/* */
BOS_Status GetPortGPIOs(uint8_t port,uint32_t *TX_Port,uint16_t *TX_Pin,uint32_t *RX_Port,uint16_t *RX_Pin);
/*----------------------------------------------------------------------------*/
/* Configure GPIO */
/*----------------------------------------------------------------------------*/
/** Pinout Configuration
*/
void GPIO_Init(void){
/* GPIO Ports Clock Enable */
__GPIOC_CLK_ENABLE();
__GPIOA_CLK_ENABLE();
__GPIOD_CLK_ENABLE();
__GPIOB_CLK_ENABLE();
__GPIOF_CLK_ENABLE(); // for HSE and Boot0
IND_LED_Init();
}
//-- Configure indicator LED
void IND_LED_Init(void){
GPIO_InitTypeDef GPIO_InitStruct;
GPIO_InitStruct.Pin = _IND_LED_PIN;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(_IND_LED_PORT,&GPIO_InitStruct);
GPIO_InitStruct.Pin = GPIO_PIN_8;
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
HAL_GPIO_Init(GPIOB,&GPIO_InitStruct);
}
/*-----------------------------------------------------------*/
void SENSORS_GPIO_Init(void)
{
GPIO_InitTypeDef GPIO_InitStruct;
/**I2C2 GPIO Configuration
PA6 ------> I2C2_SDA
PA7 ------> I2C2_SCL
*/
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
GPIO_InitStruct.Alternate = GPIO_AF8_I2C2;
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
__HAL_RCC_I2C2_CLK_ENABLE();
/*Configure GPIO pin : PB6 as output*/
GPIO_InitStruct.Pin = GPIO_PIN_6;
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}
/*-----------------------------------------------------------*/
/* --- Check for factory reset condition:
- P1 TXD is connected to last port RXD
*/
uint8_t IsFactoryReset(void){
GPIO_InitTypeDef GPIO_InitStruct;
uint32_t P1_TX_Port, P1_RX_Port, P_last_TX_Port, P_last_RX_Port;
uint16_t P1_TX_Pin, P1_RX_Pin, P_last_TX_Pin, P_last_RX_Pin;
/* -- Setup GPIOs -- */
/* Enable all GPIO Ports Clocks */
__GPIOA_CLK_ENABLE();
__GPIOB_CLK_ENABLE();
__GPIOC_CLK_ENABLE();
__GPIOD_CLK_ENABLE();
/* Get GPIOs */
GetPortGPIOs(P1,&P1_TX_Port,&P1_TX_Pin,&P1_RX_Port,&P1_RX_Pin);
GetPortGPIOs(P_LAST,&P_last_TX_Port,&P_last_TX_Pin,&P_last_RX_Port,&P_last_RX_Pin);
/* TXD of first port */
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
GPIO_InitStruct.Pull = GPIO_NOPULL;
GPIO_InitStruct.Pin =P1_TX_Pin;
HAL_GPIO_Init((GPIO_TypeDef* )P1_TX_Port,&GPIO_InitStruct);
/* RXD of last port */
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
GPIO_InitStruct.Pull = GPIO_PULLDOWN;
GPIO_InitStruct.Pin =P_last_RX_Pin;
HAL_GPIO_Init((GPIO_TypeDef* )P_last_RX_Port,&GPIO_InitStruct);
/* Check for factory reset conditions */
HAL_GPIO_WritePin((GPIO_TypeDef* )P1_TX_Port,P1_TX_Pin,GPIO_PIN_RESET);
Delay_ms_no_rtos(5);
if(HAL_GPIO_ReadPin((GPIO_TypeDef* )P_last_RX_Port,P_last_RX_Pin) == RESET){
HAL_GPIO_WritePin((GPIO_TypeDef* )P1_TX_Port,P1_TX_Pin,GPIO_PIN_SET);
Delay_ms_no_rtos(5);
if(HAL_GPIO_ReadPin((GPIO_TypeDef* )P_last_RX_Port,P_last_RX_Pin) == SET){
return 1;
}
}
/* Clear flag for formated EEPROM if it was already set */
/* Flag address (STM32F09x) - Last 4 words of SRAM */
*((unsigned long* )0x20007FF0) =0xFFFFFFFF;
return 0;
}
/*-----------------------------------------------------------*/
/* --- Get GPIO pins and ports of this array port
*/
BOS_Status GetPortGPIOs(uint8_t port,uint32_t *TX_Port,uint16_t *TX_Pin,uint32_t *RX_Port,uint16_t *RX_Pin){
BOS_Status result =BOS_OK;
/* Get port UART */
UART_HandleTypeDef *huart =GetUart(port);
if(huart == &huart1){
#ifdef _Usart1
*TX_Port =(uint32_t ) USART1_TX_PORT;
*TX_Pin = USART1_TX_PIN;
*RX_Port =(uint32_t ) USART1_RX_PORT;
*RX_Pin = USART1_RX_PIN;
#endif
}
#ifdef _Usart2
else if(huart == &huart2){
*TX_Port =(uint32_t ) USART2_TX_PORT;
*TX_Pin = USART2_TX_PIN;
*RX_Port =(uint32_t ) USART2_RX_PORT;
*RX_Pin = USART2_RX_PIN;
}
#endif
#ifdef _Usart3
else if(huart == &huart3){
*TX_Port =(uint32_t ) USART3_TX_PORT;
*TX_Pin = USART3_TX_PIN;
*RX_Port =(uint32_t ) USART3_RX_PORT;
*RX_Pin = USART3_RX_PIN;
}
#endif
#ifdef _Usart4
else if(huart == &huart4){
*TX_Port =(uint32_t ) USART4_TX_PORT;
*TX_Pin = USART4_TX_PIN;
*RX_Port =(uint32_t ) USART4_RX_PORT;
*RX_Pin = USART4_RX_PIN;
}
#endif
#ifdef _Usart5
else if(huart == &huart5){
*TX_Port =(uint32_t ) USART5_TX_PORT;
*TX_Pin = USART5_TX_PIN;
*RX_Port =(uint32_t ) USART5_RX_PORT;
*RX_Pin = USART5_RX_PIN;
}
#endif
#ifdef _Usart6
else if(huart == &huart6){
*TX_Port =(uint32_t ) USART6_TX_PORT;
*TX_Pin = USART6_TX_PIN;
*RX_Port =(uint32_t ) USART6_RX_PORT;
*RX_Pin = USART6_RX_PIN;
}
#endif
#ifdef _Usart7
else if (huart == &huart7)
{
*TX_Port = (uint32_t)USART7_TX_PORT;
*TX_Pin = USART7_TX_PIN;
*RX_Port = (uint32_t)USART7_RX_PORT;
*RX_Pin = USART7_RX_PIN;
}
#endif
#ifdef _Usart8
else if (huart == &huart8)
{
*TX_Port = (uint32_t)USART8_TX_PORT;
*TX_Pin = USART8_TX_PIN;
*RX_Port = (uint32_t)USART8_RX_PORT;
*RX_Pin = USART8_RX_PIN;
}
#endif
else
result =BOS_ERROR;
return result;
}
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
Comments