Skip to content

Commit

Permalink
Merge pull request #6 from cparata/master
Browse files Browse the repository at this point in the history
Add begin and end APIs and update examples
  • Loading branch information
cparata authored Jan 29, 2021
2 parents 3bfdd40 + 733f4cb commit 0d083fd
Show file tree
Hide file tree
Showing 6 changed files with 45 additions and 31 deletions.
18 changes: 9 additions & 9 deletions examples/VL53L3CX_Sat_HelloWorld/VL53L3CX_Sat_HelloWorld.ino
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@
#define LedPin LED_BUILTIN

// Components.
VL53LX *sensor_vl53lx_sat;
VL53LX sensor_vl53lx_sat(&DEV_I2C, A1);


/* Setup ---------------------------------------------------------------------*/
Expand All @@ -84,17 +84,17 @@ void setup()
// Initialize I2C bus.
DEV_I2C.begin();

// Create VL53LX satellite component.
sensor_vl53lx_sat = new VL53LX(&DEV_I2C, A1, A2);
// Configure VL53LX satellite component.
sensor_vl53lx_sat.begin();

// Switch off VL53LX satellite component.
sensor_vl53lx_sat->VL53LX_Off();
sensor_vl53lx_sat.VL53LX_Off();

//Initialize VL53LX satellite component.
sensor_vl53lx_sat->InitSensor(0x12);
sensor_vl53lx_sat.InitSensor(0x12);

// Start Measurements
sensor_vl53lx_sat->VL53LX_StartMeasurement();
sensor_vl53lx_sat.VL53LX_StartMeasurement();
}

void loop()
Expand All @@ -108,15 +108,15 @@ void loop()

do
{
status = sensor_vl53lx_sat->VL53LX_GetMeasurementDataReady(&NewDataReady);
status = sensor_vl53lx_sat.VL53LX_GetMeasurementDataReady(&NewDataReady);
} while (!NewDataReady);

//Led on
digitalWrite(LedPin, HIGH);

if((!status)&&(NewDataReady!=0))
{
status = sensor_vl53lx_sat->VL53LX_GetMultiRangingData(pMultiRangingData);
status = sensor_vl53lx_sat.VL53LX_GetMultiRangingData(pMultiRangingData);
no_of_object_found=pMultiRangingData->NumberOfObjectsFound;
snprintf(report, sizeof(report), "VL53LX Satellite: Count=%d, #Objs=%1d ", pMultiRangingData->StreamCount, no_of_object_found);
SerialPort.print(report);
Expand All @@ -137,7 +137,7 @@ void loop()
SerialPort.println("");
if (status==0)
{
status = sensor_vl53lx_sat->VL53LX_ClearInterruptAndStartMeasurement();
status = sensor_vl53lx_sat.VL53LX_ClearInterruptAndStartMeasurement();
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@
#define interruptPin A2

// Components.
VL53LX *sensor_vl53lx_sat;
VL53LX sensor_vl53lx_sat(&DEV_I2C, A1);

volatile int interruptCount=0;

Expand All @@ -98,20 +98,20 @@ void setup()
// Initialize I2C bus.
DEV_I2C.begin();

// Create VL53LX satellite component.
sensor_vl53lx_sat = new VL53LX(&DEV_I2C, A1, A2);
// Configure VL53LX satellite component.
sensor_vl53lx_sat.begin();

// Switch off VL53LX satellite component.
sensor_vl53lx_sat->VL53LX_Off();
sensor_vl53lx_sat.VL53LX_Off();

// Initialize VL53LX satellite component.
status = sensor_vl53lx_sat->InitSensor(0x12);
status = sensor_vl53lx_sat.InitSensor(0x12);
if(status)
{
SerialPort.println("Init sensor_vl53lx_sat failed...");
}

sensor_vl53lx_sat->VL53LX_StartMeasurement();
sensor_vl53lx_sat.VL53LX_StartMeasurement();
}

void loop()
Expand All @@ -129,10 +129,10 @@ void loop()
// Led blinking.
digitalWrite(LedPin, HIGH);

status = sensor_vl53lx_sat->VL53LX_GetMeasurementDataReady(&NewDataReady);
status = sensor_vl53lx_sat.VL53LX_GetMeasurementDataReady(&NewDataReady);
if((!status)&&(NewDataReady!=0))
{
status = sensor_vl53lx_sat->VL53LX_GetMultiRangingData(pMultiRangingData);
status = sensor_vl53lx_sat.VL53LX_GetMultiRangingData(pMultiRangingData);
no_of_object_found=pMultiRangingData->NumberOfObjectsFound;
snprintf(report, sizeof(report), "Count=%d, #Objs=%1d ", pMultiRangingData->StreamCount, no_of_object_found);
SerialPort.print(report);
Expand All @@ -153,7 +153,7 @@ void loop()
SerialPort.println("");
if (status==0)
{
status = sensor_vl53lx_sat->VL53LX_ClearInterruptAndStartMeasurement();
status = sensor_vl53lx_sat.VL53LX_ClearInterruptAndStartMeasurement();
}
}

Expand Down
4 changes: 3 additions & 1 deletion keywords.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,15 @@
#######################################

ComponentObject KEYWORD1
LightSensor KEYWORD1
RangeSensor KEYWORD1
VL53L3CX KEYWORD1

#######################################
# Methods and Functions (KEYWORD2)
#######################################

begin KEYWORD2
end KEYWORD2
VL53LX_On KEYWORD2
VL53LX_Off KEYWORD2
InitSensor KEYWORD2
Expand Down
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=STM32duino VL53L3CX
version=1.0.2
version=2.0.0
author=STMicroelectronics
maintainer=stm32duino
sentence=Allows controlling the VL53L3CX (Time-of-Flight ranging sensor with multi target detection)
Expand Down
32 changes: 22 additions & 10 deletions src/vl53lx_class.h
Original file line number Diff line number Diff line change
Expand Up @@ -99,18 +99,15 @@
class VL53LX : public RangeSensor {
public:
/** Constructor
* @param[in] &i2c device I2C to be used for communication
* @param[in] &pin_gpio1 pin Mbed InterruptIn PinName to be used as component GPIO_1 INT
* @param[in] DevAddr device address, 0x52 by default
* @param[in] i2c device I2C to be used for communication
* @param[in] pin shutdown pin to be used as component GPIO0
*/
VL53LX(TwoWire *i2c, int pin, int pin_gpio1) : RangeSensor(), dev_i2c(i2c), gpio0(pin), gpio1Int(pin_gpio1)
VL53LX(TwoWire *i2c, int pin) : RangeSensor(), dev_i2c(i2c), gpio0(pin)
{
MyDevice.I2cDevAddr = VL53LX_DEFAULT_DEVICE_ADDRESS ;
MyDevice.I2cHandle = i2c;
Dev = &MyDevice;
if (gpio0 >= 0) {
pinMode(gpio0, OUTPUT);
}
memset((void *)Dev, 0x0, sizeof(VL53LX_Dev_t));
MyDevice.I2cHandle = i2c;
MyDevice.I2cDevAddr = VL53LX_DEFAULT_DEVICE_ADDRESS ;
}


Expand All @@ -120,6 +117,22 @@ class VL53LX : public RangeSensor {
/* warning: VL53LX class inherits from GenericSensor, RangeSensor and LightSensor, that haven`t a destructor.
The warning should request to introduce a virtual destructor to make sure to delete the object */

virtual int begin()
{
if (gpio0 >= 0) {
pinMode(gpio0, OUTPUT);
}
return 0;
}

virtual int end()
{
if (gpio0 >= 0) {
pinMode(gpio0, INPUT);
}
return 0;
}

/*** Interface Methods ***/
/*** High level API ***/
/**
Expand Down Expand Up @@ -3529,7 +3542,6 @@ class VL53LX : public RangeSensor {
TwoWire *dev_i2c;
/* Digital out pin */
int gpio0;
int gpio1Int;
/* Device data */
VL53LX_Dev_t MyDevice;
VL53LX_DEV Dev;
Expand Down
2 changes: 1 addition & 1 deletion src/vl53lx_def.h
Original file line number Diff line number Diff line change
Expand Up @@ -3479,7 +3479,7 @@ typedef int8_t VL53LX_Error;
#define VL53LX_ERROR_XTALK_EXTRACTION_NO_SAMPLE_FAIL ((VL53LX_Error) - 22)
/*!< Thrown when run_xtalk_extraction fn has 0 successful samples
* when using the full array to sample the xtalk. In this case there is
* not enough information to generate new Xtalk parm info. The function
* not enough information to generate new Xtalk param info. The function
* will exit and leave the current xtalk parameters unaltered
*/
#define VL53LX_ERROR_XTALK_EXTRACTION_SIGMA_LIMIT_FAIL ((VL53LX_Error) - 23)
Expand Down

0 comments on commit 0d083fd

Please sign in to comment.