Empty I2C Slave

This commit is contained in:
Samuel 2025-05-03 14:56:56 +02:00
parent 0cd6b9b6db
commit a7291c4cda
18 changed files with 15 additions and 2767 deletions

View File

@ -2,7 +2,7 @@ cmake_minimum_required(VERSION 3.13)
include(pico_sdk_import.cmake)
project(Detection2023 C CXX ASM)
project(I2C_Slave C CXX ASM)
set(CMAKE_C_STNDARD 11)
set(CMAKE_CXX_STANDARD 17)
@ -10,23 +10,12 @@ set(PICO_EXAMPLES_PATH ${PROJECT_SOURCE_DIR})
pico_sdk_init()
add_executable(Detection2023
add_executable(I2C_Slave
main.c
i2c_slave.c
vl53l1_platform.c
VL53L1X_api.c
VL53L1X_calibration.c
VL53L1X_Fonctions.c
ws2812.c
SelectionCapteur.c
Tests.c
)
# generate the header file into the source tree as it is included in the RP2040 datasheet
pico_generate_pio_header(Detection2023 ${CMAKE_CURRENT_LIST_DIR}/ws2812.pio)
target_link_libraries(Detection2023
target_link_libraries(I2C_Slave
hardware_i2c
hardware_uart
hardware_pio
@ -34,12 +23,12 @@ target_link_libraries(Detection2023
pico_multicore
)
pico_enable_stdio_usb(Detection2023 1)
pico_enable_stdio_uart(Detection2023 1)
pico_enable_stdio_usb(I2C_Slave 1)
pico_enable_stdio_uart(I2C_Slave 1)
pico_add_extra_outputs(Detection2023)
pico_add_extra_outputs(I2C_Slave)
add_custom_target(Flash
DEPENDS Detection2023
COMMAND sudo picotool load -f ${PROJECT_BINARY_DIR}/Detection2023.uf2
DEPENDS I2C_Slave
COMMAND sudo picotool load -f ${PROJECT_BINARY_DIR}/I2C_Slave.uf2
)

View File

@ -1,46 +0,0 @@
#include "pico/stdlib.h"
#include "SelectionCapteur.h"
#define PIN_ADRESSE_A0 5
#define PIN_ADRESSE_A1 4
#define PIN_ADRESSE_A2 3
#define PIN_ADRESSE_A3 2
#define PIN_COM 6
void Selection_capteur_init_pin_low(uint pin);
void Selection_capteur_init(void){
Selection_capteur_init_pin_low(PIN_COM);
Selection_capteur_init_pin_low(PIN_ADRESSE_A0);
Selection_capteur_init_pin_low(PIN_ADRESSE_A1);
Selection_capteur_init_pin_low(PIN_ADRESSE_A2);
Selection_capteur_init_pin_low(PIN_ADRESSE_A3);
Selection_capteur_deselect();
}
/// @brief Désactive le capteur en question
/// @param capteur capteur, numéroté de 0 à 11
void Selection_capteur_select(uint32_t capteur){
uint32_t io_value;
io_value = 0;
io_value |= ((capteur & 0x08) >> 3) << 2;
io_value |= ((capteur & 0x04) >> 2) << 3;
io_value |= ((capteur & 0x02) >> 1) << 4;
io_value |= (capteur & 0x01) << 5;
gpio_put_masked(0b111100, io_value);
}
void Selection_capteur_init_pin_low(uint pin){
gpio_init(pin);
gpio_set_dir(pin, GPIO_OUT);
gpio_put(pin, 0);
}
void Selection_capteur_deselect(){
Selection_capteur_select(15);
}

View File

@ -1,5 +0,0 @@
#include "pico/stdlib.h"
void Selection_capteur_init(void);
void Selection_capteur_select(uint32_t capteur);
void Selection_capteur_deselect(void);

138
Tests.c
View File

@ -1,138 +0,0 @@
#include "pico/stdlib.h"
#include "pico/multicore.h"
#include <stdio.h>
#include "ws2812.h"
#include "VL53L1X_Fonctions.h"
void display_menu();
void test_couleur_led();
#define TEST_TIMEOUT_US 10000000
void blink_test(void){
const uint LED_PIN = PICO_DEFAULT_LED_PIN;
uint8_t * distance_capteur_cm = get_distance_capteur_cm();
while(1){
for(uint8_t capteur=0; capteur<12; capteur++){
printf(">distance%x:%d\n", capteur, distance_capteur_cm[capteur]);
}
sleep_ms(50);
}
}
void Tests(void){
int answer_at_least_once=0;
uint8_t VL53L1X_device = 0x31;
while(1){
int keycode;
display_menu();
do{
keycode = getchar_timeout_us(TEST_TIMEOUT_US);
if(!answer_at_least_once){
display_menu();
}
}while(keycode == PICO_ERROR_TIMEOUT || keycode == 0);
answer_at_least_once = 1;
switch (keycode)
{
case 'a':
case 'A':
printf("Changement d'adresse\n");
change_address(&VL53L1X_device, VL53L1X_device + 3);
printf("New address: %d\n", VL53L1X_device);
break;
case 'c':
case 'C':
printf("Affichage couleur sur LED\n");
test_couleur_led();
break;
case 'd':
case 'D':
printf("Reset affichage couleur sur LED\n");
reset_affichage_led();
break;
case 'i':
case 'I':
printf("Initialisation des capteurs\n");
initialise_adresses();
break;
case 'j':
case 'J':
printf("Lecture continue des capteurs inutilisés.\nAppuyer sur une touche pour quitter\n");
multicore_launch_core1(blink_test);
do{
static uint8_t capteur_courant=0;
uint8_t * distance_capteur_cm = get_distance_capteur_cm();
keycode = getchar_timeout_us(0);
// Lecture des capteurs
if(capteur_pret(capteur_courant)){
uint8_t distance_cm;
if(capteur_lire_distance_cm(capteur_courant, &distance_cm)){
distance_capteur_cm[capteur_courant]= distance_cm;
}
}
capteur_courant++;
if(capteur_courant > 11){
capteur_courant = 0;
}
// Affichage des distances sur les LEDs.
affiche_distance_sur_led(distance_capteur_cm);
}while(keycode == PICO_ERROR_TIMEOUT || keycode == 0);
break;
case 'k':
case 'K':
ws2812_arc_en_ciel();
break;
case 'l':
case 'L':
while(continuous_reading(0x38));
break;
case 'o':
case 'O':
while(calibration(VL53L1X_device));
break;
case 'r':
case 'R':
while(continuous_reading(VL53L1X_device));
break;
default :
break;
}
}
}
void display_menu(){
printf("Select action :\n");
printf("A - Change I2C address\n");
printf("C - Couleur Led\n");
printf("I - Init I2C address\n");
printf("J - Lecture distance multiple\n");
printf("K - Arc en ciel\n");
printf("L - Lecture distance capteur 1\n");
printf("O - Offset Calibration\n");
printf("R - Read distance\n");
}
/// @brief Force une couleur sur une led qui ne doit pas être effacée par la distance lue par le capteur.
/// A utiliser après l'initialisation des catpeurs et avant la lecture continue
void test_couleur_led(){
unsigned int couleur, led;
int scanf1, scanf2;
printf("Choississez la led (0 - 11)\n");
scanf1 = scanf("%u", &led);
printf("Choississez la couleur (0 - 255)\n");
scanf2 = scanf("%u", &couleur);
if(scanf1 == 1 && scanf2 == 1){
printf("Actualisation de la led %d avec la couleur %d\n", led, couleur);
affiche_couleur_sur_led(couleur, led);
}else{
printf("Erreur scanf...\n");
}
ws2812_affiche_buffer();
}

View File

@ -1 +0,0 @@
void Tests(void);

View File

@ -1,313 +0,0 @@
#include "pico/stdlib.h"
#include <stdio.h>
#include "VL53L1X_api.h"
#include "VL53L1X_calibration.h"
#include "VL53L1X_Fonctions.h"
#include "SelectionCapteur.h"
#include "ws2812.h"
#define DISTANCE_TROP_LOIN_CM 200 /* Distance de saturation */
#define DISTANCE_TRES_LOIN_CM 120 /* Seuil min. pour la couleur bleu*/
#define DISTANCE_LOIN_CM 80 /* Seuil min. pour la couleur verte*/
#define DISTANCE_PROCHE_CM 15 /* Seuil entre violet et jaune*/
#define NB_CAPTEURS 12
#define ADRESSE_I2C_BASE 0x31
// Stock les valeurs lues des capteurs
uint8_t distance_capteur_cm[12];
uint8_t statu_capteurs[13];
enum {
MODE_DISTANCE,
MODE_MANUEL
} mode_led[NB_CAPTEURS];
uint8_t * get_distance_capteur_cm(void){
return distance_capteur_cm;
}
void reset_affichage_led(void);
void initialise_adresses(void){
const uint8_t tmp_i2c_adresse = 0x28;
const uint8_t default_i2c_adresse = 0x29;
uint8_t adresse = default_i2c_adresse;
// On change l'adresse de tous les capteurs
Selection_capteur_deselect();
change_address(&adresse, tmp_i2c_adresse);
reset_affichage_led();
// Pour chaque capteur
for(uint capteur=0; capteur<NB_CAPTEURS; capteur++){
// reset du capteur
Selection_capteur_select(capteur);
sleep_ms(1);
Selection_capteur_deselect();
sleep_ms(1);
uint8_t VL53L1X_device = 0x29;
if(change_address(&VL53L1X_device, ADRESSE_I2C_BASE + capteur)){
printf("Erreur change adresse : %x => %x, capteur : %d\n", VL53L1X_device, ADRESSE_I2C_BASE + capteur, capteur);
ws2812_set_buffer_rgb(0x4, 0, 0, capteur);
statu_capteurs[capteur]=0;
}else{
if(VL53L1X_SensorInit(VL53L1X_device)){
// bad init
ws2812_set_buffer_rgb(0x4, 0, 0, capteur);
statu_capteurs[capteur]=0;
}else{
// good init
statu_capteurs[capteur]=1;
int status;
status = VL53L1X_SetDistanceMode (VL53L1X_device, 1); // Short mode
status |= VL53L1X_SetInterMeasurementInMs(VL53L1X_device, 200);
status |= VL53L1X_SetTimingBudgetInMs(VL53L1X_device, 200);
if(status){
printf("Custom config KO, error %d\n", status);
ws2812_set_buffer_rgb(0x4, 0, 0, capteur);
}else{
printf("Custom config OK\n");
}
status=VL53L1X_StartRanging(VL53L1X_device);
if(!status){
ws2812_set_buffer_rgb(0, 0x4, 0, capteur-1);
}else{
ws2812_set_buffer_rgb(0x2, 0x2, 0, capteur-1);
mode_led[capteur-1]=MODE_DISTANCE;
}
}
}
}
ws2812_affiche_buffer();
ws2812_affiche_buffer();
}
int change_address(uint8_t *device, uint8_t new_i2c_7bits_address){
int status;
status = VL53L1X_SetI2CAddress(*device, new_i2c_7bits_address << 1);
if(status){
//printf("VL53L1X_SetI2CAddress, Error :%d\n", status);
}else{
*device=new_i2c_7bits_address;
}
return status;
}
/// @brief Renvoie 1 si capteur prêt
/// @param capteur : capteur à interroger, entre 0 et 11
/// @return 1 si prêt, 0 si pas prêt, -1 si erreur
int capteur_pret(uint8_t capteur){
int status;
uint8_t data_ready = 0;
if(statu_capteurs[capteur]==0){
printf("capteur non prêt:%d\n",capteur);
return 0;
}
status=VL53L1X_CheckForDataReady(capteur + ADRESSE_I2C_BASE, &data_ready);
if(status){
printf("CheckForDataReady KO, error %d, capteur:%x\n", status, capteur + ADRESSE_I2C_BASE);
return 1;
}
return data_ready;
}
/// @brief Lecture d'un capteur prêt.
/// @param capteur : identifiant du capteur entre 0 et 11
/// @return 1 si la lecture s'est bien passée, 0 sinon.
int capteur_lire_distance_cm(uint8_t capteur, uint8_t * distance_cm){
int status;
uint16_t distance_mm;
uint8_t range_status;
status=VL53L1X_GetDistance(capteur + ADRESSE_I2C_BASE, &distance_mm);
if(status){
printf("GetDistance KO, error %d, capteur:%x\n", status, capteur + ADRESSE_I2C_BASE);
return 0;
}
status=VL53L1X_GetRangeStatus(capteur + ADRESSE_I2C_BASE, &range_status);
if(status){
printf("GetRangeStatus KO, error %d, capteur:%x\n", status, capteur + ADRESSE_I2C_BASE);
return 0;
}
if(range_status == 0){
if(distance_mm/10 < (uint16_t) DISTANCE_TROP_LOIN_CM){
*distance_cm = distance_mm / 10;
}else{
*distance_cm = DISTANCE_TROP_LOIN_CM;
}
}else{
*distance_cm = DISTANCE_TROP_LOIN_CM;
}
status=VL53L1X_ClearInterrupt(capteur + ADRESSE_I2C_BASE);
if(status){
printf("ClearInterrupt KO, error %d, capteur:%x\n", status, capteur + ADRESSE_I2C_BASE);
return 0;
}
return 1;
}
void affiche_distance_sur_led(unsigned char * distance_capteur_cm){
uint8_t distance_cm;
uint32_t couleur;
for(uint8_t capteur=0; capteur<12; capteur++){
if(mode_led[capteur] == MODE_DISTANCE){
distance_cm = distance_capteur_cm[capteur];
if(distance_cm == 0 ||distance_cm > DISTANCE_TRES_LOIN_CM){
ws2812_set_buffer_rgb(COULEUR_TRES_LOIN, capteur);
}else if(distance_cm > DISTANCE_LOIN_CM){
ws2812_set_buffer_rgb(COULEUR_LOIN, capteur);
}else if(distance_cm > DISTANCE_PROCHE_CM){
ws2812_set_buffer_rgb(COULEUR_PROCHE, capteur);
}else{
ws2812_set_buffer_rgb(COULEUR_TROP_PROCHE, capteur);
}
}
}
ws2812_affiche_buffer();
}
void affiche_couleur_sur_led(uint8_t couleur_8bits, uint8_t led){
mode_led[led] = MODE_MANUEL;
ws2812_set_buffer_8bits(couleur_8bits, led);
}
/// @brief Remet toutes les LEDs en mode d'affichage de la distance
void reset_affichage_led(){
for(uint8_t capteur=0; capteur<12; capteur++){
mode_led[capteur] = MODE_DISTANCE;
}
}
int calibration(uint8_t device){
uint16_t offset;
uint16_t x_talk;
int status;
uint8_t boot_state=0;
printf("Calibration...\n");
while(!boot_state){
VL53L1X_BootState(device, &boot_state);
}
printf("Sensor boot ok\n");
status=VL53L1X_SensorInit(device);
if(status){
printf("Sensor Init KO, error %d\n", status);
}else{
printf("Sensor Init OK\n");
}
status = VL53L1X_CalibrateOffset(device, 140, &offset);
if(status != 0){
printf("Error while calibrating : %d\n",status);
}else{
printf("Offset : %d\n", offset);
}
/*
// Renvoie x_talk = 0 si la calibration se passe bien car
// nous n'avons pas de vitre de protection devant le capteur
status = VL53L1X_CalibrateXtalk(device, 1000, &x_talk);
if(status != 0){
printf("Error while calibrating : %d\n",status);
}else{
printf("xTalk : %d\n", x_talk);
}
*/
return 0;
}
int continuous_reading(uint8_t device){
int status;
uint8_t data_ready, boot_state=0;
uint16_t distance;
printf("Reading distance...\nSend any character to quit.\n");
while(!boot_state){
VL53L1X_BootState(device, &boot_state);
}
printf("Sensor boot ok\n");
status=VL53L1X_SensorInit(device);
if(status){
printf("Sensor Init KO, error %d\n", status);
return 0;
}else{
printf("Sensor Init OK\n");
}
// Custom configuration
status = VL53L1X_SetDistanceMode (device, 1); // Short mode
status |= VL53L1X_SetInterMeasurementInMs(device, 200);
status |= VL53L1X_SetTimingBudgetInMs(device, 200);
if(status){
printf("Custom config KO, error %d\n", status);
return 0;
}else{
printf("Custom config OK\n");
}
status=VL53L1X_StartRanging(device);
if(status){
printf("Start ranging KO, error %d\n", status);
return 0;
}else{
printf("Start ranging OK\n");
}
while(1){
// Reading data
data_ready = 0;
while(!data_ready){
status=VL53L1X_CheckForDataReady(device, &data_ready);
if(status){
printf("CheckForDataReady KO, error %d\n", status);
return 0;
}else{
//printf("CheckForDataReady OK\n");
}
}
status=VL53L1X_GetDistance(device, &distance);
if(status){
printf("GetDistance KO, error %d\n", status);
return 0;
}else{
//printf("GetDistance OK, distance %u mm\n", distance);
printf(">distance:%d\n", distance);
}
status=VL53L1X_ClearInterrupt(device);
if(status){
printf("ClearInterrupt KO, error %d\n", status);
return 0;
}else{
//printf("ClearInterrupt OK\n");
}
int lettre = getchar_timeout_us(0);
if(lettre != PICO_ERROR_TIMEOUT && lettre != 0){
return 0;
}
}
return 0;
}

View File

@ -1,26 +0,0 @@
#include "pico/stdlib.h"
// Couleur quand la distance est trop loin pour s'en servir avec fiabilité
#define COULEUR_TRES_LOIN 0x00, 0x00, 0x01
// Couleur quand la distance fiable mais loin
#define COULEUR_LOIN 0x00, 0x01, 0x00
// Couleur quand la distance fiable et que le robot doit ralentir
#define COULEUR_PROCHE 0x01, 0x01, 0x00
// Couleur trop proche : rien ne devrait être si près
#define COULEUR_TROP_PROCHE 0x01, 0x00, 0x01
int continuous_multiple_reading(void);
int continuous_special_reading(void);
void affiche_distance_sur_led(unsigned char *);
void affiche_couleur_sur_led(uint8_t couleur_8bits, uint8_t led);
void reset_affichage_led(void);
void initialise_adresses(void);
int change_address(uint8_t *device, uint8_t new_i2c_7bits_address);
int calibration(uint8_t device);
int continuous_reading(uint8_t device);
int capteur_pret(uint8_t capteur);
int capteur_lire_distance_cm(uint8_t capteur, uint8_t * distance_cm);
uint8_t * get_distance_capteur_cm(void);
extern uint8_t statu_capteurs[];

View File

@ -1,858 +0,0 @@
/*
Copyright (c) 2017, STMicroelectronics - All Rights Reserved
This file : part of VL53L1 Core and : dual licensed,
either 'STMicroelectronics
Proprietary license'
or 'BSD 3-clause "New" or "Revised" License' , at your option.
*******************************************************************************
'STMicroelectronics Proprietary license'
*******************************************************************************
License terms: STMicroelectronics Proprietary in accordance with licensing
terms at www.st.com/sla0081
STMicroelectronics confidential
Reproduction and Communication of this document : strictly prohibited unless
specifically authorized in writing by STMicroelectronics.
*******************************************************************************
Alternatively, VL53L1 Core may be distributed under the terms of
'BSD 3-clause "New" or "Revised" License', in which case the following
provisions apply instead of the ones mentioned above :
*******************************************************************************
License terms: BSD 3-clause "New" or "Revised" License.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions 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 the copyright holder nor the names of its contributors
may be used to endorse or promote products derived from this software
without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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.
*******************************************************************************
*/
/**
* @file vl53l1x_api.c
* @brief Functions implementation
*/
#include "VL53L1X_api.h"
#include <string.h>
#if 0
uint8_t VL51L1X_NVM_CONFIGURATION[] = {
0x00, /* 0x00 : not user-modifiable */
0x29, /* 0x01 : 7 bits I2C address (default=0x29), use SetI2CAddress(). Warning: after changing the register value to a new I2C address, the device will only answer to the new address */
0x00, /* 0x02 : not user-modifiable */
0x00, /* 0x03 : not user-modifiable */
0x00, /* 0x04 : not user-modifiable */
0x00, /* 0x05 : not user-modifiable */
0x00, /* 0x06 : not user-modifiable */
0x00, /* 0x07 : not user-modifiable */
0x00, /* 0x08 : not user-modifiable */
0x50, /* 0x09 : not user-modifiable */
0x00, /* 0x0A : not user-modifiable */
0x00, /* 0x0B : not user-modifiable */
0x00, /* 0x0C : not user-modifiable */
0x00, /* 0x0D : not user-modifiable */
0x0a, /* 0x0E : not user-modifiable */
0x00, /* 0x0F : not user-modifiable */
0x00, /* 0x10 : not user-modifiable */
0x00, /* 0x11 : not user-modifiable */
0x00, /* 0x12 : not user-modifiable */
0x00, /* 0x13 : not user-modifiable */
0x00, /* 0x14 : not user-modifiable */
0x00, /* 0x15 : not user-modifiable */
0x00, /* 0x16 : Xtalk calibration value MSB (7.9 format in kcps), use SetXtalk() */
0x00, /* 0x17 : Xtalk calibration value LSB */
0x00, /* 0x18 : not user-modifiable */
0x00, /* 0x19 : not user-modifiable */
0x00, /* 0x1a : not user-modifiable */
0x00, /* 0x1b : not user-modifiable */
0x00, /* 0x1e : Part to Part offset x4 MSB (in mm), use SetOffset() */
0x50, /* 0x1f : Part to Part offset x4 LSB */
0x00, /* 0x20 : not user-modifiable */
0x00, /* 0x21 : not user-modifiable */
0x00, /* 0x22 : not user-modifiable */
0x00, /* 0x23 : not user-modifiable */
}
#endif
const uint8_t VL51L1X_DEFAULT_CONFIGURATION[] = {
0x00, /* 0x2d : set bit 2 and 5 to 1 for fast plus mode (1MHz I2C), else don't touch */
0x00, /* 0x2e : bit 0 if I2C pulled up at 1.8V, else set bit 0 to 1 (pull up at AVDD) */
0x00, /* 0x2f : bit 0 if GPIO pulled up at 1.8V, else set bit 0 to 1 (pull up at AVDD) */
0x01, /* 0x30 : set bit 4 to 0 for active high interrupt and 1 for active low (bits 3:0 must be 0x1), use SetInterruptPolarity() */
0x02, /* 0x31 : bit 1 = interrupt depending on the polarity, use CheckForDataReady() */
0x00, /* 0x32 : not user-modifiable */
0x02, /* 0x33 : not user-modifiable */
0x08, /* 0x34 : not user-modifiable */
0x00, /* 0x35 : not user-modifiable */
0x08, /* 0x36 : not user-modifiable */
0x10, /* 0x37 : not user-modifiable */
0x01, /* 0x38 : not user-modifiable */
0x01, /* 0x39 : not user-modifiable */
0x00, /* 0x3a : not user-modifiable */
0x00, /* 0x3b : not user-modifiable */
0x00, /* 0x3c : not user-modifiable */
0x00, /* 0x3d : not user-modifiable */
0xff, /* 0x3e : not user-modifiable */
0x00, /* 0x3f : not user-modifiable */
0x0F, /* 0x40 : not user-modifiable */
0x00, /* 0x41 : not user-modifiable */
0x00, /* 0x42 : not user-modifiable */
0x00, /* 0x43 : not user-modifiable */
0x00, /* 0x44 : not user-modifiable */
0x00, /* 0x45 : not user-modifiable */
0x20, /* 0x46 : interrupt configuration 0->level low detection, 1-> level high, 2-> Out of window, 3->In window, 0x20-> New sample ready , TBC */
0x0b, /* 0x47 : not user-modifiable */
0x00, /* 0x48 : not user-modifiable */
0x00, /* 0x49 : not user-modifiable */
0x02, /* 0x4a : not user-modifiable */
0x0a, /* 0x4b : not user-modifiable */
0x21, /* 0x4c : not user-modifiable */
0x00, /* 0x4d : not user-modifiable */
0x00, /* 0x4e : not user-modifiable */
0x05, /* 0x4f : not user-modifiable */
0x00, /* 0x50 : not user-modifiable */
0x00, /* 0x51 : not user-modifiable */
0x00, /* 0x52 : not user-modifiable */
0x00, /* 0x53 : not user-modifiable */
0xc8, /* 0x54 : not user-modifiable */
0x00, /* 0x55 : not user-modifiable */
0x00, /* 0x56 : not user-modifiable */
0x38, /* 0x57 : not user-modifiable */
0xff, /* 0x58 : not user-modifiable */
0x01, /* 0x59 : not user-modifiable */
0x00, /* 0x5a : not user-modifiable */
0x08, /* 0x5b : not user-modifiable */
0x00, /* 0x5c : not user-modifiable */
0x00, /* 0x5d : not user-modifiable */
0x01, /* 0x5e : not user-modifiable */
0xcc, /* 0x5f : not user-modifiable */
0x0f, /* 0x60 : not user-modifiable */
0x01, /* 0x61 : not user-modifiable */
0xf1, /* 0x62 : not user-modifiable */
0x0d, /* 0x63 : not user-modifiable */
0x01, /* 0x64 : Sigma threshold MSB (mm in 14.2 format for MSB+LSB), use SetSigmaThreshold(), default value 90 mm */
0x68, /* 0x65 : Sigma threshold LSB */
0x00, /* 0x66 : Min count Rate MSB (MCPS in 9.7 format for MSB+LSB), use SetSignalThreshold() */
0x80, /* 0x67 : Min count Rate LSB */
0x08, /* 0x68 : not user-modifiable */
0xb8, /* 0x69 : not user-modifiable */
0x00, /* 0x6a : not user-modifiable */
0x00, /* 0x6b : not user-modifiable */
0x00, /* 0x6c : Intermeasurement period MSB, 32 bits register, use SetIntermeasurementInMs() */
0x00, /* 0x6d : Intermeasurement period */
0x0f, /* 0x6e : Intermeasurement period */
0x89, /* 0x6f : Intermeasurement period LSB */
0x00, /* 0x70 : not user-modifiable */
0x00, /* 0x71 : not user-modifiable */
0x00, /* 0x72 : distance threshold high MSB (in mm, MSB+LSB), use SetD:tanceThreshold() */
0x00, /* 0x73 : distance threshold high LSB */
0x00, /* 0x74 : distance threshold low MSB ( in mm, MSB+LSB), use SetD:tanceThreshold() */
0x00, /* 0x75 : distance threshold low LSB */
0x00, /* 0x76 : not user-modifiable */
0x01, /* 0x77 : not user-modifiable */
0x0f, /* 0x78 : not user-modifiable */
0x0d, /* 0x79 : not user-modifiable */
0x0e, /* 0x7a : not user-modifiable */
0x0e, /* 0x7b : not user-modifiable */
0x00, /* 0x7c : not user-modifiable */
0x00, /* 0x7d : not user-modifiable */
0x02, /* 0x7e : not user-modifiable */
0xc7, /* 0x7f : ROI center, use SetROI() */
0xff, /* 0x80 : XY ROI (X=Width, Y=Height), use SetROI() */
0x9B, /* 0x81 : not user-modifiable */
0x00, /* 0x82 : not user-modifiable */
0x00, /* 0x83 : not user-modifiable */
0x00, /* 0x84 : not user-modifiable */
0x01, /* 0x85 : not user-modifiable */
0x00, /* 0x86 : clear interrupt, use ClearInterrupt() */
0x00 /* 0x87 : start ranging, use StartRanging() or StopRanging(), If you want an automatic start after VL53L1X_init() call, put 0x40 in location 0x87 */
};
static const uint8_t status_rtn[24] = { 255, 255, 255, 5, 2, 4, 1, 7, 3, 0,
255, 255, 9, 13, 255, 255, 255, 255, 10, 6,
255, 255, 11, 12
};
VL53L1X_ERROR VL53L1X_GetSWVersion(VL53L1X_Version_t *pVersion)
{
VL53L1X_ERROR Status = 0;
pVersion->major = VL53L1X_IMPLEMENTATION_VER_MAJOR;
pVersion->minor = VL53L1X_IMPLEMENTATION_VER_MINOR;
pVersion->build = VL53L1X_IMPLEMENTATION_VER_SUB;
pVersion->revision = VL53L1X_IMPLEMENTATION_VER_REVISION;
return Status;
}
VL53L1X_ERROR VL53L1X_SetI2CAddress(uint16_t dev, uint8_t new_address)
{
VL53L1X_ERROR status = 0;
status |= VL53L1_WrByte(dev, VL53L1_I2C_SLAVE__DEVICE_ADDRESS, new_address >> 1);
return status;
}
VL53L1X_ERROR VL53L1X_SensorInit(uint16_t dev)
{
VL53L1X_ERROR status = 0;
uint8_t Addr = 0x00, tmp;
for (Addr = 0x2D; Addr <= 0x87; Addr++){
status |= VL53L1_WrByte(dev, Addr, VL51L1X_DEFAULT_CONFIGURATION[Addr - 0x2D]);
if(status){
return status;
}
}
status |= VL53L1X_StartRanging(dev);
tmp = 0;
while(tmp==0){
status |= VL53L1X_CheckForDataReady(dev, &tmp);
}
status |= VL53L1X_ClearInterrupt(dev);
status |= VL53L1X_StopRanging(dev);
status |= VL53L1_WrByte(dev, VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND, 0x09); /* two bounds VHV */
status |= VL53L1_WrByte(dev, 0x0B, 0); /* start VHV from the previous temperature */
return status;
}
VL53L1X_ERROR VL53L1X_ClearInterrupt(uint16_t dev)
{
VL53L1X_ERROR status = 0;
status |= VL53L1_WrByte(dev, SYSTEM__INTERRUPT_CLEAR, 0x01);
return status;
}
VL53L1X_ERROR VL53L1X_SetInterruptPolarity(uint16_t dev, uint8_t NewPolarity)
{
uint8_t Temp;
VL53L1X_ERROR status = 0;
status |= VL53L1_RdByte(dev, GPIO_HV_MUX__CTRL, &Temp);
Temp = Temp & 0xEF;
status |= VL53L1_WrByte(dev, GPIO_HV_MUX__CTRL, Temp | (!(NewPolarity & 1)) << 4);
return status;
}
VL53L1X_ERROR VL53L1X_GetInterruptPolarity(uint16_t dev, uint8_t *pInterruptPolarity)
{
uint8_t Temp;
VL53L1X_ERROR status = 0;
status |= VL53L1_RdByte(dev, GPIO_HV_MUX__CTRL, &Temp);
Temp = Temp & 0x10;
*pInterruptPolarity = !(Temp>>4);
return status;
}
VL53L1X_ERROR VL53L1X_StartRanging(uint16_t dev)
{
VL53L1X_ERROR status = 0;
status |= VL53L1_WrByte(dev, SYSTEM__MODE_START, 0x40); /* Enable VL53L1X */
return status;
}
VL53L1X_ERROR VL53L1X_StopRanging(uint16_t dev)
{
VL53L1X_ERROR status = 0;
status |= VL53L1_WrByte(dev, SYSTEM__MODE_START, 0x00); /* Disable VL53L1X */
return status;
}
VL53L1X_ERROR VL53L1X_CheckForDataReady(uint16_t dev, uint8_t *isDataReady)
{
uint8_t Temp;
uint8_t IntPol;
VL53L1X_ERROR status = 0;
status |= VL53L1X_GetInterruptPolarity(dev, &IntPol);
status |= VL53L1_RdByte(dev, GPIO__TIO_HV_STATUS, &Temp);
/* Read in the register to check if a new value is available */
if (status == 0){
if ((Temp & 1) == IntPol)
*isDataReady = 1;
else
*isDataReady = 0;
}
return status;
}
VL53L1X_ERROR VL53L1X_SetTimingBudgetInMs(uint16_t dev, uint16_t TimingBudgetInMs)
{
uint16_t DM;
VL53L1X_ERROR status=0;
status |= VL53L1X_GetDistanceMode(dev, &DM);
if (DM == 0)
return 1;
else if (DM == 1) { /* Short DistanceMode */
switch (TimingBudgetInMs) {
case 15: /* only available in short distance mode */
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x01D);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x0027);
break;
case 20:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x0051);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x006E);
break;
case 33:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x00D6);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x006E);
break;
case 50:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x1AE);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x01E8);
break;
case 100:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x02E1);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x0388);
break;
case 200:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x03E1);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x0496);
break;
case 500:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x0591);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x05C1);
break;
default:
status = 1;
break;
}
} else {
switch (TimingBudgetInMs) {
case 20:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x001E);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x0022);
break;
case 33:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x0060);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x006E);
break;
case 50:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x00AD);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x00C6);
break;
case 100:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x01CC);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x01EA);
break;
case 200:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x02D9);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x02F8);
break;
case 500:
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI,
0x048F);
VL53L1_WrWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_B_HI,
0x04A4);
break;
default:
status = 1;
break;
}
}
return status;
}
VL53L1X_ERROR VL53L1X_GetTimingBudgetInMs(uint16_t dev, uint16_t *pTimingBudget)
{
uint16_t Temp;
VL53L1X_ERROR status = 0;
status |= VL53L1_RdWord(dev, RANGE_CONFIG__TIMEOUT_MACROP_A_HI, &Temp);
switch (Temp) {
case 0x001D :
*pTimingBudget = 15;
break;
case 0x0051 :
case 0x001E :
*pTimingBudget = 20;
break;
case 0x00D6 :
case 0x0060 :
*pTimingBudget = 33;
break;
case 0x1AE :
case 0x00AD :
*pTimingBudget = 50;
break;
case 0x02E1 :
case 0x01CC :
*pTimingBudget = 100;
break;
case 0x03E1 :
case 0x02D9 :
*pTimingBudget = 200;
break;
case 0x0591 :
case 0x048F :
*pTimingBudget = 500;
break;
default:
status = 1;
*pTimingBudget = 0;
}
return status;
}
VL53L1X_ERROR VL53L1X_SetDistanceMode(uint16_t dev, uint16_t DM)
{
uint16_t TB;
VL53L1X_ERROR status = 0;
status |= VL53L1X_GetTimingBudgetInMs(dev, &TB);
if (status != 0)
return 1;
switch (DM) {
case 1:
status = VL53L1_WrByte(dev, PHASECAL_CONFIG__TIMEOUT_MACROP, 0x14);
status = VL53L1_WrByte(dev, RANGE_CONFIG__VCSEL_PERIOD_A, 0x07);
status = VL53L1_WrByte(dev, RANGE_CONFIG__VCSEL_PERIOD_B, 0x05);
status = VL53L1_WrByte(dev, RANGE_CONFIG__VALID_PHASE_HIGH, 0x38);
status = VL53L1_WrWord(dev, SD_CONFIG__WOI_SD0, 0x0705);
status = VL53L1_WrWord(dev, SD_CONFIG__INITIAL_PHASE_SD0, 0x0606);
break;
case 2:
status = VL53L1_WrByte(dev, PHASECAL_CONFIG__TIMEOUT_MACROP, 0x0A);
status = VL53L1_WrByte(dev, RANGE_CONFIG__VCSEL_PERIOD_A, 0x0F);
status = VL53L1_WrByte(dev, RANGE_CONFIG__VCSEL_PERIOD_B, 0x0D);
status = VL53L1_WrByte(dev, RANGE_CONFIG__VALID_PHASE_HIGH, 0xB8);
status = VL53L1_WrWord(dev, SD_CONFIG__WOI_SD0, 0x0F0D);
status = VL53L1_WrWord(dev, SD_CONFIG__INITIAL_PHASE_SD0, 0x0E0E);
break;
default:
status = 1;
break;
}
if (status == 0)
status |= VL53L1X_SetTimingBudgetInMs(dev, TB);
return status;
}
VL53L1X_ERROR VL53L1X_GetDistanceMode(uint16_t dev, uint16_t *DM)
{
uint8_t TempDM, status=0;
status |= VL53L1_RdByte(dev,PHASECAL_CONFIG__TIMEOUT_MACROP, &TempDM);
if (TempDM == 0x14)
*DM=1;
if(TempDM == 0x0A)
*DM=2;
return status;
}
VL53L1X_ERROR VL53L1X_SetInterMeasurementInMs(uint16_t dev, uint32_t InterMeasMs)
{
uint16_t ClockPLL;
VL53L1X_ERROR status = 0;
status |= VL53L1_RdWord(dev, VL53L1_RESULT__OSC_CALIBRATE_VAL, &ClockPLL);
ClockPLL = ClockPLL&0x3FF;
VL53L1_WrDWord(dev, VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD,
(uint32_t)(ClockPLL * InterMeasMs * 1.075));
return status;
}
VL53L1X_ERROR VL53L1X_GetInterMeasurementInMs(uint16_t dev, uint16_t *pIM)
{
uint16_t ClockPLL;
VL53L1X_ERROR status = 0;
uint32_t tmp;
status |= VL53L1_RdDWord(dev,VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD, &tmp);
*pIM = (uint16_t)tmp;
status |= VL53L1_RdWord(dev, VL53L1_RESULT__OSC_CALIBRATE_VAL, &ClockPLL);
ClockPLL = ClockPLL&0x3FF;
*pIM= (uint16_t)(*pIM/(ClockPLL*1.065));
return status;
}
VL53L1X_ERROR VL53L1X_BootState(uint16_t dev, uint8_t *state)
{
VL53L1X_ERROR status = 0;
uint8_t tmp = 0;
status |= VL53L1_RdByte(dev,VL53L1_FIRMWARE__SYSTEM_STATUS, &tmp);
*state = tmp;
return status;
}
VL53L1X_ERROR VL53L1X_GetSensorId(uint16_t dev, uint16_t *sensorId)
{
VL53L1X_ERROR status = 0;
uint16_t tmp = 0;
status |= VL53L1_RdWord(dev, VL53L1_IDENTIFICATION__MODEL_ID, &tmp);
*sensorId = tmp;
return status;
}
VL53L1X_ERROR VL53L1X_GetDistance(uint16_t dev, uint16_t *distance)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= (VL53L1_RdWord(dev,
VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0, &tmp));
*distance = tmp;
return status;
}
VL53L1X_ERROR VL53L1X_GetSignalPerSpad(uint16_t dev, uint16_t *signalRate)
{
VL53L1X_ERROR status = 0;
uint16_t SpNb=1, signal;
status |= VL53L1_RdWord(dev,
VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0, &signal);
status |= VL53L1_RdWord(dev,
VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0, &SpNb);
*signalRate = (uint16_t) (200.0*signal/SpNb);
return status;
}
VL53L1X_ERROR VL53L1X_GetAmbientPerSpad(uint16_t dev, uint16_t *ambPerSp)
{
VL53L1X_ERROR status = 0;
uint16_t AmbientRate, SpNb = 1;
status |= VL53L1_RdWord(dev, RESULT__AMBIENT_COUNT_RATE_MCPS_SD, &AmbientRate);
status |= VL53L1_RdWord(dev, VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0, &SpNb);
*ambPerSp=(uint16_t) (200.0 * AmbientRate / SpNb);
return status;
}
VL53L1X_ERROR VL53L1X_GetSignalRate(uint16_t dev, uint16_t *signal)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev,
VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0, &tmp);
*signal = tmp*8;
return status;
}
VL53L1X_ERROR VL53L1X_GetSpadNb(uint16_t dev, uint16_t *spNb)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev,
VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0, &tmp);
*spNb = tmp >> 8;
return status;
}
VL53L1X_ERROR VL53L1X_GetAmbientRate(uint16_t dev, uint16_t *ambRate)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev, RESULT__AMBIENT_COUNT_RATE_MCPS_SD, &tmp);
*ambRate = tmp*8;
return status;
}
VL53L1X_ERROR VL53L1X_GetRangeStatus(uint16_t dev, uint8_t *rangeStatus)
{
VL53L1X_ERROR status = 0;
uint8_t RgSt;
*rangeStatus = 255;
status |= VL53L1_RdByte(dev, VL53L1_RESULT__RANGE_STATUS, &RgSt);
RgSt = RgSt & 0x1F;
if (RgSt < 24)
*rangeStatus = status_rtn[RgSt];
return status;
}
VL53L1X_ERROR VL53L1X_GetResult(uint16_t dev, VL53L1X_Result_t *pResult)
{
VL53L1X_ERROR status = 0;
uint8_t Temp[17];
uint8_t RgSt = 255;
status |= VL53L1_ReadMulti(dev, VL53L1_RESULT__RANGE_STATUS, Temp, 17);
RgSt = Temp[0] & 0x1F;
if (RgSt < 24)
RgSt = status_rtn[RgSt];
pResult->Status = RgSt;
pResult->Ambient = (Temp[7] << 8 | Temp[8]) * 8;
pResult->NumSPADs = Temp[3];
pResult->SigPerSPAD = (Temp[15] << 8 | Temp[16]) * 8;
pResult->Distance = Temp[13] << 8 | Temp[14];
return status;
}
VL53L1X_ERROR VL53L1X_SetOffset(uint16_t dev, int16_t OffsetValue)
{
VL53L1X_ERROR status = 0;
int16_t Temp;
Temp = (OffsetValue*4);
status |= VL53L1_WrWord(dev, ALGO__PART_TO_PART_RANGE_OFFSET_MM,
(uint16_t)Temp);
status |= VL53L1_WrWord(dev, MM_CONFIG__INNER_OFFSET_MM, 0x0);
status |= VL53L1_WrWord(dev, MM_CONFIG__OUTER_OFFSET_MM, 0x0);
return status;
}
VL53L1X_ERROR VL53L1X_GetOffset(uint16_t dev, int16_t *offset)
{
VL53L1X_ERROR status = 0;
uint16_t Temp;
status |= VL53L1_RdWord(dev,ALGO__PART_TO_PART_RANGE_OFFSET_MM, &Temp);
Temp = Temp<<3;
Temp = Temp>>5;
*offset = (int16_t)(Temp);
if(*offset > 1024)
{
*offset = *offset - 2048;
}
return status;
}
VL53L1X_ERROR VL53L1X_SetXtalk(uint16_t dev, uint16_t XtalkValue)
{
/* XTalkValue in count per second to avoid float type */
VL53L1X_ERROR status = 0;
status |= VL53L1_WrWord(dev,
ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS,
0x0000);
status |= VL53L1_WrWord(dev, ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS,
0x0000);
status |= VL53L1_WrWord(dev, ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS,
(XtalkValue<<9)/1000); /* * << 9 (7.9 format) and /1000 to convert cps to kpcs */
return status;
}
VL53L1X_ERROR VL53L1X_GetXtalk(uint16_t dev, uint16_t *xtalk )
{
VL53L1X_ERROR status = 0;
status |= VL53L1_RdWord(dev,ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS, xtalk);
*xtalk = (uint16_t)((*xtalk*1000)>>9); /* * 1000 to convert kcps to cps and >> 9 (7.9 format) */
return status;
}
VL53L1X_ERROR VL53L1X_SetDistanceThreshold(uint16_t dev, uint16_t ThreshLow,
uint16_t ThreshHigh, uint8_t Window,
uint8_t IntOnNoTarget)
{
VL53L1X_ERROR status = 0;
uint8_t Temp = 0;
status |= VL53L1_RdByte(dev, SYSTEM__INTERRUPT_CONFIG_GPIO, &Temp);
Temp = Temp & 0x47;
if (IntOnNoTarget == 0) {
status = VL53L1_WrByte(dev, SYSTEM__INTERRUPT_CONFIG_GPIO,
(Temp | (Window & 0x07)));
} else {
status = VL53L1_WrByte(dev, SYSTEM__INTERRUPT_CONFIG_GPIO,
((Temp | (Window & 0x07)) | 0x40));
}
status |= VL53L1_WrWord(dev, SYSTEM__THRESH_HIGH, ThreshHigh);
status |= VL53L1_WrWord(dev, SYSTEM__THRESH_LOW, ThreshLow);
return status;
}
VL53L1X_ERROR VL53L1X_GetDistanceThresholdWindow(uint16_t dev, uint16_t *window)
{
VL53L1X_ERROR status = 0;
uint8_t tmp;
status |= VL53L1_RdByte(dev,SYSTEM__INTERRUPT_CONFIG_GPIO, &tmp);
*window = (uint16_t)(tmp & 0x7);
return status;
}
VL53L1X_ERROR VL53L1X_GetDistanceThresholdLow(uint16_t dev, uint16_t *low)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev,SYSTEM__THRESH_LOW, &tmp);
*low = tmp;
return status;
}
VL53L1X_ERROR VL53L1X_GetDistanceThresholdHigh(uint16_t dev, uint16_t *high)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev,SYSTEM__THRESH_HIGH, &tmp);
*high = tmp;
return status;
}
VL53L1X_ERROR VL53L1X_SetROICenter(uint16_t dev, uint8_t ROICenter)
{
VL53L1X_ERROR status = 0;
status |= VL53L1_WrByte(dev, ROI_CONFIG__USER_ROI_CENTRE_SPAD, ROICenter);
return status;
}
VL53L1X_ERROR VL53L1X_GetROICenter(uint16_t dev, uint8_t *ROICenter)
{
VL53L1X_ERROR status = 0;
uint8_t tmp;
status |= VL53L1_RdByte(dev, ROI_CONFIG__USER_ROI_CENTRE_SPAD, &tmp);
*ROICenter = tmp;
return status;
}
VL53L1X_ERROR VL53L1X_SetROI(uint16_t dev, uint16_t X, uint16_t Y)
{
uint8_t OpticalCenter;
VL53L1X_ERROR status = 0;
status |=VL53L1_RdByte(dev, VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD, &OpticalCenter);
if (X > 16)
X = 16;
if (Y > 16)
Y = 16;
if (X > 10 || Y > 10){
OpticalCenter = 199;
}
status |= VL53L1_WrByte(dev, ROI_CONFIG__USER_ROI_CENTRE_SPAD, OpticalCenter);
status |= VL53L1_WrByte(dev, ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE,
(Y - 1) << 4 | (X - 1));
return status;
}
VL53L1X_ERROR VL53L1X_GetROI_XY(uint16_t dev, uint16_t *ROI_X, uint16_t *ROI_Y)
{
VL53L1X_ERROR status = 0;
uint8_t tmp;
status = VL53L1_RdByte(dev,ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE, &tmp);
*ROI_X |= ((uint16_t)tmp & 0x0F) + 1;
*ROI_Y |= (((uint16_t)tmp & 0xF0) >> 4) + 1;
return status;
}
VL53L1X_ERROR VL53L1X_SetSignalThreshold(uint16_t dev, uint16_t Signal)
{
VL53L1X_ERROR status = 0;
status |= VL53L1_WrWord(dev,RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS,Signal>>3);
return status;
}
VL53L1X_ERROR VL53L1X_GetSignalThreshold(uint16_t dev, uint16_t *signal)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev,
RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS, &tmp);
*signal = tmp <<3;
return status;
}
VL53L1X_ERROR VL53L1X_SetSigmaThreshold(uint16_t dev, uint16_t Sigma)
{
VL53L1X_ERROR status = 0;
if(Sigma>(0xFFFF>>2)){
return 1;
}
/* 16 bits register 14.2 format */
status |= VL53L1_WrWord(dev,RANGE_CONFIG__SIGMA_THRESH,Sigma<<2);
return status;
}
VL53L1X_ERROR VL53L1X_GetSigmaThreshold(uint16_t dev, uint16_t *sigma)
{
VL53L1X_ERROR status = 0;
uint16_t tmp;
status |= VL53L1_RdWord(dev,RANGE_CONFIG__SIGMA_THRESH, &tmp);
*sigma = tmp >> 2;
return status;
}
VL53L1X_ERROR VL53L1X_StartTemperatureUpdate(uint16_t dev)
{
VL53L1X_ERROR status = 0;
uint8_t tmp=0;
status |= VL53L1_WrByte(dev,VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND,0x81); /* full VHV */
status |= VL53L1_WrByte(dev,0x0B,0x92);
status |= VL53L1X_StartRanging(dev);
while(tmp==0){
status |= VL53L1X_CheckForDataReady(dev, &tmp);
}
tmp = 0;
status |= VL53L1X_ClearInterrupt(dev);
status |= VL53L1X_StopRanging(dev);
status |= VL53L1_WrByte(dev, VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND, 0x09); /* two bounds VHV */
status |= VL53L1_WrByte(dev, 0x0B, 0); /* start VHV from the previous temperature */
return status;
}

View File

@ -1,393 +0,0 @@
/*
* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
*
* This file : part of VL53L1 Core and : dual licensed,
* either 'STMicroelectronics
* Proprietary license'
* or 'BSD 3-clause "New" or "Revised" License' , at your option.
*
********************************************************************************
*
* 'STMicroelectronics Proprietary license'
*
********************************************************************************
*
* License terms: STMicroelectronics Proprietary in accordance with licensing
* terms at www.st.com/sla0081
*
* STMicroelectronics confidential
* Reproduction and Communication of this document : strictly prohibited unless
* specifically authorized in writing by STMicroelectronics.
*
*
********************************************************************************
*
* Alternatively, VL53L1 Core may be distributed under the terms of
* 'BSD 3-clause "New" or "Revised" License', in which case the following
* provisions apply instead of the ones mentioned above :
*
********************************************************************************
*
* License terms: BSD 3-clause "New" or "Revised" License.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions 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 the copyright holder nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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.
*
*
********************************************************************************
*
*/
/**
* @file vl53l1x_api.h
* @brief Functions definition
*/
#ifndef _API_H_
#define _API_H_
#include "vl53l1_platform.h"
#define VL53L1X_IMPLEMENTATION_VER_MAJOR 3
#define VL53L1X_IMPLEMENTATION_VER_MINOR 5
#define VL53L1X_IMPLEMENTATION_VER_SUB 2
#define VL53L1X_IMPLEMENTATION_VER_REVISION 0000
typedef int8_t VL53L1X_ERROR;
#define SOFT_RESET 0x0000
#define VL53L1_I2C_SLAVE__DEVICE_ADDRESS 0x0001
#define VL53L1_VHV_CONFIG__TIMEOUT_MACROP_LOOP_BOUND 0x0008
#define ALGO__CROSSTALK_COMPENSATION_PLANE_OFFSET_KCPS 0x0016
#define ALGO__CROSSTALK_COMPENSATION_X_PLANE_GRADIENT_KCPS 0x0018
#define ALGO__CROSSTALK_COMPENSATION_Y_PLANE_GRADIENT_KCPS 0x001A
#define ALGO__PART_TO_PART_RANGE_OFFSET_MM 0x001E
#define MM_CONFIG__INNER_OFFSET_MM 0x0020
#define MM_CONFIG__OUTER_OFFSET_MM 0x0022
#define GPIO_HV_MUX__CTRL 0x0030
#define GPIO__TIO_HV_STATUS 0x0031
#define SYSTEM__INTERRUPT_CONFIG_GPIO 0x0046
#define PHASECAL_CONFIG__TIMEOUT_MACROP 0x004B
#define RANGE_CONFIG__TIMEOUT_MACROP_A_HI 0x005E
#define RANGE_CONFIG__VCSEL_PERIOD_A 0x0060
#define RANGE_CONFIG__VCSEL_PERIOD_B 0x0063
#define RANGE_CONFIG__TIMEOUT_MACROP_B_HI 0x0061
#define RANGE_CONFIG__TIMEOUT_MACROP_B_LO 0x0062
#define RANGE_CONFIG__SIGMA_THRESH 0x0064
#define RANGE_CONFIG__MIN_COUNT_RATE_RTN_LIMIT_MCPS 0x0066
#define RANGE_CONFIG__VALID_PHASE_HIGH 0x0069
#define VL53L1_SYSTEM__INTERMEASUREMENT_PERIOD 0x006C
#define SYSTEM__THRESH_HIGH 0x0072
#define SYSTEM__THRESH_LOW 0x0074
#define SD_CONFIG__WOI_SD0 0x0078
#define SD_CONFIG__INITIAL_PHASE_SD0 0x007A
#define ROI_CONFIG__USER_ROI_CENTRE_SPAD 0x007F
#define ROI_CONFIG__USER_ROI_REQUESTED_GLOBAL_XY_SIZE 0x0080
#define SYSTEM__SEQUENCE_CONFIG 0x0081
#define VL53L1_SYSTEM__GROUPED_PARAMETER_HOLD 0x0082
#define SYSTEM__INTERRUPT_CLEAR 0x0086
#define SYSTEM__MODE_START 0x0087
#define VL53L1_RESULT__RANGE_STATUS 0x0089
#define VL53L1_RESULT__DSS_ACTUAL_EFFECTIVE_SPADS_SD0 0x008C
#define RESULT__AMBIENT_COUNT_RATE_MCPS_SD 0x0090
#define VL53L1_RESULT__FINAL_CROSSTALK_CORRECTED_RANGE_MM_SD0 0x0096
#define VL53L1_RESULT__PEAK_SIGNAL_COUNT_RATE_CROSSTALK_CORRECTED_MCPS_SD0 0x0098
#define VL53L1_RESULT__OSC_CALIBRATE_VAL 0x00DE
#define VL53L1_FIRMWARE__SYSTEM_STATUS 0x00E5
#define VL53L1_IDENTIFICATION__MODEL_ID 0x010F
#define VL53L1_ROI_CONFIG__MODE_ROI_CENTRE_SPAD 0x013E
/****************************************
* PRIVATE define do not edit
****************************************/
/**
* @brief defines SW Version
*/
typedef struct {
uint8_t major; /*!< major number */
uint8_t minor; /*!< minor number */
uint8_t build; /*!< build number */
uint32_t revision; /*!< revision number */
} VL53L1X_Version_t;
/**
* @brief defines packed reading results type
*/
typedef struct {
uint8_t Status; /*!< ResultStatus */
uint16_t Distance; /*!< ResultDistance */
uint16_t Ambient; /*!< ResultAmbient */
uint16_t SigPerSPAD;/*!< ResultSignalPerSPAD */
uint16_t NumSPADs; /*!< ResultNumSPADs */
} VL53L1X_Result_t;
/**
* @brief This function returns the SW driver version
*/
VL53L1X_ERROR VL53L1X_GetSWVersion(VL53L1X_Version_t *pVersion);
/**
* @brief This function sets the sensor I2C address used in case multiple devices application, default address 0x52
*/
VL53L1X_ERROR VL53L1X_SetI2CAddress(uint16_t, uint8_t new_address);
/**
* @brief This function loads the 135 bytes default values to initialize the sensor.
* @param dev Device address
* @return 0:success, != 0:failed
*/
VL53L1X_ERROR VL53L1X_SensorInit(uint16_t dev);
/**
* @brief This function clears the interrupt, to be called after a ranging data reading
* to arm the interrupt for the next data ready event.
*/
VL53L1X_ERROR VL53L1X_ClearInterrupt(uint16_t dev);
/**
* @brief This function programs the interrupt polarity\n
* 1=active high (default), 0=active low
*/
VL53L1X_ERROR VL53L1X_SetInterruptPolarity(uint16_t dev, uint8_t IntPol);
/**
* @brief This function returns the current interrupt polarity\n
* 1=active high (default), 0=active low
*/
VL53L1X_ERROR VL53L1X_GetInterruptPolarity(uint16_t dev, uint8_t *pIntPol);
/**
* @brief This function starts the ranging distance operation\n
* The ranging operation is continuous. The clear interrupt has to be done after each get data to allow the interrupt to raise when the next data is ready\n
* 1=active high (default), 0=active low, use SetInterruptPolarity() to change the interrupt polarity if required.
*/
VL53L1X_ERROR VL53L1X_StartRanging(uint16_t dev);
/**
* @brief This function stops the ranging.
*/
VL53L1X_ERROR VL53L1X_StopRanging(uint16_t dev);
/**
* @brief This function checks if the new ranging data is available by polling the dedicated register.
* @param : isDataReady==0 -> not ready; isDataReady==1 -> ready
*/
VL53L1X_ERROR VL53L1X_CheckForDataReady(uint16_t dev, uint8_t *isDataReady);
/**
* @brief This function programs the timing budget in ms.
* Predefined values = 15, 20, 33, 50, 100(default), 200, 500.
*/
VL53L1X_ERROR VL53L1X_SetTimingBudgetInMs(uint16_t dev, uint16_t TimingBudgetInMs);
/**
* @brief This function returns the current timing budget in ms.
*/
VL53L1X_ERROR VL53L1X_GetTimingBudgetInMs(uint16_t dev, uint16_t *pTimingBudgetInMs);
/**
* @brief This function programs the distance mode (1=short, 2=long(default)).
* Short mode max distance is limited to 1.3 m but better ambient immunity.\n
* Long mode can range up to 4 m in the dark with 200 ms timing budget.
*/
VL53L1X_ERROR VL53L1X_SetDistanceMode(uint16_t dev, uint16_t DistanceMode);
/**
* @brief This function returns the current distance mode (1=short, 2=long).
*/
VL53L1X_ERROR VL53L1X_GetDistanceMode(uint16_t dev, uint16_t *pDistanceMode);
/**
* @brief This function programs the Intermeasurement period in ms\n
* Intermeasurement period must be >/= timing budget. This condition is not checked by the API,
* the customer has the duty to check the condition. Default = 100 ms
*/
VL53L1X_ERROR VL53L1X_SetInterMeasurementInMs(uint16_t dev,
uint32_t InterMeasurementInMs);
/**
* @brief This function returns the Intermeasurement period in ms.
*/
VL53L1X_ERROR VL53L1X_GetInterMeasurementInMs(uint16_t dev, uint16_t * pIM);
/**
* @brief This function returns the boot state of the device (1:booted, 0:not booted)
*/
VL53L1X_ERROR VL53L1X_BootState(uint16_t dev, uint8_t *state);
/**
* @brief This function returns the sensor id, sensor Id must be 0xEEAC
*/
VL53L1X_ERROR VL53L1X_GetSensorId(uint16_t dev, uint16_t *id);
/**
* @brief This function returns the distance measured by the sensor in mm
*/
VL53L1X_ERROR VL53L1X_GetDistance(uint16_t dev, uint16_t *distance);
/**
* @brief This function returns the returned signal per SPAD in kcps/SPAD.
* With kcps stands for Kilo Count Per Second
*/
VL53L1X_ERROR VL53L1X_GetSignalPerSpad(uint16_t dev, uint16_t *signalPerSp);
/**
* @brief This function returns the ambient per SPAD in kcps/SPAD
*/
VL53L1X_ERROR VL53L1X_GetAmbientPerSpad(uint16_t dev, uint16_t *amb);
/**
* @brief This function returns the returned signal in kcps.
*/
VL53L1X_ERROR VL53L1X_GetSignalRate(uint16_t dev, uint16_t *signalRate);
/**
* @brief This function returns the current number of enabled SPADs
*/
VL53L1X_ERROR VL53L1X_GetSpadNb(uint16_t dev, uint16_t *spNb);
/**
* @brief This function returns the ambient rate in kcps
*/
VL53L1X_ERROR VL53L1X_GetAmbientRate(uint16_t dev, uint16_t *ambRate);
/**
* @brief This function returns the ranging status error \n
* (0:no error, 1:sigma failed, 2:signal failed, ..., 7:wrap-around)
*/
VL53L1X_ERROR VL53L1X_GetRangeStatus(uint16_t dev, uint8_t *rangeStatus);
/**
* @brief This function returns measurements and the range status in a single read access
*/
VL53L1X_ERROR VL53L1X_GetResult(uint16_t dev, VL53L1X_Result_t *pResult);
/**
* @brief This function programs the offset correction in mm
* @param OffsetValue:the offset correction value to program in mm
*/
VL53L1X_ERROR VL53L1X_SetOffset(uint16_t dev, int16_t OffsetValue);
/**
* @brief This function returns the programmed offset correction value in mm
*/
VL53L1X_ERROR VL53L1X_GetOffset(uint16_t dev, int16_t *Offset);
/**
* @brief This function programs the xtalk correction value in cps (Count Per Second).\n
* This is the number of photons reflected back from the cover glass in cps.
*/
VL53L1X_ERROR VL53L1X_SetXtalk(uint16_t dev, uint16_t XtalkValue);
/**
* @brief This function returns the current programmed xtalk correction value in cps
*/
VL53L1X_ERROR VL53L1X_GetXtalk(uint16_t dev, uint16_t *Xtalk);
/**
* @brief This function programs the threshold detection mode\n
* Example:\n
* VL53L1X_SetDistanceThreshold(dev,100,300,0,1): Below 100 \n
* VL53L1X_SetDistanceThreshold(dev,100,300,1,1): Above 300 \n
* VL53L1X_SetDistanceThreshold(dev,100,300,2,1): Out of window \n
* VL53L1X_SetDistanceThreshold(dev,100,300,3,1): In window \n
* @param dev : device address
* @param ThreshLow(in mm) : the threshold under which one the device raises an interrupt if Window = 0
* @param ThreshHigh(in mm) : the threshold above which one the device raises an interrupt if Window = 1
* @param Window detection mode : 0=below, 1=above, 2=out, 3=in
* @param IntOnNoTarget = 0 (No longer used - just use 0)
*/
VL53L1X_ERROR VL53L1X_SetDistanceThreshold(uint16_t dev, uint16_t ThreshLow,
uint16_t ThreshHigh, uint8_t Window,
uint8_t IntOnNoTarget);
/**
* @brief This function returns the window detection mode (0=below; 1=above; 2=out; 3=in)
*/
VL53L1X_ERROR VL53L1X_GetDistanceThresholdWindow(uint16_t dev, uint16_t *window);
/**
* @brief This function returns the low threshold in mm
*/
VL53L1X_ERROR VL53L1X_GetDistanceThresholdLow(uint16_t dev, uint16_t *low);
/**
* @brief This function returns the high threshold in mm
*/
VL53L1X_ERROR VL53L1X_GetDistanceThresholdHigh(uint16_t dev, uint16_t *high);
/**
* @brief This function programs the ROI (Region of Interest)\n
* The ROI position is centered, only the ROI size can be reprogrammed.\n
* The smallest acceptable ROI size = 4\n
* @param X:ROI Width; Y=ROI Height
*/
VL53L1X_ERROR VL53L1X_SetROI(uint16_t dev, uint16_t X, uint16_t Y);
/**
*@brief This function returns width X and height Y
*/
VL53L1X_ERROR VL53L1X_GetROI_XY(uint16_t dev, uint16_t *ROI_X, uint16_t *ROI_Y);
/**
*@brief This function programs the new user ROI center, please to be aware that there is no check in this function.
*if the ROI center vs ROI size is out of border the ranging function return error #13
*/
VL53L1X_ERROR VL53L1X_SetROICenter(uint16_t dev, uint8_t ROICenter);
/**
*@brief This function returns the current user ROI center
*/
VL53L1X_ERROR VL53L1X_GetROICenter(uint16_t dev, uint8_t *ROICenter);
/**
* @brief This function programs a new signal threshold in kcps (default=1024 kcps\n
*/
VL53L1X_ERROR VL53L1X_SetSignalThreshold(uint16_t dev, uint16_t signal);
/**
* @brief This function returns the current signal threshold in kcps
*/
VL53L1X_ERROR VL53L1X_GetSignalThreshold(uint16_t dev, uint16_t *signal);
/**
* @brief This function programs a new sigma threshold in mm (default=15 mm)
*/
VL53L1X_ERROR VL53L1X_SetSigmaThreshold(uint16_t dev, uint16_t sigma);
/**
* @brief This function returns the current sigma threshold in mm
*/
VL53L1X_ERROR VL53L1X_GetSigmaThreshold(uint16_t dev, uint16_t *signal);
/**
* @brief This function performs the temperature calibration.
* It is recommended to call this function any time the temperature might have changed by more than 8 deg C
* without sensor ranging activity for an extended period.
*/
VL53L1X_ERROR VL53L1X_StartTemperatureUpdate(uint16_t dev);
#endif

View File

@ -1,138 +0,0 @@
/*
* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
*
* This file : part of VL53L1 Core and : dual licensed,
* either 'STMicroelectronics
* Proprietary license'
* or 'BSD 3-clause "New" or "Revised" License' , at your option.
*
********************************************************************************
*
* 'STMicroelectronics Proprietary license'
*
********************************************************************************
*
* License terms: STMicroelectronics Proprietary in accordance with licensing
* terms at www.st.com/sla0081
*
* STMicroelectronics confidential
* Reproduction and Communication of this document : strictly prohibited unless
* specifically authorized in writing by STMicroelectronics.
*
*
********************************************************************************
*
* Alternatively, VL53L1 Core may be distributed under the terms of
* 'BSD 3-clause "New" or "Revised" License', in which case the following
* provisions apply instead of the ones mentioned above :
*
********************************************************************************
*
* License terms: BSD 3-clause "New" or "Revised" License.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions 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 the copyright holder nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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.
*
*
********************************************************************************
*
*/
/**
* @file vl53l1x_calibration.c
* @brief Calibration functions implementation
*/
#include "VL53L1X_api.h"
#include "VL53L1X_calibration.h"
#define ALGO__PART_TO_PART_RANGE_OFFSET_MM 0x001E
#define MM_CONFIG__INNER_OFFSET_MM 0x0020
#define MM_CONFIG__OUTER_OFFSET_MM 0x0022
int8_t VL53L1X_CalibrateOffset(uint16_t dev, uint16_t TargetDistInMm, int16_t *offset)
{
uint8_t i, tmp;
int16_t AverageDistance = 0;
uint16_t distance;
VL53L1X_ERROR status = 0;
status |= VL53L1_WrWord(dev, ALGO__PART_TO_PART_RANGE_OFFSET_MM, 0x0);
status |= VL53L1_WrWord(dev, MM_CONFIG__INNER_OFFSET_MM, 0x0);
status |= VL53L1_WrWord(dev, MM_CONFIG__OUTER_OFFSET_MM, 0x0);
status |= VL53L1X_StartRanging(dev); /* Enable VL53L1X sensor */
for (i = 0; i < 50; i++) {
tmp = 0;
while (tmp == 0){
status |= VL53L1X_CheckForDataReady(dev, &tmp);
}
status |= VL53L1X_GetDistance(dev, &distance);
status |= VL53L1X_ClearInterrupt(dev);
AverageDistance = AverageDistance + distance;
}
status |= VL53L1X_StopRanging(dev);
AverageDistance = AverageDistance / 50;
*offset = TargetDistInMm - AverageDistance;
status |= VL53L1_WrWord(dev, ALGO__PART_TO_PART_RANGE_OFFSET_MM, *offset*4);
return status;
}
int8_t VL53L1X_CalibrateXtalk(uint16_t dev, uint16_t TargetDistInMm, uint16_t *xtalk)
{
uint8_t i, tmp;
float AverageSignalRate = 0;
float AverageDistance = 0;
float AverageSpadNb = 0;
uint16_t distance = 0, spadNum;
uint16_t sr;
VL53L1X_ERROR status = 0;
uint32_t calXtalk;
status |= VL53L1_WrWord(dev, 0x0016,0);
status |= VL53L1X_StartRanging(dev);
for (i = 0; i < 50; i++) {
tmp = 0;
while (tmp == 0){
status |= VL53L1X_CheckForDataReady(dev, &tmp);
}
status |= VL53L1X_GetSignalRate(dev, &sr);
status |= VL53L1X_GetDistance(dev, &distance);
status |= VL53L1X_ClearInterrupt(dev);
AverageDistance = AverageDistance + distance;
status = VL53L1X_GetSpadNb(dev, &spadNum);
AverageSpadNb = AverageSpadNb + spadNum;
AverageSignalRate =
AverageSignalRate + sr;
}
status |= VL53L1X_StopRanging(dev);
AverageDistance = AverageDistance / 50;
AverageSpadNb = AverageSpadNb / 50;
AverageSignalRate = AverageSignalRate / 50;
/* Calculate Xtalk value */
calXtalk = (uint16_t)(512*(AverageSignalRate*(1-(AverageDistance/TargetDistInMm)))/AverageSpadNb);
if(calXtalk > 0xffff)
calXtalk = 0xffff;
*xtalk = (uint16_t)((calXtalk*1000)>>9);
status |= VL53L1_WrWord(dev, 0x0016, (uint16_t)calXtalk);
return status;
}

View File

@ -1,93 +0,0 @@
/*
* Copyright (c) 2017, STMicroelectronics - All Rights Reserved
*
* This file : part of VL53L1 Core and : dual licensed,
* either 'STMicroelectronics
* Proprietary license'
* or 'BSD 3-clause "New" or "Revised" License' , at your option.
*
********************************************************************************
*
* 'STMicroelectronics Proprietary license'
*
********************************************************************************
*
* License terms: STMicroelectronics Proprietary in accordance with licensing
* terms at www.st.com/sla0081
*
* STMicroelectronics confidential
* Reproduction and Communication of this document : strictly prohibited unless
* specifically authorized in writing by STMicroelectronics.
*
*
********************************************************************************
*
* Alternatively, VL53L1 Core may be distributed under the terms of
* 'BSD 3-clause "New" or "Revised" License', in which case the following
* provisions apply instead of the ones mentioned above :
*
********************************************************************************
*
* License terms: BSD 3-clause "New" or "Revised" License.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions 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 the copyright holder nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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.
*
*
********************************************************************************
*
*/
/**
* @file vl53l1x_calibration.h
* @brief Calibration Functions definition
*/
#ifndef _CALIBRATION_H_
#define _CALIBRATION_H_
/**
* @brief This function performs the offset calibration.\n
* The function returns the offset value found and programs the offset compensation into the device.
* @param TargetDistInMm target distance in mm, ST recommended 100 mm
* Target reflectance = grey17%
* @return 0:success, !=0: failed
* @return offset pointer contains the offset found in mm
*/
int8_t VL53L1X_CalibrateOffset(uint16_t dev, uint16_t TargetDistInMm, int16_t *offset);
/**
* @brief This function performs the xtalk calibration.\n
* The function returns the xtalk value found and programs the xtalk compensation to the device
* @param TargetDistInMm target distance in mm\n
* The target distance : the distance where the sensor start to "under range"\n
* due to the influence of the photons reflected back from the cover glass becoming strong\n
* It's also called inflection point\n
* Target reflectance = grey 17%
* @return 0: success, !=0: failed
* @return xtalk pointer contains the xtalk value found in cps (number of photons in count per second)
*/
int8_t VL53L1X_CalibrateXtalk(uint16_t dev, uint16_t TargetDistInMm, uint16_t *xtalk);
#endif

143
main.c
View File

@ -2,43 +2,16 @@
#include "pico/stdlib.h"
#include "pico/multicore.h"
#include "hardware/i2c.h"
#include "VL53L1X_Fonctions.h"
#include "SelectionCapteur.h"
#include "hardware/pio.h"
#include "hardware/i2c.h"
#include "ws2812.h"
#include "ws2812.pio.h"
#include "i2c_fifo.h"
#include "i2c_slave.h"
#define I2C0_SDA_PIN 4
#define I2C0_SCL_PIN 5
#include "Tests.h"
#define I2C_SLAVE_ADDRESS 0x10
#define I2C0_SDA_PIN 0
#define I2C0_SCL_PIN 1
#define I2C1_SDA_PIN 18
#define I2C1_SCL_PIN 19
void i2c_master_init(void);
int continuous_reading(uint8_t device);
int calibration(uint8_t device);
int change_address(uint8_t * device, uint8_t new_i2c_7bits_address);
void initialise_adresses(void);
void affiche_distance_sur_led();
void init_sensors(void);
uint8_t tampon_commande_led[3];
#define I2C_SLAVE_ADDRESS 0x18
#define ADRESSE_RECEPTION_DATA 0x10
#define ADRESSE_COULEUR_LED 0x10
#define ADRESSE_MASQUE_LED_1 0x11
#define ADRESSE_MASQUE_LED_2 0x12
static const uint I2C_SLAVE_SDA_PIN = I2C1_SDA_PIN;
static const uint I2C_SLAVE_SCL_PIN = I2C1_SCL_PIN;
static const uint I2C_SLAVE_SDA_PIN = I2C0_SDA_PIN;
static const uint I2C_SLAVE_SCL_PIN = I2C0_SCL_PIN;
// The slave implements a 256 byte memory. To write a series of bytes, the master first
// writes the memory address, followed by the data. The address is automatically incremented
@ -99,121 +72,19 @@ static void setup_slave() {
gpio_set_function(I2C_SLAVE_SCL_PIN, GPIO_FUNC_I2C);
gpio_pull_up(I2C_SLAVE_SCL_PIN);
i2c_slave_init(i2c1, I2C_SLAVE_ADDRESS, &i2c_slave_handler);
i2c_slave_init(i2c0, I2C_SLAVE_ADDRESS, &i2c_slave_handler);
}
void blink(void){
const uint LED_PIN = PICO_DEFAULT_LED_PIN;
while(1){
printf("couleur_Led:%2x\n", tampon_commande_led[0]);
printf("masque_Led:%3x\n", (tampon_commande_led[1]<<8) | tampon_commande_led[2]);
for(uint8_t capteur=0; capteur<12; capteur++){
printf(">distance%x:%d\n", capteur, context.mem[capteur]);
}
gpio_put(LED_PIN, !gpio_get(LED_PIN));
sleep_ms(20);
}
}
void main(void)
{
int status;
uint8_t distance_capteur_cm[12];
const uint LED_PIN = PICO_DEFAULT_LED_PIN;
gpio_init(LED_PIN);
gpio_set_dir(LED_PIN, GPIO_OUT);
gpio_put(LED_PIN, 1);
tampon_commande_led[0]=0;
tampon_commande_led[1]=0;
tampon_commande_led[2]=0;
uint8_t VL53L1X_device = 0x29;
stdio_init_all();
i2c_master_init();
Selection_capteur_init();
//Selection_capteur_select(1);
ws2812_init();
printf("End waiting\n");
setup_slave();
//Tests();
multicore_launch_core1(blink);
initialise_adresses();
uint8_t capteur_courant=0;
while(1){
// Lecture des capteurs
if(capteur_pret(capteur_courant)){
uint8_t distance_cm;
if(capteur_lire_distance_cm(capteur_courant, &distance_cm)){
distance_capteur_cm[capteur_courant]= distance_cm;
}
}
capteur_courant++;
if(capteur_courant > 11){
capteur_courant = 0;
}
// Affichage des distances sur les LEDs.
affiche_distance_sur_led(distance_capteur_cm);
// Envoie des valeurs des capteurs
for(uint8_t capteur=0; capteur<12; capteur++){
context.mem[capteur] = distance_capteur_cm[capteur];
}
// Reception des données à afficher sur les capteurs
// Si nous avons reçu une nouvelle commande
if(tampon_commande_led[0] != context.mem[0x10] ||
tampon_commande_led[1] != context.mem[0x11] ||
tampon_commande_led[2] != context.mem[0x12] ){
tampon_commande_led[0] = context.mem[0x10];
tampon_commande_led[1] = context.mem[0x11];
tampon_commande_led[2] = context.mem[0x12];
uint8_t couleur = tampon_commande_led[0];
uint16_t masque_led = (tampon_commande_led[1] << 8) | tampon_commande_led[2];
reset_affichage_led();
for(uint8_t led=0; led < 12; led++){
if((masque_led >> led) & 0x01){
affiche_couleur_sur_led(couleur, led);
}
}
ws2812_affiche_buffer();
}
}
}
void i2c_master_init(void){
//stdio_init_all();
i2c_init(i2c0, 100 * 1000);
printf("Initialisation des broches\n");
for(int i=0; i++; i<=28){
if(gpio_get_function(i) == GPIO_FUNC_I2C){
printf("Pin I2C : %d\n", i);
gpio_set_function(i, GPIO_FUNC_NULL);
}
}
printf("%d and %d for I2C\n", I2C0_SDA_PIN, I2C0_SCL_PIN);
gpio_set_function(I2C0_SDA_PIN, GPIO_FUNC_I2C);
gpio_set_function(I2C0_SCL_PIN, GPIO_FUNC_I2C);
}

View File

@ -1,178 +0,0 @@
/*
* This file is part of VL53L1 Platform
*
* Copyright (c) 2016, STMicroelectronics - All Rights Reserved
*
* License terms: BSD 3-clause "New" or "Revised" License.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions 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 the copyright holder nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER 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.
*
*/
#include "vl53l1_platform.h"
#include "hardware/i2c.h"
#include "hardware/gpio.h"
#define I2C_SUCCESS 0
#define I2C_FAILED -1
#define I2C_BUFFER_EXCEEDED -2
#define MAX_I2C_BUFFER 100
/// @brief Blocking function allowing to write a register on an I2C device
/// @param address_7_bits
/// @param index : register to write
/// @param values : values to write
/// @param count : number of byte to send
/// @return 0: Success, -1 or -2: Failed
int8_t i2c_write_register(char adresse_7_bits, uint16_t index, uint8_t * values, uint32_t count){
int statu;
uint8_t buffer[MAX_I2C_BUFFER];
uint8_t index_to_unint8[2];
absolute_time_t timeout_time;
if(count > MAX_I2C_BUFFER - 2){
return I2C_BUFFER_EXCEEDED;
}
index_to_unint8[0] = (index >> 8) & 0xFF;
index_to_unint8[1] = index & 0xFF;
buffer[0] = index_to_unint8[0];
buffer[1] = index_to_unint8[1];
for(uint32_t i=0; i<count; i++){
buffer[2+i] = values[i];
}
// Define timeout - now + 1s.
timeout_time = time_us_64() + 1000000;
statu = i2c_write_blocking_until (i2c0, adresse_7_bits, buffer, count + 2, 0, timeout_time);
//statu = i2c_write_blocking (i2c0, adresse_7_bits, buffer, count + 2, 0);
if(statu == PICO_ERROR_GENERIC){
//printf("Erreur ecrire registre\n");
return I2C_FAILED;
}else if(statu == PICO_ERROR_TIMEOUT){
printf("Erreur ecrire registre: timeout\n");
return I2C_FAILED;
}
return I2C_SUCCESS;
}
/// @brief Blocking function allowing to write a register on an I2C device
/// @param address_7_bits
/// @param index : register to write
/// @param values : values to write
/// @param count : number of byte to send
/// @return 0: Success, -1 or -2: Failed
int8_t i2c_read_register(char adresse_7_bits, uint16_t index, uint8_t *pdata, uint32_t count){
int statu;
uint8_t buffer[MAX_I2C_BUFFER];
uint8_t index_to_unint8[2];
index_to_unint8[0] = (index >> 8) & 0xFF;
index_to_unint8[1] = index & 0xFF;
statu = i2c_write_blocking (i2c0, adresse_7_bits, index_to_unint8, 2, 0);
if(statu == PICO_ERROR_GENERIC){
printf("I2C - Envoi registre Echec\n");
return I2C_FAILED;
}
statu = i2c_read_blocking (i2c0, adresse_7_bits, pdata, count, 0);
if(statu == PICO_ERROR_GENERIC){
printf("I2C - Lecture registre Echec\n");
return I2C_FAILED;
}
return I2C_SUCCESS;
}
int8_t VL53L1_WriteMulti( uint16_t dev, uint16_t index, uint8_t *pdata, uint32_t count) {
return i2c_write_register(dev, index, pdata, count);
}
int8_t VL53L1_ReadMulti(uint16_t dev, uint16_t index, uint8_t *pdata, uint32_t count){
return i2c_read_register(dev, index, pdata, count);
}
int8_t VL53L1_WrByte(uint16_t dev, uint16_t index, uint8_t data) {
return i2c_write_register(dev, index, &data, 1);
}
int8_t VL53L1_WrWord(uint16_t dev, uint16_t index, uint16_t data) {
uint8_t buffer[2];
buffer[0] = (data >> 8) & 0xFF;
buffer[1] = data & 0xFF;
return VL53L1_WriteMulti(dev, index, buffer, 2);
}
int8_t VL53L1_WrDWord(uint16_t dev, uint16_t index, uint32_t data) {
uint8_t buffer[4];
buffer[0] = (data >> 24) & 0xFF;
buffer[1] = (data >> 16) & 0xFF;
buffer[2] = (data >> 8) & 0xFF;
buffer[3] = data & 0xFF;
return VL53L1_WriteMulti(dev, index, buffer, 4);
}
int8_t VL53L1_RdByte(uint16_t dev, uint16_t index, uint8_t *data) {
return VL53L1_ReadMulti(dev, index, data, 1);
}
int8_t VL53L1_RdWord(uint16_t dev, uint16_t index, uint16_t *data) {
int8_t status;
uint8_t buffer[2];
status = VL53L1_ReadMulti(dev, index, buffer, 2);
*data = (uint16_t) buffer[1] | (uint16_t) buffer[0] << 8;
return status;
}
int8_t VL53L1_RdDWord(uint16_t dev, uint16_t index, uint32_t *data) {
int8_t status;
uint8_t buffer[4];
status = VL53L1_ReadMulti(dev, index, buffer, 4);
*data = (uint32_t) buffer[0] << 24 |
(uint32_t) buffer[1] << 16 |
(uint32_t) buffer[2] << 8 |
(uint32_t) buffer[3];
return status;
}
int8_t VL53L1_WaitMs(uint16_t dev, int32_t wait_ms){
sleep_ms(wait_ms);
return 0;
}

View File

@ -1,91 +0,0 @@
/**
* @file vl53l1_platform.h
* @brief Those platform functions are platform dependent and have to be implemented by the user
*/
#ifndef _VL53L1_PLATFORM_H_
#define _VL53L1_PLATFORM_H_
#include "vl53l1_types.h"
#ifdef __cplusplus
extern "C"
{
#endif
typedef struct {
uint32_t dummy;
} VL53L1_Dev_t;
typedef VL53L1_Dev_t *VL53L1_DEV;
/** @brief VL53L1_WriteMulti() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_WriteMulti(
uint16_t dev,
uint16_t index,
uint8_t *pdata,
uint32_t count);
/** @brief VL53L1_ReadMulti() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_ReadMulti(
uint16_t dev,
uint16_t index,
uint8_t *pdata,
uint32_t count);
/** @brief VL53L1_WrByte() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_WrByte(
uint16_t dev,
uint16_t index,
uint8_t data);
/** @brief VL53L1_WrWord() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_WrWord(
uint16_t dev,
uint16_t index,
uint16_t data);
/** @brief VL53L1_WrDWord() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_WrDWord(
uint16_t dev,
uint16_t index,
uint32_t data);
/** @brief VL53L1_RdByte() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_RdByte(
uint16_t dev,
uint16_t index,
uint8_t *pdata);
/** @brief VL53L1_RdWord() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_RdWord(
uint16_t dev,
uint16_t index,
uint16_t *pdata);
/** @brief VL53L1_RdDWord() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_RdDWord(
uint16_t dev,
uint16_t index,
uint32_t *pdata);
/** @brief VL53L1_WaitMs() definition.\n
* To be implemented by the developer
*/
int8_t VL53L1_WaitMs(
uint16_t dev,
int32_t wait_ms);
#ifdef __cplusplus
}
#endif
#endif

View File

@ -1,114 +0,0 @@
/*******************************************************************************
Copyright (C) 2015, 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:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* 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.
* Neither the name of STMicroelectronics nor the
names of its contributors may be used to endorse or promote products
derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, AND
NON-INFRINGEMENT OF INTELLECTUAL PROPERTY RIGHTS ARE DISCLAIMED.
IN NO EVENT SHALL STMICROELECTRONICS INTERNATIONAL N.V. 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.
********************************************************************************/
/**
* @file vl53l1_types.h
* @brief VL53L1 types definition
*/
#ifndef _VL53L1_TYPES_H_
#define _VL53L1_TYPES_H_
/** @defgroup porting_type Basic type definition
* @ingroup api_platform
*
* @brief file vl53l1_types.h files hold basic type definition that may requires porting
*
* contains type that must be defined for the platform\n
* when target platform and compiler provide stdint.h and stddef.h it is enough to include it.\n
* If stdint.h is not available review and adapt all signed and unsigned 8/16/32 bits basic types. \n
* If stddef.h is not available review and adapt NULL definition .
*/
#include <stdint.h>
#include <stddef.h>
#include <string.h>
#include <stdio.h>
#include <stdlib.h>
#ifndef NULL
#error "Error NULL definition should be done. Please add required include "
#endif
#if !defined(STDINT_H) && !defined(_STDINT_H) && !defined(_GCC_STDINT_H) && !defined(__STDINT_DECLS) && !defined(_GCC_WRAP_STDINT_H) && !defined(_STDINT)
#pragma message("Please review type definition of STDINT define for your platform and add to list above ")
/*
* target platform do not provide stdint or use a different #define than above
* to avoid seeing the message below addapt the #define list above or implement
* all type and delete these pragma
*/
/** \ingroup VL53L1_portingType_group
* @{
*/
typedef unsigned long long uint64_t;
/** @brief Typedef defining 32 bit unsigned int type.\n
* The developer should modify this to suit the platform being deployed.
*/
typedef unsigned int uint32_t;
/** @brief Typedef defining 32 bit int type.\n
* The developer should modify this to suit the platform being deployed.
*/
typedef int int32_t;
/** @brief Typedef defining 16 bit unsigned short type.\n
* The developer should modify this to suit the platform being deployed.
*/
typedef unsigned short uint16_t;
/** @brief Typedef defining 16 bit short type.\n
* The developer should modify this to suit the platform being deployed.
*/
typedef short int16_t;
/** @brief Typedef defining 8 bit unsigned char type.\n
* The developer should modify this to suit the platform being deployed.
*/
typedef unsigned char uint8_t;
/** @brief Typedef defining 8 bit char type.\n
* The developer should modify this to suit the platform being deployed.
*/
typedef signed char int8_t;
/** @} */
#endif /* _STDINT_H */
/** use where fractional values are expected
*
* Given a floating point value f it's .16 bit point is (int)(f*(1<<16))*/
typedef uint32_t FixPoint1616_t;
#endif /* VL53L1_TYPES_H_ */

126
ws2812.c
View File

@ -1,126 +0,0 @@
#include "pico/stdlib.h"
#include "hardware/pio.h"
#include "ws2812.h"
#include "ws2812.pio.h"
#define WS2812_PIN 7
#define IS_RGBW false
uint32_t couleur[13];
uint32_t buffer_couleur[12];
void ws2812_set_buffer(uint32_t couleur, uint8_t index_led);
void ws2812_init(){
/*couleur[0]=0x000200;
couleur[1]=0x010200;
couleur[2]=0x020200;
couleur[3]=0x020100;
couleur[4]=0x020000;
couleur[5]=0x020001;
couleur[6]=0x020002;
couleur[7]=0x010002;
couleur[8]=0x000002;
couleur[9]=0x000102;
couleur[10]=0x000202;
couleur[11]=0x000201;
couleur[12]=0x000200;*/
couleur[0]=0x002000;
couleur[1]=0x102000;
couleur[2]=0x202000;
couleur[3]=0x201000;
couleur[4]=0x200000;
couleur[5]=0x200010;
couleur[6]=0x200020;
couleur[7]=0x100020;
couleur[8]=0x000020;
couleur[9]=0x001020;
couleur[10]=0x002020;
couleur[11]=0x002010;
couleur[12]=0x002000;
/*couleur[0]=0x00FF00;
couleur[1]=0x80FF00;
couleur[2]=0xFFFF00;
couleur[3]=0xFF8000;
couleur[4]=0xFF0000;
couleur[5]=0xFF0080;
couleur[6]=0xFF00FF;
couleur[7]=0x8000FF;
couleur[8]=0x0000FF;
couleur[9]=0x0080FF;
couleur[10]=0x00FFFF;
couleur[11]=0x00FF80;
couleur[12]=0x00FF00;*/
// initialisation du PIO
PIO pio = pio0;
int sm = 0;
uint offset = pio_add_program(pio, &ws2812_program);
ws2812_program_init(pio, sm, offset, WS2812_PIN, 800000, IS_RGBW);
// Tout rouge !
for(uint32_t i = 0; i<12; i++){
ws2812_set_buffer_rgb(0x4, 0x1, 0, i);
}
ws2812_affiche_buffer();
}
void ws2812_arc_en_ciel(){
while(1){
uint32_t i;
sleep_ms(50);
// Affichage
for(i = 0; i<12; i++){
ws2812_set_buffer(couleur[i], i);
}
ws2812_affiche_buffer();
// Décalage des couleurs
for(i = 0; i<12; i++){
couleur[i] = couleur[i+1];
}
couleur[12]=couleur[0];
}
}
static inline void put_pixel(uint32_t pixel_grb) {
pio_sm_put_blocking(pio0, 0, pixel_grb << 8u);
}
static inline uint32_t urgb_u32(uint8_t r, uint8_t g, uint8_t b) {
return
((uint32_t) (r) << 8) |
((uint32_t) (g) << 16) |
(uint32_t) (b);
}
void ws2812_affiche_buffer(){
for(uint32_t i = 0; i<12; i++){
put_pixel(buffer_couleur[i]);
}
}
void ws2812_set_buffer_rgb(uint8_t rouge, uint8_t vert, uint8_t bleu, uint8_t index_led){
ws2812_set_buffer(urgb_u32(rouge, vert,bleu), index_led);
}
//Bit 7 6 5 4 3 2 1 0
//Data R R R G G G B B
void ws2812_set_buffer_8bits(uint8_t couleur, uint8_t index_led){
ws2812_set_buffer(urgb_u32(couleur >> 5, (couleur >> 2) & 0x07, couleur & 0x03), index_led);
}
/// @brief Rempli le buffer à envoyer au LED, necessite d'appeler la fonction ws2812_affiche_buffer() ensuite
/// @param couleur : couleur en RVB
/// @param index_led : index entre 0 et 11
void ws2812_set_buffer(uint32_t couleur, uint8_t index_led){
if(index_led <12){
buffer_couleur[index_led] = couleur;
}
}

View File

@ -1,7 +0,0 @@
#include "pico/stdlib.h"
void ws2812_init(void);
void ws2812_affiche_buffer(void);
void ws2812_set_buffer_rgb(uint8_t rouge, uint8_t vert, uint8_t bleu, uint8_t index_led);
void ws2812_set_buffer_8bits(uint8_t couleur, uint8_t index_led);
void ws2812_arc_en_ciel(void);

View File

@ -1,85 +0,0 @@
;
; Copyright (c) 2020 Raspberry Pi (Trading) Ltd.
;
; SPDX-License-Identifier: BSD-3-Clause
;
.program ws2812
.side_set 1
.define public T1 2
.define public T2 5
.define public T3 3
.lang_opt python sideset_init = pico.PIO.OUT_HIGH
.lang_opt python out_init = pico.PIO.OUT_HIGH
.lang_opt python out_shiftdir = 1
.wrap_target
bitloop:
out x, 1 side 0 [T3 - 1] ; Side-set still takes place when instruction stalls
jmp !x do_zero side 1 [T1 - 1] ; Branch on the bit we shifted out. Positive pulse
do_one:
jmp bitloop side 1 [T2 - 1] ; Continue driving high, for a long pulse
do_zero:
nop side 0 [T2 - 1] ; Or drive low, for a short pulse
.wrap
% c-sdk {
#include "hardware/clocks.h"
static inline void ws2812_program_init(PIO pio, uint sm, uint offset, uint pin, float freq, bool rgbw) {
pio_gpio_init(pio, pin);
pio_sm_set_consecutive_pindirs(pio, sm, pin, 1, true);
pio_sm_config c = ws2812_program_get_default_config(offset);
sm_config_set_sideset_pins(&c, pin);
sm_config_set_out_shift(&c, false, true, rgbw ? 32 : 24);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
int cycles_per_bit = ws2812_T1 + ws2812_T2 + ws2812_T3;
float div = clock_get_hz(clk_sys) / (freq * cycles_per_bit);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, true);
}
%}
.program ws2812_parallel
.define public T1 2
.define public T2 5
.define public T3 3
.wrap_target
out x, 32
mov pins, !null [T1-1]
mov pins, x [T2-1]
mov pins, null [T3-2]
.wrap
% c-sdk {
#include "hardware/clocks.h"
static inline void ws2812_parallel_program_init(PIO pio, uint sm, uint offset, uint pin_base, uint pin_count, float freq) {
for(uint i=pin_base; i<pin_base+pin_count; i++) {
pio_gpio_init(pio, i);
}
pio_sm_set_consecutive_pindirs(pio, sm, pin_base, pin_count, true);
pio_sm_config c = ws2812_parallel_program_get_default_config(offset);
sm_config_set_out_shift(&c, true, true, 32);
sm_config_set_out_pins(&c, pin_base, pin_count);
sm_config_set_set_pins(&c, pin_base, pin_count);
sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
int cycles_per_bit = ws2812_parallel_T1 + ws2812_parallel_T2 + ws2812_parallel_T3;
float div = clock_get_hz(clk_sys) / (freq * cycles_per_bit);
sm_config_set_clkdiv(&c, div);
pio_sm_init(pio, sm, offset, &c);
pio_sm_set_enabled(pio, sm, true);
}
%}