Working version without LEDs
Voici le dernier schéma de cablage (version du 08/02/2020)
https://os.mbed.com/media/uploads/max_ence/schemarobot_fev2020.pdf
Revision 0:0e577ce96b2f, committed 2020-02-08
- Comitter:
- elab
- Date:
- Sat Feb 08 09:48:46 2020 +0000
- Child:
- 1:69b5d8f0ba9c
- Commit message:
- working version wihout LEDs
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/CreabotLib/CreaBot.cpp Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,283 @@
+#include "CreaBot.h"
+
+Creabot::Creabot(Motor *left, Motor *right, float diameter_wheel_cm, float distance_wheel_cm):motor_left(left), motor_right(right), diameter_wheel(diameter_wheel_cm), distance_wheel(distance_wheel_cm)
+{
+ perimeter_wheel = PI*diameter_wheel;
+ perimeter_bot = PI*distance_wheel;
+ degree_wheel_per_cm=360.0f/perimeter_wheel;
+ degree_bot_per_cm=360.0f/perimeter_bot;;
+ ratio_wheel_bot=perimeter_bot/perimeter_wheel;
+ status=0;
+
+ motor_left->setMotorCallback(this, &Creabot::callBackLeft);
+ motor_right->setMotorCallback(this, &Creabot::callBackRight);
+ extCallBack = NULL;
+ setSpeed(DEFAULT_SPEED);
+ callLeft = true;
+ callRight = true;
+ endMove=true;
+ executingFifo=false;
+}
+
+void Creabot::moveForward(float cm)
+{
+ float angle;
+ if(cm<0) moveBackward(cm);
+ angle = cm*degree_wheel_per_cm;
+ setSpeedLeft(current_speed);
+ setSpeedRight(current_speed);
+ moveMotorLeft(COUNTERCLOCKWISE, angle);
+ moveMotorRight(CLOCKWISE, angle);
+
+}
+
+void Creabot::moveBackward(float cm)
+{
+ float angle;
+ if(cm<0) moveForward(cm);
+ angle = cm*degree_wheel_per_cm;
+ setSpeedLeft(current_speed);
+ setSpeedRight(current_speed);
+ moveMotorLeft(CLOCKWISE, angle);
+ moveMotorRight(COUNTERCLOCKWISE, angle);
+
+}
+void Creabot::rotate(float angleBot)
+{
+ float angleWheel;
+ setSpeedLeft(current_speed);
+ setSpeedRight(current_speed);
+ angleWheel = angleBot*ratio_wheel_bot;
+ if(angleBot<0) {
+ moveMotorLeft(CLOCKWISE, -angleWheel);
+ moveMotorRight(CLOCKWISE, -angleWheel);
+ } else {
+ moveMotorLeft(COUNTERCLOCKWISE, angleWheel);
+ moveMotorRight(COUNTERCLOCKWISE, angleWheel);
+ }
+}
+void Creabot::moveRight(float angle)
+{
+ moveRight(angle,distance_wheel);
+}
+void Creabot::moveRight(float angle, float center_cm)
+{
+ if(center_cm<0) center_cm=0; /* TO remove? */
+ float perimeter_outer = 2.0f*angle*(center_cm+distance_wheel)*PI/360.0f;
+ float perimeter_inner = 2.0f*angle*(center_cm)*PI/360.0f;
+ float angleLeft = perimeter_outer*degree_wheel_per_cm;
+ float angleRight = perimeter_inner*degree_wheel_per_cm;
+ float ratio = angleRight/angleLeft;
+ float speedRight = current_speed * ratio;
+ // pc_uart.printf("Set Perimeter angle =%f center_cm=%f outer = %f inner = %f angle_left %f angle right %f ratio %f cs %f\n\r",angle, center_cm, perimeter_outer,perimeter_inner,angleLeft,angleRight,ratio, current_speed);
+ setSpeedLeft(current_speed);
+ setSpeedRight(speedRight);
+ moveMotorLeft(COUNTERCLOCKWISE, angleLeft);
+ moveMotorRight(CLOCKWISE, angleRight);
+
+}
+void Creabot::moveLeft(float angle)
+{
+ moveLeft(angle,0);
+}
+void Creabot::moveLeft(float angle, float center_cm)
+{
+ if(center_cm<0) center_cm=0; /* TO remove? */
+ float perimeter_outer = 2.0f*angle*(center_cm+distance_wheel)*PI/360.0f;
+ float perimeter_inner = 2.0f*angle*(center_cm)*PI/360.0f;
+ float angleLeft = perimeter_inner*degree_wheel_per_cm;
+ float angleRight = perimeter_outer*degree_wheel_per_cm;
+ float ratio = angleLeft/angleRight;
+ float speedRLeft = current_speed * ratio;
+ setSpeedLeft(speedRLeft);
+ setSpeedRight(current_speed);
+ moveMotorLeft(COUNTERCLOCKWISE, angleLeft);
+ moveMotorRight(CLOCKWISE, angleRight);
+
+}
+void Creabot::stopMove()
+{
+ motor_left->Stop();
+ motor_right->Stop();
+ callLeft = true;
+ callRight = true;
+ endMove = true;
+ flushFifo();
+ // callBack(); // ? To be called or set as parameter?
+}
+int Creabot::getStatus()
+{
+ if(endMove == true) return 0; // No Movement
+ if(callRight == true) return 1; // Left Motor still running
+ if(callLeft == true) return 3; // ERROR
+ return 2; // Left Motor still running
+}
+
+void Creabot::setSpeed(float cm_per_second)
+{
+ setSpeedLeft(cm_per_second);
+ setSpeedRight(cm_per_second);
+ current_speed = cm_per_second;
+}
+
+uint32_t Creabot::computeSpeed(Motor *motor, float cm_per_second)
+{
+ uint32_t tick, timeUnit;
+ tick = motor->getCalibration();
+ if(cm_per_second <0.0001f) timeUnit = 1000000; else
+ timeUnit = perimeter_wheel * 1000000 / cm_per_second / tick;
+ return timeUnit;
+}
+
+void Creabot::setSpeedLeft(float cm_per_second)
+{
+ motor_left->setDelayBtwTicks(computeSpeed(motor_left, cm_per_second));
+}
+
+void Creabot::setSpeedRight(float cm_per_second)
+{
+ motor_right->setDelayBtwTicks(computeSpeed(motor_right, cm_per_second));
+}
+
+void Creabot::waitEndMove()
+{
+ while(!endMove || executingFifo) {
+ wait(0.1);
+ }
+
+}
+void Creabot::waitEndMove(uint32_t delay_us)
+{
+ uint32_t v=0;
+ while(!endMove || executingFifo) {
+ wait(0.1);
+ v++;
+ if((v*10000)>delay_us) endMove = true;
+ }
+} // watchdog
+
+void Creabot::setCallBack(void (*callback)(int status))
+{
+ extCallBack = callback;
+}
+
+void Creabot::fifo(cmdbot_t moveType, float angle_or_cm)
+{
+ CommandBot *cmd = fifoBot.put();
+ if(cmd!=NULL) {
+ cmd->add_command(moveType, angle_or_cm, 0);
+ }
+ executeFifo();
+}
+void Creabot::fifo(cmdbot_t moveType, float angle, float cm)
+{
+ CommandBot *cmd = fifoBot.put();
+ if(cmd!=NULL) {
+ cmd->add_command(moveType, angle, cm);
+ }
+ executeFifo();
+}
+
+
+void Creabot::moveAndWait(cmdbot_t moveType, float angle_or_cm)
+{
+ move(moveType,angle_or_cm);
+ waitEndMove();
+}
+void Creabot::moveAndWait(cmdbot_t moveType, float angle, float cm)
+{
+ move(moveType,angle,cm);
+ waitEndMove();
+}
+
+void Creabot::move(cmdbot_t moveType, float angle_or_cm)
+{
+ current_cmd.add_command(moveType, angle_or_cm, 0);
+ executeCommand(¤t_cmd);
+}
+void Creabot::move(cmdbot_t moveType, float angle, float cm)
+{
+ current_cmd.add_command(moveType, angle, cm);
+ executeCommand(¤t_cmd);
+}
+
+void Creabot::flushFifo()
+{
+ fifoBot.empty();
+ if(executingFifo) botTicker.detach();
+ executingFifo=false;
+}
+int Creabot::moveInFifo()
+{
+ return fifoBot.getSize();
+}
+void Creabot::executeCommand(CommandBot *cmd) {
+ switch (cmd->command) {
+ case FORWARD:
+ moveForward(cmd->cm);
+ break;
+ case BACKWARD:
+ moveBackward(cmd->cm);
+ break;
+ case ROTATE:
+ rotate(cmd->angle);
+ break;
+ case LEFT:
+ moveLeft(cmd->angle, cmd->cm);
+ break;
+ case RIGHT:
+ moveRight(cmd->angle, cmd->cm);
+ break;
+ case IDLE:
+ // wait(10); // Not to be done in an interrupt. could start a timer with a call back with 'end move'? Would be stopped by stopMove...
+ break;
+ default:
+ break;
+ };
+}
+void Creabot::executeFifo()
+{
+
+ if(fifoBot.getSize()==0) flushFifo();
+ else {
+ if(endMove) {
+ CommandBot *cmd = fifoBot.get();
+ executeCommand(cmd);
+ if(!executingFifo) botTicker.attach_us(callback(this,&Creabot::executeFifo),3150);
+ executingFifo=true;
+
+ }
+ }
+}
+
+void Creabot::callBackLeft()
+{
+ callLeft=true;
+ if(callRight)callBack();
+}
+void Creabot::callBackRight()
+{
+ callRight=true;
+ if(callLeft)callBack();
+}
+
+void Creabot::callBack()
+{
+ endMove=true;
+ if(extCallBack!=NULL) extCallBack(status);
+}
+
+void Creabot::moveMotorLeft(MotorDir dir, float angle)
+{
+ if(angle>0) {
+ motor_left->RunDegrees(dir, angle);
+ endMove = callLeft = false;
+ }
+}
+void Creabot::moveMotorRight(MotorDir dir, float angle)
+{
+ if(angle>0) {
+ motor_right->RunDegrees(dir, angle);
+ endMove = callRight = false;
+ }
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/CreabotLib/CreaBot.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,144 @@
+
+#ifndef CREABOT_H
+#define CREABOT_H
+
+#include "mbed.h"
+#include "motor.h"
+
+#define MAX_SPEED 30 //cm per second
+#define DEFAULT_SPEED 2 //cm per second
+#define PI 3.141592f
+#define DEPTH_FIFO 256
+
+typedef enum {FORWARD, BACKWARD, ROTATE, LEFT, RIGHT, IDLE} cmdbot_t;
+class CommandBot {
+ public:
+ cmdbot_t command;
+ float angle;
+ float cm;
+
+ void add_command(cmdbot_t cmd, float p1, float p2) {command = cmd; switch (command) {case FORWARD:;case BACKWARD: cm=p1; angle=0; break; case ROTATE: angle = p1; break; case LEFT: case RIGHT: angle = p1; cm=p2;break; case IDLE:break; default: break;}};
+};
+
+class MyFifoCmd {
+
+ public:
+ MyFifoCmd() {start = end = size = 0;cmd_idle.command = IDLE;cmd_idle.angle=0;cmd_idle.cm=0;};
+ void empty() {start=end=size=0;};
+ CommandBot *put() {if(size<DEPTH_FIFO) {int old_end = end;end++;if(end==DEPTH_FIFO)end=0;size++;return &cmd[old_end];} else return NULL;};
+ CommandBot *get() {if(size>0) {int old_start = start; start++;if(start==DEPTH_FIFO)start=0; size--; return &cmd[old_start];} else return NULL;}
+ int getSize() {return size;}
+ private:
+ int start, end, size;
+ CommandBot cmd[DEPTH_FIFO];
+ CommandBot cmd_idle;
+};
+
+
+/** Asynchronous Control of 2 motors part of a robot
+ *
+ * Example:
+ * @code
+ * // --- Define the Four PINs & Time of movement used for Motor drive -----
+ * Motor motorLeft(PA_12, PB_0, PB_1, PB_6); // Declare first the 2 motors (to avoid to have an object with 8 pins to create)
+ * Motor motorRight(PA_5,PA_4,PA_3,PA_1);
+ * Creabot mybot(&motorLeft, &motorRight, 10.0f,13.0f); // insert the motors and indicate wheel diameter and distance between wheels
+ *
+ * int main() {
+ *
+ * mybot.setSpeed(12.5); // 12.5cm/s
+ * mybot.move(FORWARD,10); // Go forward of 10cm
+ * mybot.waitEndMove(); // Wait end of Move
+ * mybot.move(ROTATE,90); // Start rotation of 90° around the center between wheels (two wheels running in same direction at same speed)
+ * mybot.move(BACKWARD,40); // Stop immediately the rotation and go backward of 40cm
+ * mybot.waitEndMove(); // Wait end of Backward
+ * mybot.moveAndWait(LEFT,60); // Move Left of 60° in circle, center being the left wheel (off). Wait end of move
+ * mybot.waitEndMove(); // Not needed, as already waited...
+ * mybot.moveAndWait(RIGHT,45, 33); // Move Right of 45°, center being at 33cm of the right wheel. Right wheel moving slower and on a shorter distance than left one.
+ * mybot.moveAndWait(ROTATE,90);
+ * mybot.move(ROTATE,-90); // Opposite direction.
+ * mybot.waitEndMove(60); // with watchdog => if after 60s the move is not ended, continue the execution
+ * mybot.stopMove(); // Stop the movement before end...
+ *
+ * // Same with a fifo of command, opposite to the move, receiving a new command will not stop the current execution, but the bot will store it.
+ * mybot.fifo(FORWARD,10); // Already starting...
+ * mybot.fifo(BACKWARD,10); // will wait end of previous command to go
+ * mybot.fifo(ROTATE,120.0);
+ * mybot.fifo(LEFT, 30, 120);
+ * mybot.fifo(RIGHT, 25);
+ * mybot.waitEndMove(100000); // wait until fifo end... can flush anytime with stopMove...
+ * mybot.stopMove(); // before end... Flush the fifo and remove all instructions…
+ *
+ * while(1) {
+ * };
+ * }
+ * @endcode
+ */
+class Creabot {
+public:
+ /** Create a Creabot object to synchronize 2 motors
+ *
+ * @param left Motor object declared before corresponding to left motor of the Creabot
+ * @param right Motor object declared before corresponding to right motor of the Creabot
+ * @param diameter_wheel_cm diameter in cm of the wheels (both supposed to be at same diameter)
+ * @param distance_wheel_cm distance in cm between center of left wheel and center of right wheel
+ */
+ Creabot(Motor *left, Motor *right, float diameter_wheel_cm, float distance_wheel_cm);
+ int getStatus();
+ void setSpeed(float cm_per_second);
+ void waitEndMove();
+ void waitEndMove(uint32_t delay_us); // watchdog
+ void setCallBack(void (*callback)(int status));
+ void moveAndWait(cmdbot_t moveType, float angle_or_cm);
+ void moveAndWait(cmdbot_t moveType, float angle, float cm);
+ void move(cmdbot_t moveType, float angle_or_cm);
+ void move(cmdbot_t moveType, float angle, float cm);
+ void fifo(cmdbot_t moveType, float angle_or_cm);
+ void fifo(cmdbot_t moveType, float angle, float cm);
+ void flushFifo();
+ int moveInFifo();
+ void executeFifo();
+ void stopMove();
+
+private:
+ void moveForward(float cm);
+ void moveBackward(float cm);
+ void rotate(float angle);
+ void moveRight(float angle);
+ void moveRight(float angle, float center_cm);
+ void moveLeft(float angle);
+ void moveLeft(float angle, float center_cm);
+ void callBackLeft();
+ void callBackRight();
+ void callBack();
+ uint32_t computeSpeed(Motor *motor, float cm_per_second);
+ void setSpeedLeft(float cm_per_second);
+ void setSpeedRight(float cm_per_second);
+
+ void (*extCallBack)(int status);
+ void moveMotorLeft(MotorDir dir, float angle);
+ void moveMotorRight(MotorDir dir, float angle);
+ void executeCommand(CommandBot *cmd);
+
+
+ Motor *motor_left;
+ Motor *motor_right;
+ float diameter_wheel;
+ float distance_wheel;
+ float perimeter_wheel;
+ float perimeter_bot;
+ float degree_wheel_per_cm;
+ float degree_bot_per_cm;
+ float ratio_wheel_bot;
+ float current_speed;
+ int status;
+ bool callLeft;
+ bool callRight;
+ bool endMove;
+ MyFifoCmd fifoBot;
+ CommandBot current_cmd;
+ Ticker botTicker;
+ bool executingFifo;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/Crealab.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,16 @@
+#include "mbed.h"
+#include "CreaBot.h"
+
+// --- USB Debug Port -----------
+
+// #define DEBUG(...) { pc_uart.printf(__VA_ARGS__); bt_uart.printf(__VA_ARGS__);}
+#define DEBUG(...) { __disable_irq();bt_uart.printf(__VA_ARGS__); pc_uart.printf(__VA_ARGS__);__enable_irq();}
+
+//#define DEBUG(...) { pc_uart.printf(__VA_ARGS__); }
+//#define DEBUG(...) { bt_uart.printf(__VA_ARGS__); }
+
+#define CATCH_BUTTON(button, func) button.fall(&func)
+
+#define CASE(letter, text, commands) case letter: DEBUG("\t%c : %s\n\r", letter,text);if(!flaghelp) {commands;break;};
+
+
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/LED_WS2812/LED_WS2812.cpp Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,209 @@
+#include "LED_WS2812.h"
+
+
+
+LED_WS2812::LED_WS2812(PinName _PinOut, int _nbLeds) {
+ nbLeds = _nbLeds;
+ double period_ns;
+ Timer tuneTimings;
+ int sum = 0;
+ int nopRun;
+
+ for(int kavg = 0; kavg<20;kavg++) {
+ tuneTimings.reset();
+ tuneTimings.start();
+ for(int nopCount=0; nopCount < 10000; nopCount ++) {
+ __nop();
+ }
+ tuneTimings.stop();
+ nopRun = tuneTimings.read_us();
+ sum=nopRun+sum;
+ }
+ period_ns = sum/200; /* *1000 for nanoseconds /20 average /10000 count */
+
+ int zero_high = ZERO_HIGH/period_ns;
+ int zero_low = ZERO_LOW/period_ns;
+ int one_high = ONE_HIGH/period_ns;
+ int one_low = ONE_LOW/period_ns;
+
+ ws = new WS2812(_PinOut, nbLeds, zero_high, zero_low, one_high, one_low);
+ ws->useII(WS2812::PER_PIXEL);
+
+ pxArray = new PixelArray(nbLeds);
+ pxInsert = new PixelArray(nbLeds);
+ ResetColor();
+ rotationState = false;
+ rotationPosition = nbLeds-1;
+ blinkState = false;
+ blinkONOFF = false;
+ intensity = 0xff;
+};
+
+LED_WS2812::~LED_WS2812() {
+ delete(ws);
+ delete(pxArray);
+}
+
+
+
+void LED_WS2812::SetColor(LED_COLORS _color, int position) {
+ SetColor((unsigned int) _color, position);
+};
+
+void LED_WS2812::SetColor(unsigned int _color, int position) {
+ if(position < nbLeds && position >=0 ) {
+ pxArray->Set(position, _color);
+ pxArray->SetI(position,intensity);
+
+ }
+ __writeBuf(0);
+ nbInsert = 0;
+ if(rotationState) StopRotation();
+ rotationPosition = nbLeds;
+};
+
+void LED_WS2812::SetColor(LED_COLORS _color) {
+ SetColor((unsigned int) _color);
+};
+
+void LED_WS2812::SetColor(unsigned int _color) {
+ for(int i=0;i<nbLeds;i++) {
+ pxArray->Set(i, _color);
+ pxArray->SetI(i,intensity);
+ }
+ __writeBuf(0);
+ nbInsert = 0;
+ if(rotationState) StopRotation();
+ rotationPosition = nbLeds;
+};
+
+
+void LED_WS2812::ResetColor() {
+ SetColor(BLACK);
+
+ }
+
+void LED_WS2812::__writeBuf(int z) {
+ ws->write_offsets(pxArray->getBuf(),z,z,z);
+ wait(0.01);
+ }
+
+void LED_WS2812::__insert2buf() {
+ for(int i=0;i<nbLeds;i++) {
+ pxArray->Set(i, pxInsert->Get(i%nbInsert));
+ }
+ __writeBuf(0);
+ rotationPosition = nbLeds;
+}
+
+void LED_WS2812::__insertColor(unsigned int _color, int _intensity) {
+ pxInsert->Set(nbInsert%nbLeds,_color);
+ pxInsert->SetI(nbInsert%nbLeds,_intensity);
+ nbInsert++;
+
+};
+
+void LED_WS2812::InsertColor(unsigned int _color) {
+ InsertColor(_color,intensity*100/0xFF);
+};
+
+
+void LED_WS2812::InsertColor(unsigned int _color, float brightness) {
+ int pixelIntensity = brightness*0xFF/100;
+ __insertColor(_color, pixelIntensity);
+ __insert2buf();
+};
+
+
+void LED_WS2812::InsertColorNtimes(int N, unsigned int _color, float brightness) {
+ for(int i=0;i<N;i++) {
+ InsertColor(_color, brightness);
+ }
+};
+
+void LED_WS2812::InsertColorNtimes(int N, unsigned int _color) {
+ InsertColorNtimes(N, _color, intensity*100/0xFF);
+};
+
+
+void LED_WS2812::InsertColor(LED_COLORS _color) {
+ InsertColor((unsigned int)_color);
+};
+
+
+void LED_WS2812::InsertColor(LED_COLORS _color, float brightness) {
+ InsertColor((unsigned int)_color, brightness);
+};
+
+
+void LED_WS2812::InsertColorNtimes(int N, LED_COLORS _color, float brightness) {
+ InsertColorNtimes(N, (unsigned int)_color, brightness);
+};
+
+void LED_WS2812::InsertColorNtimes(int N, LED_COLORS _color) {
+ InsertColorNtimes(N, _color, intensity*100/0xFF);
+};
+
+
+void LED_WS2812::SetIntensity(float perCent) {
+ intensity = perCent*0xFF/100;
+ ws->setII(intensity);
+ for(int i=0;i<nbLeds;i++) {
+ pxArray->SetI(i,intensity);
+ }
+}
+
+void LED_WS2812::StartRotation(float interval) {
+ if(rotationState==false) {
+ rotationState = true;
+ LEDSystemTick.attach_us(callback(this, &LED_WS2812::Rotate), interval*1000000);
+ }
+}
+
+
+void LED_WS2812::StopRotation() {
+ if(rotationState==true) {
+ rotationState = false;
+ rotationPosition = 0;
+ LEDSystemTick.detach();
+ }
+}
+
+void LED_WS2812::Rotate() {
+ rotationPosition--;
+ if (rotationPosition == -1)
+ rotationPosition = nbLeds-1;
+ if(!blinkState) __writeBuf(rotationPosition);
+}
+
+
+void LED_WS2812::StartBlink(float interval) {
+ StopBlink();
+ if(blinkState==false) {
+ blinkState = true;
+ LEDBlinkSystemTick.attach_us(callback(this, &LED_WS2812::Blink), interval*1000000);
+ }
+}
+
+
+void LED_WS2812::StopBlink() {
+ if(blinkState==true) {
+ blinkState = false;
+ LEDBlinkSystemTick.detach();
+ }
+}
+
+void LED_WS2812::Blink() {
+ blinkONOFF = !blinkONOFF;
+ if (blinkONOFF)
+ __writeBuf(rotationPosition);
+ else {
+ ws->useII(WS2812::GLOBAL);
+ ws->setII(0);
+ __writeBuf(rotationPosition);
+ ws->useII(WS2812::PER_PIXEL);
+ ws->setII(intensity);
+
+ }
+
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/LED_WS2812/LED_WS2812.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,84 @@
+
+#ifndef LED_WS2812_H
+#define LED_WS2812_H
+
+#include "mbed.h"
+#include "WS2812.h"
+#include "PixelArray.h"
+
+/*
+#define ZERO_HIGH 250.0
+#define ZERO_LOW 1000.0
+#define ONE_HIGH 1000.0
+#define ONE_LOW 250.0
+*/
+#define ZERO_HIGH 200.0
+#define ZERO_LOW 800.0
+#define ONE_HIGH 800.0
+#define ONE_LOW 200.0
+
+ typedef enum _LED_COLORS {
+ BLUE = 0x0000FF,
+ LIGHTBLUE = 0x00FFF6,
+ RED = 0xFF0000,
+ ORANGE = 0xFF3500,
+ GREEN = 0X00FF00,
+ BLACK = 0X000000,
+ WHITE = 0XFFFFFF,
+ PURPLE = 0XFF00FF,
+ PINK = 0XFF84A3,
+ YELLOW = 0XFFFF00,
+ DARK_YELLOW = 0X555500,
+ DEFAULT = 0x000000
+ } LED_COLORS;
+
+class LED_WS2812
+{
+public:
+ LED_WS2812(PinName _PinOut, int _nbLeds);
+ ~LED_WS2812();
+ void SetColor(LED_COLORS _color, int position);
+ void SetColor(unsigned int _color, int position);
+ void SetColor(unsigned int _color);
+ void SetColor(LED_COLORS _color);
+ void ResetColor();
+ void SetIntensity(float perCent);
+
+ void InsertColor(unsigned int _color);
+ void InsertColor(unsigned int _color, float brightness);
+ void InsertColorNtimes(int N, unsigned int _color, float brightness);
+ void InsertColorNtimes(int N, unsigned int _color);
+
+ void InsertColor(LED_COLORS _color);
+ void InsertColor(LED_COLORS _color, float brightness);
+ void InsertColorNtimes(int N, LED_COLORS _color, float brightness);
+ void InsertColorNtimes(int N, LED_COLORS _color);
+
+ void StartRotation(float interval); // interval in s
+ void StopRotation(); //
+ void Rotate(); // One Rotation
+
+ void StartBlink(float interval); // interval in s
+ void StopBlink(); //
+ void Blink(); // One Rotation
+
+private:
+ void __writeBuf(int z);
+ void __insert2buf();
+ void __insertColor(unsigned int _color, int _intensity);
+
+ WS2812 *ws;
+ int nbLeds;
+ PixelArray *pxArray;
+ int nbInsert;
+ PixelArray *pxInsert;
+ Ticker LEDSystemTick; // System Callback for Rotation
+ Ticker LEDBlinkSystemTick; // System Callback for Rotation
+ bool rotationState;
+ bool blinkState;
+ int rotationPosition;
+ bool blinkONOFF; // ON = true, OFF = false
+ int intensity;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/LED_WS2812/Pixel/PixelArray.cpp Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,173 @@
+#include "PixelArray.h"
+
+PixelArray::PixelArray(int size)
+{
+ pbufsize = size;
+ pbuf = new int[pbufsize];
+ SetAll(0x0); // initialise memory to zeros
+
+}
+
+PixelArray::~PixelArray()
+{
+ delete[] pbuf;
+}
+
+void PixelArray::SetAll(unsigned int value)
+{
+ // for each pixel
+ for (int i=0 ; i < pbufsize; i++) {
+ __set_pixel(i,value);
+ }
+}
+
+
+void PixelArray::SetAllI(unsigned char value)
+{
+ // for each pixel
+ for (int i=0 ; i < pbufsize; i++) {
+ __set_pixel_component(i,3,value);
+ }
+}
+
+
+
+void PixelArray::SetAllR(unsigned char value)
+{
+ // for each pixel
+ for (int i=0 ; i < pbufsize; i++) {
+ __set_pixel_component(i,2,value);
+ }
+}
+
+void PixelArray::SetAllG(unsigned char value)
+{
+ // for each pixel
+ for (int i=0 ; i < pbufsize; i++) {
+ __set_pixel_component(i,1,value);
+ }
+}
+
+void PixelArray::SetAllB(unsigned char value)
+{
+ // for each pixel
+ for (int i=0 ; i < pbufsize; i++) {
+ __set_pixel_component(i,0,value);
+ }
+}
+
+
+
+
+
+void PixelArray::Set(int i, unsigned int value)
+{
+ if ((i >= 0) && (i < pbufsize)) {
+ __set_pixel(i,value);
+ }
+}
+
+
+
+void PixelArray::SetI(int i, unsigned char value)
+{
+ if ((i >= 0) && (i < pbufsize)) {
+ __set_pixel_component(i,3,value);
+ }
+}
+
+
+void PixelArray::SetR(int i, unsigned char value)
+{
+ if ((i >= 0) && (i < pbufsize)) {
+ __set_pixel_component(i,2,value);
+ }
+}
+
+void PixelArray::SetG(int i, unsigned char value)
+{
+ if ((i >= 0) && (i < pbufsize)) {
+ __set_pixel_component(i,1,value);
+ }
+}
+
+void PixelArray::SetB(int i, unsigned char value)
+{
+ if ((i >= 0) && (i < pbufsize)) {
+ __set_pixel_component(i,0,value);
+ }
+}
+
+
+unsigned int PixelArray::Get(int i)
+{
+ return __get_pixel(i);
+}
+
+unsigned int PixelArray::GetI(int i)
+{
+ return __get_pixel_component(i,3);
+}
+
+unsigned int PixelArray::GetR(int i)
+{
+ return __get_pixel_component(i,2);
+}
+
+unsigned int PixelArray::GetG(int i)
+{
+ return __get_pixel_component(i,1);
+}
+
+unsigned int PixelArray::GetB(int i)
+{
+ return __get_pixel_component(i,0);
+}
+
+
+
+int* PixelArray::getBuf()
+{
+ return (pbuf);
+}
+
+
+// set either the I,R,G,B value of specific pixel channel
+void PixelArray::__set_pixel_component(int index, int channel, int value)
+{
+
+ // AND with 0x00 shifted to the right location to clear the bits
+ pbuf[index] &= ~(0xFF << (8 * channel));
+
+ // Set the bits with an OR
+ pbuf[index] |= (value << (8 * channel));
+}
+
+
+// set either the I,R,G,B value of specific pixel channel
+void PixelArray::__set_pixel(int index, int value)
+{
+ // AND with 0x00 shifted to the right location to clear the bits
+ pbuf[index] = value;
+}
+
+
+// get specific pixel
+int PixelArray::__get_pixel(int index)
+{
+ if ((index >= 0) && (index < pbufsize)) {
+ return pbuf[index];
+ } else {
+ return 0;
+ }
+}
+
+
+// get specific pixel
+int PixelArray::__get_pixel_component(int index, int channel)
+{
+ // AND with 0xFF shifted to the right location to get the bits
+ return ( (__get_pixel(index) & (0xFF << (8 * channel))) >> (8*channel) );
+}
+
+
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/LED_WS2812/Pixel/PixelArray.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,77 @@
+/* Copyright (c) 2012 cstyles, MIT License
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy of this software
+ * and associated documentation files (the "Software"), to deal in the Software without restriction,
+ * including without limitation the rights to use, copy, modify, merge, publish, distribute,
+ * sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in all copies or
+ * substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING
+ * BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+ * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM,
+ * DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+ */
+
+#ifndef PixelArray_H
+#define PixelArray_H
+
+#include "mbed.h"
+
+//!Library for the WS2812 RGB LED with integrated controller
+/*!
+PixelArray
+*/
+class PixelArray
+{
+public:
+ //!Creates an instance of the class.
+ /*!
+ Pixel Array
+ */
+ PixelArray(int);
+
+ /*!
+ Destroys instance.
+ */
+ ~PixelArray();
+
+ int* getBuf();
+
+ void SetAll(unsigned int);
+ void SetAllI(unsigned char);
+ void SetAllR(unsigned char);
+ void SetAllG(unsigned char);
+ void SetAllB(unsigned char);
+
+ // location, value
+ void Set(int, unsigned int);
+ void SetI(int, unsigned char);
+ void SetR(int, unsigned char);
+ void SetG(int, unsigned char);
+ void SetB(int, unsigned char);
+
+ unsigned int Get(int);
+ unsigned int GetI(int);
+ unsigned int GetR(int);
+ unsigned int GetG(int);
+ unsigned int GetB(int);
+
+private:
+
+ int *pbuf;
+ int pbufsize;
+
+ void __set_pixel_component(int index, int channel, int value);
+ void __set_pixel(int index, int value);
+
+ int __get_pixel_component(int index, int channel);
+ int __get_pixel(int index);
+
+};
+
+#endif
+
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/LED_WS2812/WS2812.lib Sat Feb 08 09:48:46 2020 +0000 @@ -0,0 +1,1 @@ +http://developer.mbed.org/users/bridadan/code/WS2812/#6e647820f587
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MotorLib/motor.cpp Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,248 @@
+#include "motor.h"
+
+void Motor::initialization(PinName _MPh0, PinName _MPh1, PinName _MPh2, PinName _MPh3, uint32_t tickTime) {
+//pc_uart.printf("MOTOR INIT\n");
+ MPh0 = new DigitalOut(_MPh0);
+ MPh1 = new DigitalOut(_MPh1);
+ MPh2 = new DigitalOut(_MPh2);
+ MPh3 = new DigitalOut(_MPh3);
+ init = true;
+ MotorIndex = 0;
+ //
+ // Connect Interrupt routine in which the motor and all the state machine is performed
+ //
+ direction = CLOCKWISE; // Default direction is clockwise
+ state = Motor_IDLE; // Default state is IDLE
+ command = MOTOR_nop; // Default command is NOP
+ MotorStepTime = tickTime; // value in micro second for one step
+ MotorFullTurn = MOTOR_TICKS_FOR_A_TURN; // Initial Calibration
+ NumSteps = MotorFullTurn; // Default 1 turn
+ itOnStop = true;
+ tuneTimings.reset();
+ tuneTimings.start();
+}
+
+Motor::Motor(PinName _MPh0, PinName _MPh1, PinName _MPh2, PinName _MPh3) {
+ initialization( _MPh0, _MPh1, _MPh2, _MPh3, MOTOR_STEP_TIME_DEFAULT);
+
+}
+
+
+Motor::Motor(PinName _MPh0, PinName _MPh1, PinName _MPh2, PinName _MPh3, uint32_t tickTime) {
+
+ initialization( _MPh0, _MPh1, _MPh2, _MPh3, tickTime);
+
+}
+
+
+void Motor::removeMotorCallback() {
+
+ _callback = NULL;
+
+}
+
+void Motor::setMotorCallback(void (*function)(void))
+{
+ setMotorCallback(function, true);
+}
+void Motor::setMotorCallback(void (*function)(void), bool onStop)
+{
+ _callback = function;
+ itOnStop = onStop;
+}
+
+
+uint32_t Motor::getCalibration()
+{
+ return MotorFullTurn;
+}
+
+void Motor::setCalibration(uint32_t nbTicksforFullTurn) {
+ MotorFullTurn = nbTicksforFullTurn;
+}
+
+void Motor::setDelayBtwTicks(uint32_t tickTime) {
+ if(MotorStepTime == tickTime) return;
+ MotorStepTime = tickTime;
+ if(MotorStepTime < MOTOR_STEP_TIME_MIN) MotorStepTime = MOTOR_STEP_TIME_MIN;
+ // pc_uart.printf("Change ticktime to %d %d\n\r",tickTime, MotorStepTime);
+ if(!init) {
+ MotorSystemTick.detach();
+ MotorSystemTick.attach_us(callback(this, &Motor::ProcessMotorStateMachine), MotorStepTime);
+ }
+}
+
+void Motor::setSpeed(float sForOneTurn) {
+ MotorStepTime = 1000*sForOneTurn / MotorFullTurn;
+ if(MotorStepTime < MOTOR_STEP_TIME_MIN) MotorStepTime = MOTOR_STEP_TIME_MIN;
+ if(!init) {
+
+ MotorSystemTick.detach();
+ MotorSystemTick.attach_us(callback(this, &Motor::ProcessMotorStateMachine), MotorStepTime);
+ }
+}
+
+void Motor::Start() {
+ SetCommand(MOTOR_start);
+};
+
+void Motor::Stop() {
+ SetCommand(MOTOR_stop);
+}
+
+
+void Motor::Pause() {
+ SetCommand(MOTOR_pause);
+}
+
+
+void Motor::Restart() {
+ SetCommand(MOTOR_restart);
+}
+
+void Motor::SetZero() {
+ SetCommand(MOTOR_zero);
+}
+
+void Motor::RunInfinite(MotorDir dir) {
+ SetDirection( dir);
+ NumSteps = -1;
+ SetCommand(MOTOR_start);
+}
+
+void Motor::RunSteps(MotorDir dir, uint32_t steps) {
+ SetDirection( dir);
+ NumSteps = steps;
+ SetCommand(MOTOR_start);
+}
+
+void Motor::RunDegrees(MotorDir dir, float degree) {
+ SetDirection( dir);
+ NumSteps = (int)(degree * (float)MotorFullTurn / (float)360.0);
+ SetCommand(MOTOR_start);
+}
+void Motor::SetDirection(MotorDir dir) {
+ direction=dir;
+}
+
+void Motor::SetCommand(MotorCommand cmd) {
+ if(init) {
+ MotorSystemTick.attach_us(callback(this, &Motor::ProcessMotorStateMachine), MotorStepTime);
+ last=tuneTimings.read_us();
+ init=false;
+ }
+ command=cmd;
+}
+
+void Motor::StopMotor() // --- Stop Motor
+{
+ *MPh0 = 0; *MPh1 = 0; *MPh2 = 0; *MPh3 = 0;
+ MotorIndex = 0;
+
+}
+
+
+void Motor::StartMotor()
+{
+ MotorIndex = 0;
+ *MPh0 = 1; *MPh1 = 0; *MPh2 = 0; *MPh3 = 0;
+}
+
+void Motor::RightMotor() // Move the Motor one step Right
+{
+ static const int RPh0[8] = {1, 1, 0, 0, 0, 0, 0, 1};
+ static const int RPh1[8] = {0, 1, 1, 1, 0, 0, 0, 0};
+ static const int RPh2[8] = {0, 0, 0, 1, 1, 1, 0, 0};
+ static const int RPh3[8] = {0, 0, 0, 0, 0, 1, 1, 1};
+ *MPh0 = RPh0[MotorIndex]; *MPh1 = RPh1[MotorIndex]; *MPh2 = RPh2[MotorIndex]; *MPh3 = RPh3[MotorIndex];
+ if (MotorIndex<7) MotorIndex++;
+ else MotorIndex = 0;
+}
+void Motor::LeftMotor() // Move the Motor one step Right
+{
+ static const int LPh0[8] = {1, 1, 0, 0, 0, 0, 0, 1};
+ static const int LPh1[8] = {0, 1, 1, 1, 0, 0, 0, 0};
+ static const int LPh2[8] = {0, 0, 0, 1, 1, 1, 0, 0};
+ static const int LPh3[8] = {0, 0, 0, 0, 0, 1, 1, 1};
+ *MPh0 = LPh0[MotorIndex]; *MPh1 = LPh1[MotorIndex]; *MPh2 = LPh2[MotorIndex]; *MPh3 = LPh3[MotorIndex];
+ if (MotorIndex>0) MotorIndex--;
+ else MotorIndex = 7;
+}
+
+void Motor::RunMotor() // Move the Motor in the user direction
+{
+ if (direction==CLOCKWISE) RightMotor();
+ else LeftMotor();
+}
+
+
+void Motor::ProcessMotorStateMachine()
+{
+
+ if (state==Motor_IDLE) {
+ if (command == MOTOR_start) {
+ // Start the Motor
+ StartMotor();
+ state = Motor_RUN;
+ }
+ else if (command == MOTOR_zero) {
+ // Start zeroing the Motor
+ StartMotor();
+ state = Motor_ZERO;
+ }
+ command = MOTOR_nop;
+ }
+ else if (state==Motor_RUN) {
+ // Action always performed in that state
+ if (NumSteps>0 || NumSteps <0) {
+ RunMotor();
+ NumSteps--;
+ }
+ // Check next state
+ if (command == MOTOR_pause) {
+ state = Motor_PAUSE;
+ }
+ else if ((command == MOTOR_stop)||(NumSteps==0)) {
+ StopMotor();
+ if(state != Motor_IDLE ){//|| itOnStop == true) {
+ _callback.call();
+ }
+ state = Motor_IDLE;
+ }
+ command = MOTOR_nop;
+ }
+ else if (state==Motor_PAUSE) {
+ if (command == MOTOR_stop) {
+ StopMotor();
+ NumSteps=0;
+ state = Motor_IDLE;
+ }
+ else if (command == MOTOR_restart) {
+ state = Motor_RUN;
+ }
+ command = MOTOR_nop;
+ }
+ else if (state==Motor_ZERO) {
+ command = MOTOR_nop;
+ }
+}
+
+MotorStateList Motor::getState() {
+ return state;
+}
+
+void Motor::TestMotor() // Just to check that it make a full taurn back and forth
+{
+ int i;
+ StartMotor();
+ for (i=0; i<MotorFullTurn; i++) {
+ wait(0.005);
+ RightMotor();
+ }
+ wait(0.5);
+ for (i=0; i<MotorFullTurn; i++) {
+ wait(0.005);
+ LeftMotor();
+ }
+ StopMotor();
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/MotorLib/motor.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,102 @@
+// -------------------- Motor ---------------------------
+#ifdef MOTOR_H
+#else
+#define MOTOR_H
+
+#include "mbed.h"
+
+#define MOTOR_STEP_TIME_MIN 700
+#define MOTOR_STEP_TIME_DEFAULT 5000
+#define MOTOR_TICKS_FOR_A_TURN 4096
+
+typedef enum MotorStateList { // Define Motor States for the State Machine
+ Motor_IDLE = 0,
+ Motor_RUN,
+ Motor_PAUSE,
+ Motor_ZERO,
+ Motor_CALIB
+ } MotorState;
+
+typedef enum MotorCommandList { // Define Motor State Machine Commands
+ MOTOR_nop = 0,
+ MOTOR_start,
+ MOTOR_pause,
+ MOTOR_restart,
+ MOTOR_stop,
+ MOTOR_zero
+ } MotorCommand;
+
+typedef enum MotorDirectionList { // Define Motor Clockwise or Anticlockwise
+ CLOCKWISE = 0,
+ COUNTERCLOCKWISE
+ } MotorDir;
+
+class Motor {
+
+ MotorState state;
+ MotorCommand command;
+ MotorDir direction;
+
+
+ public:
+
+
+ Motor(PinName _MPh0, PinName _MPh1, PinName _MPh2, PinName _MPh3, uint32_t TickTime);
+ Motor(PinName _MPh0, PinName _MPh1, PinName _MPh2, PinName _MPh3);
+ void RunSteps(MotorDir direction, uint32_t steps);
+ void RunDegrees(MotorDir direction, float steps);
+ void RunInfinite(MotorDir direction);
+ void SetDirection(MotorDir dir);
+ void TestMotor();
+ void RunMotor();
+ void setMotorCallback(void (*mIT)());
+ void setMotorCallback(void (*mIT)(), bool itOnStop);
+
+template<typename T>
+void setMotorCallback(T *object, void (T::*member)(void))
+{
+ _callback = callback(object,member);
+ itOnStop = true;
+}
+
+ void removeMotorCallback();
+
+ uint32_t getCalibration();
+ void setCalibration(uint32_t nbTicksforFullTurn);
+ void setDelayBtwTicks(uint32_t tickTime); // in ms
+ void setSpeed(float sForOneTurn) ;// nb of s to get rotation of 360° (if 20s, the motor will do 360° in 20 s).
+
+ void Start();
+ void Stop();
+ void Pause();
+ void Restart();
+ void SetZero();
+
+ MotorStateList getState();
+
+ private:
+ void initialization(PinName _MPh0, PinName _MPh1, PinName _MPh2, PinName _MPh3, uint32_t TickTime);
+
+ void StopMotor();
+ void StartMotor();
+ void SetCommand(MotorCommand cmd);
+ void LeftMotor();
+ void RightMotor();
+ void ProcessMotorStateMachine();
+ Timer tuneTimings;
+uint32_t last;
+ DigitalOut *MPh0, *MPh1, *MPh2, *MPh3;
+
+ int MotorIndex; // --- Motor Variable
+
+ bool init;
+ Ticker MotorSystemTick; // System Callback for Motor
+ timestamp_t MotorStepTime; // Time in µs for one motor step
+ uint32_t MotorFullTurn; // Number of step for a complete turn
+ int32_t NumSteps; // Number of Steps = NumWire * MotorFullTurn
+ Callback<void()> _callback;
+
+ bool itOnStop;
+};
+
+#endif
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/VL53L0X.cpp Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,4532 @@
+/**
+ ******************************************************************************
+ * @file VL53L0X_class.cpp
+ * @author IMG
+ * @version V0.0.1
+ * @date 28-June-2016
+ * @brief Implementation file for the VL53L0X driver class
+ ******************************************************************************
+ * @attention
+ *
+ * <h2><center>© COPYRIGHT(c) 2016 STMicroelectronics</center></h2>
+ *
+ * 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 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 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.
+ *
+ ******************************************************************************
+*/
+
+/*
+Simplifications versus the original library:
+
+Replace:
+ * "MicroSeconds" or "micro_seconds" by "us" or "_us"
+ * "MilliSeconds" or "milli_seconds" by "ms" or "_ms"
+ * "MegaCps" or "MCps" or "_mega_cps" by "MHz" or "_MHz"
+ * "MicroMeter" by "um" or "_um"
+ * "FIXEDPNT" by "FP"
+
+Everything related to histogram_mode seems completely not implemented, so all definitions removed.
+
+Everything related to x_talk_compensation seems also not implemented, all removed
+
+Some example regular expressinos used to simplify the code:
+b) Search for: \QRead_Byte(\E([A-Za-z_\d]+)[[:punct:]](\s*)\Q&\E([A-Za-z\d_]+)\Q);\E
+ Replace by: \3 = Read_Byte\(\1\);
+ to replace: Read_Byte(0x90,&module_id);
+ by this: module_id = Read_Byte(0x90);
+
+c) Search for: ([A-Za-z_\d]+)\Q(\E\r\n(\s*)
+ Replace by: \1\(
+ To join lines where the first line has an open bracket, and the next line starts listing the parameters.
+ for example: Status = VL53L0X_UpdateByte(V
+ L53L0X_REG_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV, ....
+ becomes: Status = VL53L0X_UpdateByte(VL53L0X_REG_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV, ....
+
+*/
+
+/* Includes */
+#include <stdlib.h>
+#include "VL53L0X.h"
+
+void Report_Range_Infos(VL53L0X_RangingMeasurementData_t RangeResults, Serial *aSerial )
+{
+ aSerial->printf("\n\r Reporting All Fields of VL53L0X_RangingMeasurementData_t structure \n\r" );
+ aSerial->printf(" .Range_mm = %dmm; Ranged distance. \n\r", RangeResults.Range_mm );
+ aSerial->printf(" .RangeDMax_mm = %dmm; maximum detection distance in current setup and environment conditions \n\r", RangeResults.RangeDMax_mm );
+ aSerial->printf(" .SignalRateRtn_MHz = %3.3fMHz; effectively a measure of target reflectance \n\r", RangeResults.SignalRateRtn_MHz / 65535.01);
+ aSerial->printf(" .AmbientRateRtn_MHz = %3.3fMHz; effectively a measure of the ambient light \n\r", RangeResults.AmbientRateRtn_MHz / 65535.01 );
+ aSerial->printf(" .EffectiveSpadRtnCount = %3.3f; effective SPAD count for the return signal \n\r", RangeResults.EffectiveSpadRtnCount / 256.001 );
+ aSerial->printf(" .RangeFractionalPart = %d; Fractional part of range distance. \n\r", RangeResults.RangeFractionalPart >> 6 );
+ aSerial->printf(" .RangeStatus = %d[u8]; Status for the current measurement, 0 = value is valid \n\r", RangeResults.RangeStatus );
+ aSerial->printf(" .SigmaEstimate = %3.2f; Estimated Sigma - based on ambient & VCSEL rates and signal_total_events \n\r", RangeResults.SigmaEstimate/ 65535.01 );
+};
+
+void Report_Deep_Infos(VL53L0X TOF1, Serial *aSerial)
+{
+ aSerial->printf("\n\r Reporting All Top Level Infos of the class \n\r" );
+ aSerial->printf("I2cDevAddr = %d. \n\r", TOF1.I2cDevAddr );
+ aSerial->printf("comms_type = %d. Type of comms: 1=VL53L0X_COMMS_I2C or VL53L0X_COMMS_SPI \n\r", TOF1.comms_type );
+ aSerial->printf("comms_speed = %d. Communication speed [kHz] : typically 400kHz for I2C \n\r", TOF1.comms_speed_khz );
+
+ aSerial->printf("\n\r Reporting All Infos of the Device_Info structure: \n\r" );
+ aSerial->printf("Device_Info.ProductType = 0x%2X. VL53L0X = 1, VL53L1 = 2 \n\r", TOF1.Device_Info.ProductType );
+ aSerial->printf("Device_Info.ProductRevision = %d.%d. Revision NR, major.minor \n\r",
+ TOF1.Device_Info.ProductRevisionMajor, TOF1.Device_Info.ProductRevisionMinor );
+ aSerial->printf("Device_Info.Name = %s. Name of Device e.g. Left_Distance\n\r", TOF1.Device_Info.Name );
+ aSerial->printf("Device_Info.Type = %s. Type of Device e.g VL53L0X \n\r", TOF1.Device_Info.Type );
+ aSerial->printf("Device_Info.ProductId = %s. Product Identifier String \n\r", TOF1.Device_Info.ProductId );
+
+ aSerial->printf("\n\r Reporting All Fields of CurrentParameters \n\r" );
+ aSerial->printf(" .DeviceMode = %d. Defines type of measurement to be done for the next measurement \n\r",
+ TOF1.CurrentParameters.DeviceMode );
+ aSerial->printf(" .Measure_Time_Budget_us= %dus. Allowed total time for a single measurement \n\r",
+ TOF1.CurrentParameters.MeasurementTimingBudget_us );
+ aSerial->printf(" .Measure_Period_ms = %dms. Time between two consecutive measurements \n\r",
+ TOF1.CurrentParameters.InterMeasurementPeriod_ms );
+ aSerial->printf(" .XTalk_Compens_En = %d. Crosstalk compensation enable or not (0, default) \n\r",
+ TOF1.CurrentParameters.XTalkCompensationEnable );
+ aSerial->printf(" .XTalk_CompRange_mm = %dmm. CrossTalk compensation range, seems never used \n\r",
+ TOF1.CurrentParameters.XTalkCompensationRange_mm );
+ aSerial->printf(" .XTalk_CompRate_MHz = %3.2fMHz. CrossTalk compensation rate . \n\r",
+ (float) TOF1.CurrentParameters.XTalkCompensationRate_MHz / 65536);
+ aSerial->printf(" .RangeOffset_um = %d. Range offset adjustment (um) last programmed.\n\r",
+ TOF1.CurrentParameters.RangeOffset_um );
+ aSerial->printf(" .LimitChecks ... = SIGMA_FINAL, SIGNAL_RATE_FINAL, SIGNAL_REF_CLIP, IGNORE_THRESHOLD, SIGNAL_RATE_MSRC, SIGNAL_RATE_PRE.\n\r");
+ aSerial->printf(" .LimitChecksEnable[x] = %d %d %d %d %d %d. The Limit Checks enabled or not.\n\r",
+ TOF1.CurrentParameters.LimitChecksEnable[0],TOF1.CurrentParameters.LimitChecksEnable[1] ,TOF1.CurrentParameters.LimitChecksEnable[2],
+ TOF1.CurrentParameters.LimitChecksEnable[3],TOF1.CurrentParameters.LimitChecksEnable[4] ,TOF1.CurrentParameters.LimitChecksEnable[5] );
+ aSerial->printf(" .LimitChecksStatus[x] = %d %d %d %d %d %d. Status of checks of last measurement.\n\r",
+ TOF1.CurrentParameters.LimitChecksStatus[0],TOF1.CurrentParameters.LimitChecksStatus[1] ,TOF1.CurrentParameters.LimitChecksStatus[2],
+ TOF1.CurrentParameters.LimitChecksStatus[3],TOF1.CurrentParameters.LimitChecksStatus[4] ,TOF1.CurrentParameters.LimitChecksStatus[5] );
+ aSerial->printf(" .LimitChecksValue[x] = %d %d %d %d %d %d [FP1616]. The Limit Check values \n\r",
+ TOF1.CurrentParameters.LimitChecksValue[0],TOF1.CurrentParameters.LimitChecksValue[1] ,TOF1.CurrentParameters.LimitChecksValue[2],
+ TOF1.CurrentParameters.LimitChecksValue[3],TOF1.CurrentParameters.LimitChecksValue[4] ,TOF1.CurrentParameters.LimitChecksValue[5] );
+ aSerial->printf(" .WrapAroundCheckEnable = %d. Wrap Around Check enabled or not \n\r",
+ TOF1.CurrentParameters.WrapAroundCheckEnable );
+
+ aSerial->printf("\n\r Reporting All Fields of VL53L0X_DevData_t Data structure \n\r" );
+ aSerial->printf(" .OscFrequency_MHz = %3.2fMHz; Frequency used \n\r", (float) TOF1.Data.OscFrequency_MHz/65536 );
+ aSerial->printf(" .LastEncodedTimeout = %d[u16]; Last encoded Time out used for timing budget \n\r", TOF1.Data.LastEncodedTimeout );
+ aSerial->printf(" .Pin0GpioFunctionality = %d[u8]; functionality of the GPIO: pin0 \n\r", TOF1.Data.Pin0GpioFunctionality );
+ aSerial->printf(" .FinalRangeTimeout_us = %d[u32]; Execution time of the final ranging \n\r", TOF1.Data.FinalRangeTimeout_us );
+ aSerial->printf(" .FinalRangeVcselPulsePeriod= %d[u8]; Vcsel pulse period (pll clocks) for the final range measurement \n\r", TOF1.Data.FinalRangeVcselPulsePeriod );
+ aSerial->printf(" .PreRangeTimeout_us = %d[u32]; Execution time of the final range \n\r", TOF1.Data.PreRangeTimeout_us );
+ aSerial->printf(" .PreRangeVcselPulsePeriod = %d[u8]; Vcsel pulse period (pll clocks) for the pre-range measurement \n\r", TOF1.Data.PreRangeVcselPulsePeriod );
+ aSerial->printf(" .ReadDataFromDeviceDone = %2d; reads from device has been done (>0) or not. \n\r", TOF1.Data.ReadDataFromDeviceDone );
+ aSerial->printf(" .ModuleId = %X; Module ID \n\r", TOF1.Data.ModuleId );
+ aSerial->printf(" .Revision = %d[u8]; test Revision \n\r", TOF1.Data.Revision );
+ aSerial->printf(" .ProductId = %s[char*]; Product Identifier String \n\r", TOF1.Data.ProductId );
+ aSerial->printf(" .ReferenceSpadCount = %d[u8]; used for ref spad management \n\r", TOF1.Data.ReferenceSpadCount );
+ aSerial->printf(" .ReferenceSpadType = %d[u8]; used for ref spad management \n\r", TOF1.Data.ReferenceSpadType );
+ aSerial->printf(" .RefSpadsInitialised = %d[u8]; reports if ref spads are initialised. \n\r", TOF1.Data.RefSpadsInitialised );
+ aSerial->printf(" .PartUIDUpper = %d[u32]; Unique Part ID Upper \n\r", TOF1.Data.PartUIDUpper );
+ aSerial->printf(" .PartUIDLower = %d[u32]; Unique Part ID Lower \n\r", TOF1.Data.PartUIDLower );
+ aSerial->printf(" .SignalRateMeasFixed400mm = %3.3f; Peak Signal rate at 400 mm \n\r", 1.0 / 65535.0 * TOF1.Data.SignalRateMeasFixed400mm );
+ aSerial->printf(" .RefSpadEnables[x] = %X %X %X %X %X %X[hex8]; Reference Spad Enables \n\r",
+ TOF1.Data.RefSpadEnables[0], TOF1.Data.RefSpadEnables[1], TOF1.Data.RefSpadEnables[2],
+ TOF1.Data.RefSpadEnables[3], TOF1.Data.RefSpadEnables[4], TOF1.Data.RefSpadEnables[5] );
+ aSerial->printf(" .RefGoodSpadMap[x] = %X %X %X %X %X %X[hex8]; Reference Spad Good Spad Map\n\r",
+ TOF1.Data.RefGoodSpadMap[0], TOF1.Data.RefGoodSpadMap[1], TOF1.Data.RefGoodSpadMap[2],
+ TOF1.Data.RefGoodSpadMap[3], TOF1.Data.RefGoodSpadMap[4], TOF1.Data.RefGoodSpadMap[5] );
+ aSerial->printf(" .Part2PartOffsetNVM_um = %d[i32]; backed up NVM value \n\r", TOF1.Data.Part2PartOffsetNVM_um );
+ aSerial->printf(" .Part2PartOffsetAdjustNVM_um= %d[i32]; backed up NVM value of additional offset adjustment \n\r", TOF1.Data.Part2PartOffsetAdjustNVM_um );
+ aSerial->printf(" .SequenceConfig = %d[u8]; Internal value for the sequence config \n\r", TOF1.Data.SequenceConfig );
+ aSerial->printf(" .RangeFractionalEnable = %d[u8]; Enable/Disable fractional part of range data \n\r", TOF1.Data.RangeFractionalEnable);
+ aSerial->printf(" .PalState = %d[u8]; Current state of the PAL \n\r", TOF1.Data.PalState );
+ aSerial->printf(" .PowerMode = %d[u8]; Current Power Mode; Stdby1/2, Idle1/2 \n\r", TOF1.Data.PowerMode );
+ aSerial->printf(" .SigmaEstRefArray = %d[u16]; Reference array sigma value in 1/100th of [mm] \n\r", TOF1.Data.SigmaEstRefArray );
+ aSerial->printf(" .SigmaEstEffPulseWidth = %d[u16]; Effective Pulse width for sigma estimate in 1/100th of ns \n\r", TOF1.Data.SigmaEstEffPulseWidth );
+ aSerial->printf(" .SigmaEstEffAmbWidth = %d. Effective Ambient width for sigma estimate in 1/100th of ns \n\r", TOF1.Data.SigmaEstEffAmbWidth );
+ aSerial->printf(" .StopVariable = %d[u8]; StopVariable used during the stop sequence \n\r", TOF1.Data.StopVariable );
+ aSerial->printf(" .targetRefRate = %d. Target Ambient Rate for Ref spad management \n\r", TOF1.Data.targetRefRate );
+ aSerial->printf(" .LastSignalRef_MHz = %3.3fMHz; Latest Signal ref \n\r", TOF1.Data.LastSignalRef_MHz / 65535.01 );
+ aSerial->printf(" .UseInternalTuningSetting = %d[u8]; Indicate if we use Tuning Settings table \n\r", TOF1.Data.UseInternalTuningSettings );
+ aSerial->printf(" .LinearityCorrectiveGain = %d[u8]; Linearity Corrective Gain value in x1000 \n\r", TOF1.Data.LinearityCorrectiveGain );
+ aSerial->printf(" .DmaxCalRange_mm = %dmm; Dmax Calibration Range \n\r", TOF1.Data.DmaxCalRange_mm );
+ aSerial->printf(" .DmaxCalSignalRateRtn_MHz = %3.3fMHz; Dmax Calibration Signal Rate Return \n\r", TOF1.Data.DmaxCalSignalRateRtn_MHz / 65535.01 );
+}
+
+int VL53L0X::read_id(uint8_t *id)
+{ int status = 0;
+ uint16_t rl_id = 0;
+
+ status = VL53L0X_read_word(VL53L0X_REG_IDENTIFICATION_MODEL_ID, &rl_id);
+ if (rl_id == 0xEEAA) {
+ return status;
+ }
+ return -1;
+}
+
+int VL53L0X::init_sensor(uint8_t new_addr)
+{ int status;
+
+ VL53L0X_off();
+ VL53L0X_on();
+
+ // Verify if the device is actually present
+ uint8_t id = 0;
+ status = read_id(&id);
+ if (status != 0) {
+ //aSerial->printf("VL53L0X sensor is not present!\n\r");
+ return 99; } // device is not present
+
+ status = VL53L0X_data_init();
+ if (status != VL53L0X_ERROR_NONE) {
+ //aSerial->printf("Failed to init VL53L0X sensor!\n\r");
+ return status;
+ }
+
+ // deduce silicon version
+ status = VL53L0X_get_device_info();
+
+ status = prepare();
+ if (status != VL53L0X_ERROR_NONE) {
+ //aSerial->printf("Failed to prepare VL53L0X!\n\r");
+ return status;
+ }
+
+ if (new_addr != VL53L0X_DEFAULT_ADDRESS) {
+ status = set_device_address(new_addr);
+ if (status) {
+ //aSerial->printf("Failed to change I2C address!\n\r");
+ return status;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_data_init(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ VL53L0X_DeviceParameters_t CurrentParameters;
+ int i;
+ uint8_t StopVariable;
+
+ /* by default the I2C is running at 1V8 if you want to change it you
+ * need to include this define at compilation level. */
+#ifdef USE_I2C_2V8
+ Status = VL53L0X_UpdateByte(VL53L0X_REG_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV,0xFE,0x01);
+#endif
+
+ /* Set I2C standard mode */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0x88, 0x00); }
+
+ Data.ReadDataFromDeviceDone = 0;
+ Data.ReadDataFromDeviceDone = 0;
+
+#ifdef USE_IQC_STATION
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_apply_offset_adjustment();
+ }
+#endif
+
+ /* Default value is 1000 for Linearity Corrective Gain */
+ Data.LinearityCorrectiveGain = 1000;
+
+ /* Dmax default Parameter */
+ Data.DmaxCalRange_mm = 400;
+ Data.DmaxCalSignalRateRtn_MHz = (FixPoint1616_t)((0x00016B85)); /* 1.42 No Cover Glass*/
+
+ /* Set Default static parameters
+ *set first temporary values 9.44_MHz * 65536 = 618660 */
+ Data.OscFrequency_MHz = 618660;
+
+ /* Set Default XTalkCompensationRate_MHz to 0 */
+ CurrentParameters.XTalkCompensationRate_MHz = 0;
+
+ /* Get default parameters */
+ status = VL53L0X_get_device_parameters( &CurrentParameters);
+ if (status == VL53L0X_ERROR_NONE) {
+ /* initialize PAL values */
+ CurrentParameters.DeviceMode = VL53L0X_DEVICEMODE_SINGLE_RANGING;
+ CurrentParameters = CurrentParameters;
+ }
+
+ /* Sigma estimator variable */
+ Data.SigmaEstRefArray = 100;
+ Data.SigmaEstEffPulseWidth = 900;
+ Data.SigmaEstEffAmbWidth = 500;
+ Data.targetRefRate = 0x0A00; /* 20 MHz in 9:7 format */
+
+ /* Use internal default settings */
+ Data.UseInternalTuningSettings = 1;
+
+ status |= VL53L0X_write_byte( 0x80, 0x01);
+ status |= VL53L0X_write_byte( 0xFF, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x00);
+ status |= VL53L0X_read_byte( 0x91, &StopVariable);
+ Data.StopVariable = StopVariable;
+ status |= VL53L0X_write_byte( 0x00, 0x01);
+ status |= VL53L0X_write_byte( 0xFF, 0x00);
+ status |= VL53L0X_write_byte( 0x80, 0x00);
+
+ /* Enable all check */
+ for (i = 0; i < VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS; i++) {
+ if (status == VL53L0X_ERROR_NONE) {
+ status |= VL53L0X_set_limit_check_enable( i, 1);
+ } else { break; }
+ }
+
+ /* Disable the following checks */
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_set_limit_check_enable(VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP, 0);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_set_limit_check_enable(VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD, 0);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_set_limit_check_enable(VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC, 0);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_set_limit_check_enable(VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE, 0);
+
+ /* Limit default values */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_limit_check_value(VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE,
+ (FixPoint1616_t)(18 * 65536));
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_limit_check_value(VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE,
+ (FixPoint1616_t)(25 * 65536 / 100)); /* 0.25 * 65536 */
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_limit_check_value(VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP,
+ (FixPoint1616_t)(35 * 65536));
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_limit_check_value(VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD,
+ (FixPoint1616_t)(0 * 65536));
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = 0xFF;
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG,0xFF);
+
+ /* Set PAL state to tell that we are waiting for call to VL53L0X_StaticInit */
+ Data.PalState = VL53L0X_STATE_WAIT_STATICINIT;
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.RefSpadsInitialised = 0;
+ }
+
+ return status;
+}
+
+int VL53L0X::prepare()
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint32_t ref_spad_count;
+ uint8_t is_aperture_spads;
+ uint8_t vhv_settings;
+ uint8_t phase_cal;
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_static_init(); // Device Initialization
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_ref_calibration(&vhv_settings, &phase_cal); // Device Initialization
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_ref_spad_management(&ref_spad_count, &is_aperture_spads); // Device Initialization
+ }
+
+ return status;
+}
+
+int VL53L0X::start_measurement(OperatingMode operating_mode, void (*fptr)(void),
+ VL53L0X_RangingConfig rangingConfig)
+{ int Status = VL53L0X_ERROR_NONE;
+ int ClrStatus;
+
+ uint8_t VhvSettings;
+ uint8_t PhaseCal;
+ // default settings, for normal range.
+ FixPoint1616_t signalLimit = (FixPoint1616_t)(0.25 * 65536);
+ FixPoint1616_t sigmaLimit = (FixPoint1616_t)(25 * 65536);
+ uint32_t timingBudget = 33000;
+ uint8_t preRangeVcselPeriod = 14;
+ uint8_t finalRangeVcselPeriod = 10;
+
+ if (operating_mode == range_continuous_interrupt) {
+ if (_gpio1Int == NULL) {
+ //aSerial->printf("GPIO1 Error\r\n");
+ return 1;
+ }
+
+ Status = VL53L0X_stop_measurement(); // it is safer to do this while sensor is stopped
+
+// Status = VL53L0X_SetInterruptThresholds(Device, VL53L0X_DEVICEMODE_CONTINUOUS_RANGING, 0, 300);
+
+ Status = VL53L0X_set_gpio_config(0, VL53L0X_DEVICEMODE_CONTINUOUS_RANGING,
+ VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY,
+ VL53L0X_INTERRUPTPOLARITY_HIGH);
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ attach_interrupt_measure_detection_irq(fptr);
+ enable_interrupt_measure_detection_irq();
+ }
+
+ ClrStatus = clear_interrupt(VL53L0X_REG_RESULT_INTERRUPT_STATUS | VL53L0X_REG_RESULT_RANGE_STATUS);
+ if (ClrStatus) { Status = 97; } // VL53L0X_ClearErrorInterrupt fail
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ CurrentParameters.DeviceMode = VL53L0X_DEVICEMODE_CONTINUOUS_RANGING; // Setup in continuous ranging mode
+ Status = VL53L0X_start_measurement();
+ }
+ }
+
+ if (operating_mode == range_single_shot_polling) {
+ // singelshot, polled ranging
+ if (Status == VL53L0X_ERROR_NONE) {
+ // no need to do this when we use VL53L0X_PerformSingleRangingMeasurement
+ CurrentParameters.DeviceMode = VL53L0X_DEVICEMODE_SINGLE_RANGING; // Setup in single ranging mode
+ // Enable/Disable Sigma and Signal check
+ Status = VL53L0X_set_limit_check_enable(VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, 1);
+ }
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_set_limit_check_enable(VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, 1);
+ }
+
+ /* Preselected Ranging configurations */
+ switch(rangingConfig) {
+ case Range_Config_DEFAULT:
+ // default settings, for normal range.
+ signalLimit = (FixPoint1616_t)(0.25 * 65536);
+ sigmaLimit = (FixPoint1616_t)(16 * 65536);
+ timingBudget = 33000;
+ preRangeVcselPeriod = 14;
+ finalRangeVcselPeriod = 10;
+ break;
+ case Range_Config_LONG_RANGE: // *** from mass market cube expansion v1.1, ranging with satellites.
+ signalLimit = (FixPoint1616_t)(0.1 * 65536);
+ sigmaLimit = (FixPoint1616_t)(60 * 65536);
+ timingBudget = 33000;
+ preRangeVcselPeriod = 18;
+ finalRangeVcselPeriod = 14;
+ break;
+ case Range_Config_HIGH_ACCURACY:
+ signalLimit = (FixPoint1616_t)(0.25*65536);
+ sigmaLimit = (FixPoint1616_t)(18*65536);
+ timingBudget = 200000;
+ preRangeVcselPeriod = 14;
+ finalRangeVcselPeriod = 10;
+ break;
+ case Range_Config_HIGH_SPEED:
+ signalLimit = (FixPoint1616_t)(0.25*65536);
+ sigmaLimit = (FixPoint1616_t)(60*65536);
+ timingBudget = 20000;
+ preRangeVcselPeriod = 14;
+ finalRangeVcselPeriod = 10;
+ break;
+ default:
+ Status = 96; // Config Not Supported
+ }
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_set_limit_check_value(VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE, signalLimit);}
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_set_limit_check_value(VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE, sigmaLimit);}
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_set_measurement_timing_budget_us( timingBudget);}
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_set_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE, preRangeVcselPeriod);}
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_set_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_FINAL_RANGE, finalRangeVcselPeriod);}
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_perform_ref_calibration( &VhvSettings, &PhaseCal);}
+
+ }
+
+ if (operating_mode == range_continuous_polling) {
+ if (Status == VL53L0X_ERROR_NONE) {
+ CurrentParameters.DeviceMode = VL53L0X_DEVICEMODE_CONTINUOUS_RANGING; // Setup in continuous ranging mode
+ Status = VL53L0X_start_measurement();
+ }
+ }
+ return Status;
+}
+
+int VL53L0X::range_meas_int_continuous_mode(void (*fptr)(void))
+{ int status, clr_status;
+
+ status = VL53L0X_stop_measurement(); // it is safer to do this while sensor is stopped
+
+// status = VL53L0X_SetInterruptThresholds(Device, VL53L0X_DEVICEMODE_CONTINUOUS_RANGING, 0, 300);
+
+ status = VL53L0X_set_gpio_config( 0, VL53L0X_DEVICEMODE_CONTINUOUS_RANGING,
+ VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY, VL53L0X_INTERRUPTPOLARITY_HIGH);
+
+ if (!status) {
+ attach_interrupt_measure_detection_irq(fptr);
+ enable_interrupt_measure_detection_irq();
+ }
+
+ clr_status = clear_interrupt(VL53L0X_REG_RESULT_INTERRUPT_STATUS | VL53L0X_REG_RESULT_RANGE_STATUS);
+ if (clr_status!=0) { status = 98; } // VL53L0X_ClearErrorInterrupt_fail;
+
+ if (!status) {
+ status = range_start_continuous_mode();
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::wait_measurement_data_ready(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t new_dat_ready = 0;
+ uint32_t loop_nb;
+
+ // Wait until it finished
+ // use timeout to avoid deadlock
+ if (status == VL53L0X_ERROR_NONE) {
+ loop_nb = 0;
+ do {
+ status = VL53L0X_get_measurement_data_ready( &new_dat_ready);
+ if ((new_dat_ready == 0x01) || status != VL53L0X_ERROR_NONE) {
+ break;
+ }
+ loop_nb = loop_nb + 1;
+ VL53L0X_polling_delay();
+ } while (loop_nb < VL53L0X_DEFAULT_MAX_LOOP);
+
+ if (loop_nb >= VL53L0X_DEFAULT_MAX_LOOP) {
+ status = VL53L0X_ERROR_TIME_OUT;
+ }
+ }
+
+ return status;
+}
+
+int VL53L0X::get_distance(uint32_t *p_data)
+{
+ int status = 0;
+ VL53L0X_RangingMeasurementData_t p_ranging_measurement_data;
+
+ status = start_measurement(range_single_shot_polling, NULL, Range_Config_DEFAULT);
+ if (!status) {
+ status = get_measurement(range_single_shot_polling, &p_ranging_measurement_data);
+ }
+ if (p_ranging_measurement_data.RangeStatus == 0) { // we have a valid range.
+ *p_data = p_ranging_measurement_data.Range_mm;
+ } else {
+ *p_data = 0;
+ status = VL53L0X_ERROR_RANGE_ERROR;
+ }
+ stop_measurement(range_single_shot_polling);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::wait_stop_completed(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint32_t stop_completed = 0;
+ uint32_t loop_nb;
+
+ // Wait until it finished
+ // use timeout to avoid deadlock
+ if (status == VL53L0X_ERROR_NONE) {
+ loop_nb = 0;
+ do {
+ status = VL53L0X_get_stop_completed_status( &stop_completed);
+ if ((stop_completed == 0x00) || status != VL53L0X_ERROR_NONE) {
+ break;
+ }
+ loop_nb = loop_nb + 1;
+ VL53L0X_polling_delay();
+ } while (loop_nb < VL53L0X_DEFAULT_MAX_LOOP);
+
+ if (loop_nb >= VL53L0X_DEFAULT_MAX_LOOP) {
+ status = VL53L0X_ERROR_TIME_OUT;
+ }
+ }
+
+ return status;
+}
+
+int VL53L0X::get_measurement(OperatingMode operating_mode, VL53L0X_RangingMeasurementData_t *p_data)
+{ int Status = VL53L0X_ERROR_NONE;
+
+ if (operating_mode == range_single_shot_polling) {
+ Status = VL53L0X_perform_single_ranging_measurement( p_data);
+ }
+
+ if (operating_mode == range_continuous_polling) {
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_measurement_poll_for_completion();
+ }
+
+ if (Status == VL53L0X_ERROR_NONE) {
+ Status = VL53L0X_get_ranging_measurement_data( p_data);
+
+ // Clear the interrupt
+ VL53L0X_clear_interrupt_mask( VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY);
+ VL53L0X_polling_delay();
+ }
+ }
+
+ if (operating_mode == range_continuous_interrupt) {
+ Status = VL53L0X_get_ranging_measurement_data( p_data);
+ VL53L0X_clear_interrupt_mask( VL53L0X_REG_SYSTEM_INTERRUPT_CLEAR | VL53L0X_REG_RESULT_INTERRUPT_STATUS);
+ }
+
+ return Status;
+}
+
+int VL53L0X::stop_measurement(OperatingMode operating_mode)
+{ int status = VL53L0X_ERROR_NONE;
+
+ // don't need to stop for a singleshot range!
+ if (operating_mode == range_single_shot_polling) {
+ }
+
+ if (operating_mode == range_continuous_interrupt || operating_mode == range_continuous_polling) {
+ // continuous mode
+ if (status == VL53L0X_ERROR_NONE) {
+ //aSerial->printf("Call of VL53L0X_StopMeasurement\n");
+ status = VL53L0X_stop_measurement();
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ //aSerial->printf("Wait Stop to be competed\n");
+ status = wait_stop_completed();
+ }
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_clear_interrupt_mask(VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY);
+ }
+
+ return status;
+}
+
+int VL53L0X::handle_irq(OperatingMode operating_mode, VL53L0X_RangingMeasurementData_t *data)
+{ int status;
+ status = get_measurement(operating_mode, data);
+ enable_interrupt_measure_detection_irq();
+ return status;
+}
+
+int VL53L0X::range_start_continuous_mode()
+{ CurrentParameters.DeviceMode = VL53L0X_DEVICEMODE_CONTINUOUS_RANGING;
+
+ return VL53L0X_start_measurement();
+
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_device_read_strobe(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t strobe;
+ uint32_t loop_nb;
+
+ status |= VL53L0X_write_byte( 0x83, 0x00);
+
+ /* polling
+ * use timeout to avoid deadlock*/
+ if (status == VL53L0X_ERROR_NONE) {
+ loop_nb = 0;
+ do {
+ status = VL53L0X_read_byte( 0x83, &strobe);
+ if ((strobe != 0x00) || status != VL53L0X_ERROR_NONE) {
+ break;
+ }
+
+ loop_nb = loop_nb + 1;
+ } while (loop_nb < VL53L0X_DEFAULT_MAX_LOOP);
+
+ if (loop_nb >= VL53L0X_DEFAULT_MAX_LOOP) {
+ status = VL53L0X_ERROR_TIME_OUT;
+ }
+ }
+
+ status |= VL53L0X_write_byte( 0x83, 0x01);
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_info_from_device( uint8_t option)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t byte;
+ uint32_t tmp_dword;
+ uint8_t module_id;
+ uint8_t revision;
+ uint8_t reference_spad_count = 0;
+ uint8_t reference_spad_type = 0;
+ uint32_t part_uid_upper = 0;
+ uint32_t part_uid_lower = 0;
+ uint32_t offset_fixed1104_mm = 0;
+ int16_t offset_micro_meters = 0;
+ uint32_t dist_meas_tgt_fixed1104_mm = 400 << 4;
+ uint32_t dist_meas_fixed1104_400_mm = 0;
+ uint32_t signal_rate_meas_fixed1104_400_mm = 0;
+ char product_id[19];
+ char *product_id_tmp;
+ uint8_t read_data_from_device_done;
+ FixPoint1616_t signal_rate_meas_fixed400_mm_fix = 0;
+ uint8_t nvm_ref_good_spad_map[VL53L0X_REF_SPAD_BUFFER_SIZE];
+ int i;
+
+ read_data_from_device_done = Data.ReadDataFromDeviceDone;
+ read_data_from_device_done = Data.ReadDataFromDeviceDone;
+ read_data_from_device_done = Data.ReadDataFromDeviceDone;
+
+ /* This access is done only once after that a GetDeviceInfo or
+ * datainit is done*/
+ if (read_data_from_device_done != 7) {
+
+ status |= VL53L0X_write_byte( 0x80, 0x01);
+ status |= VL53L0X_write_byte( 0xFF, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x00);
+ status |= VL53L0X_write_byte( 0xFF, 0x06);
+ status |= VL53L0X_read_byte ( 0x83, &byte);
+ status |= VL53L0X_write_byte( 0x83, byte | 4);
+ status |= VL53L0X_write_byte( 0xFF, 0x07);
+ status |= VL53L0X_write_byte( 0x81, 0x01);
+
+ status |= VL53L0X_polling_delay();
+
+ status |= VL53L0X_write_byte( 0x80, 0x01);
+
+ if (((option & 1) == 1) &&
+ ((read_data_from_device_done & 1) == 0)) {
+ status |= VL53L0X_write_byte( 0x94, 0x6b);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ reference_spad_count = (uint8_t)((tmp_dword >> 8) & 0x07f);
+ reference_spad_type = (uint8_t)((tmp_dword >> 15) & 0x01);
+
+ status |= VL53L0X_write_byte( 0x94, 0x24);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ nvm_ref_good_spad_map[0] = (uint8_t)((tmp_dword >> 24) & 0xff);
+ nvm_ref_good_spad_map[1] = (uint8_t)((tmp_dword >> 16) & 0xff);
+ nvm_ref_good_spad_map[2] = (uint8_t)((tmp_dword >> 8) & 0xff);
+ nvm_ref_good_spad_map[3] = (uint8_t)(tmp_dword & 0xff);
+
+ status |= VL53L0X_write_byte( 0x94, 0x25);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ nvm_ref_good_spad_map[4] = (uint8_t)((tmp_dword >> 24) & 0xff);
+ nvm_ref_good_spad_map[5] = (uint8_t)((tmp_dword >> 16) & 0xff);
+ }
+
+ if (((option & 2) == 2) &&
+ ((read_data_from_device_done & 2) == 0)) {
+
+ status |= VL53L0X_write_byte( 0x94, 0x02);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_byte( 0x90, &module_id);
+
+ status |= VL53L0X_write_byte( 0x94, 0x7B);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_byte( 0x90, &revision);
+
+ status |= VL53L0X_write_byte( 0x94, 0x77);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ product_id[0] = (char)((tmp_dword >> 25) & 0x07f);
+ product_id[1] = (char)((tmp_dword >> 18) & 0x07f);
+ product_id[2] = (char)((tmp_dword >> 11) & 0x07f);
+ product_id[3] = (char)((tmp_dword >> 4) & 0x07f);
+
+ byte = (uint8_t)((tmp_dword & 0x00f) << 3);
+
+ status |= VL53L0X_write_byte( 0x94, 0x78);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ product_id[4] = (char)(byte +
+ ((tmp_dword >> 29) & 0x07f));
+ product_id[5] = (char)((tmp_dword >> 22) & 0x07f);
+ product_id[6] = (char)((tmp_dword >> 15) & 0x07f);
+ product_id[7] = (char)((tmp_dword >> 8) & 0x07f);
+ product_id[8] = (char)((tmp_dword >> 1) & 0x07f);
+
+ byte = (uint8_t)((tmp_dword & 0x001) << 6);
+
+ status |= VL53L0X_write_byte( 0x94, 0x79);
+
+ status |= VL53L0X_device_read_strobe();
+
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ product_id[9] = (char)(byte +
+ ((tmp_dword >> 26) & 0x07f));
+ product_id[10] = (char)((tmp_dword >> 19) & 0x07f);
+ product_id[11] = (char)((tmp_dword >> 12) & 0x07f);
+ product_id[12] = (char)((tmp_dword >> 5) & 0x07f);
+
+ byte = (uint8_t)((tmp_dword & 0x01f) << 2);
+
+ status |= VL53L0X_write_byte( 0x94, 0x7A);
+
+ status |= VL53L0X_device_read_strobe();
+
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+
+ product_id[13] = (char)(byte +
+ ((tmp_dword >> 30) & 0x07f));
+ product_id[14] = (char)((tmp_dword >> 23) & 0x07f);
+ product_id[15] = (char)((tmp_dword >> 16) & 0x07f);
+ product_id[16] = (char)((tmp_dword >> 9) & 0x07f);
+ product_id[17] = (char)((tmp_dword >> 2) & 0x07f);
+ product_id[18] = '\0';
+
+ }
+
+ if (((option & 4) == 4) &&
+ ((read_data_from_device_done & 4) == 0)) {
+
+ status |= VL53L0X_write_byte( 0x94, 0x7B);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &part_uid_upper);
+ status |= VL53L0X_write_byte( 0x94, 0x7C);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &part_uid_lower);
+
+ status |= VL53L0X_write_byte( 0x94, 0x73);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+ signal_rate_meas_fixed1104_400_mm = (tmp_dword & 0x0000000ff) << 8;
+
+ status |= VL53L0X_write_byte( 0x94, 0x74);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+ signal_rate_meas_fixed1104_400_mm |= ((tmp_dword & 0xff000000) >> 24);
+
+ status |= VL53L0X_write_byte( 0x94, 0x75);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+ dist_meas_fixed1104_400_mm = (tmp_dword & 0x0000000ff) << 8;
+
+ status |= VL53L0X_write_byte( 0x94, 0x76);
+ status |= VL53L0X_device_read_strobe();
+ status |= VL53L0X_read_dword( 0x90, &tmp_dword);
+ dist_meas_fixed1104_400_mm |= ((tmp_dword & 0xff000000) >> 24);
+ }
+
+ status |= VL53L0X_write_byte( 0x81, 0x00);
+ status |= VL53L0X_write_byte( 0xFF, 0x06);
+ status |= VL53L0X_read_byte( 0x83, &byte);
+ status |= VL53L0X_write_byte( 0x83, byte & 0xfb);
+ status |= VL53L0X_write_byte( 0xFF, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x01);
+ status |= VL53L0X_write_byte( 0xFF, 0x00);
+ status |= VL53L0X_write_byte( 0x80, 0x00);
+ }
+
+ if ((status == VL53L0X_ERROR_NONE) &&
+ (read_data_from_device_done != 7)) {
+ /* Assign to variable if status is ok */
+ if (((option & 1) == 1) &&
+ ((read_data_from_device_done & 1) == 0)) {
+ Data.ReferenceSpadCount = reference_spad_count;
+ Data.ReferenceSpadType = reference_spad_type;
+
+ for (i = 0; i < VL53L0X_REF_SPAD_BUFFER_SIZE; i++) {
+ Data.RefGoodSpadMap[i] =
+ nvm_ref_good_spad_map[i];
+ }
+ }
+
+ if (((option & 2) == 2) &&
+ ((read_data_from_device_done & 2) == 0)) {
+ Data.ModuleId = module_id;
+ Data.Revision = revision;
+ product_id_tmp = Data.ProductId;
+ VL53L0X_COPYSTRING(product_id_tmp, product_id);
+ }
+
+ if (((option & 4) == 4) &&
+ ((read_data_from_device_done & 4) == 0)) {
+ Data.PartUIDUpper = part_uid_upper;
+ Data.PartUIDLower = part_uid_lower;
+ signal_rate_meas_fixed400_mm_fix =
+ VL53L0X_FP97TOFP1616(signal_rate_meas_fixed1104_400_mm);
+ Data.SignalRateMeasFixed400mm = signal_rate_meas_fixed400_mm_fix;
+
+ offset_micro_meters = 0;
+ if (dist_meas_fixed1104_400_mm != 0) {
+ offset_fixed1104_mm =
+ dist_meas_fixed1104_400_mm -
+ dist_meas_tgt_fixed1104_mm;
+ offset_micro_meters = (offset_fixed1104_mm
+ * 1000) >> 4;
+ offset_micro_meters *= -1;
+ }
+
+ Data.Part2PartOffsetAdjustNVM_um = offset_micro_meters;
+ }
+ byte = (uint8_t)(read_data_from_device_done | option);
+ Data.ReadDataFromDeviceDone = byte;
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_offset_calibration_data_micro_meter(int32_t *p_offset_calibration_data_micro_meter)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint16_t range_offset_register;
+ int16_t c_max_offset = 2047;
+ int16_t c_offset_range = 4096;
+
+ /* Note, that offset has 10.2 format */
+ status = VL53L0X_read_word(VL53L0X_REG_ALGO_PART_TO_PART_RANGE_OFFSET_MM,
+ &range_offset_register);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ range_offset_register = (range_offset_register & 0x0fff);
+
+ /* Apply 12 bit 2's compliment conversion */
+ if (range_offset_register > c_max_offset) {
+ *p_offset_calibration_data_micro_meter =
+ (int16_t)(range_offset_register - c_offset_range) * 250;
+ } else {
+ *p_offset_calibration_data_micro_meter =
+ (int16_t)range_offset_register * 250; }
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_offset_calibration_data_micro_meter(int32_t offset_calibration_data_micro_meter)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ int32_t c_max_offset_micro_meter = 511000;
+ int32_t c_min_offset_micro_meter = -512000;
+ int16_t c_offset_range = 4096;
+ uint32_t encoded_offset_val;
+
+ if (offset_calibration_data_micro_meter > c_max_offset_micro_meter) {
+ offset_calibration_data_micro_meter = c_max_offset_micro_meter;
+ } else {
+ if (offset_calibration_data_micro_meter < c_min_offset_micro_meter) {
+ offset_calibration_data_micro_meter = c_min_offset_micro_meter;
+ }
+ }
+
+ /* The offset register is 10.2 format and units are mm
+ * therefore conversion is applied by a division of 250. */
+ if (offset_calibration_data_micro_meter >= 0) {
+ encoded_offset_val = offset_calibration_data_micro_meter / 250;
+ } else {
+ encoded_offset_val =
+ c_offset_range + offset_calibration_data_micro_meter / 250;
+ }
+
+ status = VL53L0X_write_word(VL53L0X_REG_ALGO_PART_TO_PART_RANGE_OFFSET_MM,
+ encoded_offset_val);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_apply_offset_adjustment(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ int32_t corrected_offset_micro_meters;
+ int32_t current_offset_micro_meters;
+
+ /* if we run on this function we can read all the NVM info used by the API */
+ status = VL53L0X_get_info_from_device( 7);
+
+ /* Read back current device offset */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_offset_calibration_data_micro_meter(¤t_offset_micro_meters);
+ }
+
+ /* Apply Offset Adjustment derived from 400mm measurements */
+ if (status == VL53L0X_ERROR_NONE) {
+
+ /* Store initial device offset */
+ Data.Part2PartOffsetNVM_um = current_offset_micro_meters;
+
+ corrected_offset_micro_meters = current_offset_micro_meters +
+ (int32_t)Data.Part2PartOffsetAdjustNVM_um;
+
+ status = VL53L0X_set_offset_calibration_data_micro_meter(corrected_offset_micro_meters);
+
+ /* store current, adjusted offset */
+ if (status == VL53L0X_ERROR_NONE) {
+ CurrentParameters.RangeOffset_um = corrected_offset_micro_meters;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_inter_measurement_period_ms(uint32_t *p_inter_measurement_period_ms)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint16_t osc_calibrate_val;
+ uint32_t im_period_ms;
+
+
+
+ status = VL53L0X_read_word( VL53L0X_REG_OSC_CALIBRATE_VAL,
+ &osc_calibrate_val);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_dword(VL53L0X_REG_SYSTEM_INTERMEASUREMENT_PERIOD,
+ &im_period_ms);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (osc_calibrate_val != 0) {
+ *p_inter_measurement_period_ms =
+ im_period_ms / osc_calibrate_val;
+ }
+ CurrentParameters.InterMeasurementPeriod_ms = *p_inter_measurement_period_ms;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_x_talk_compensation_rate_MHz(FixPoint1616_t *p_xtalk_compensation_rate_MHz)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint16_t value;
+ FixPoint1616_t temp_fix1616;
+
+ status = VL53L0X_read_word(VL53L0X_REG_CROSSTALK_COMPENSATION_PEAK_RATE_MHz, (uint16_t *)&value);
+ if (status == VL53L0X_ERROR_NONE) {
+ if (value == 0) {
+ /* the Xtalk is disabled return value from memory */
+ temp_fix1616 = CurrentParameters.XTalkCompensationRate_MHz ;
+ *p_xtalk_compensation_rate_MHz = temp_fix1616;
+ CurrentParameters.XTalkCompensationEnable = 0;
+ } else {
+ temp_fix1616 = VL53L0X_FP313TOFP1616(value);
+ *p_xtalk_compensation_rate_MHz = temp_fix1616;
+ CurrentParameters.XTalkCompensationRate_MHz = temp_fix1616;
+ CurrentParameters.XTalkCompensationEnable = 1;
+ }
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_limit_check_value( uint16_t limit_check_id,
+ FixPoint1616_t *p_limit_check_value)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t enable_zero_value = 0;
+ uint16_t temp16;
+ FixPoint1616_t temp_fix1616;
+
+ switch (limit_check_id) {
+
+ case VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE:
+ /* internal computation: */
+ temp_fix1616 = CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE];
+ enable_zero_value = 0;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
+ status = VL53L0X_read_word(VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT, &temp16);
+ if (status == VL53L0X_ERROR_NONE) {
+ temp_fix1616 = VL53L0X_FP97TOFP1616(temp16);
+ }
+ enable_zero_value = 1;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP:
+ /* internal computation: */
+ temp_fix1616 = CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP];
+ enable_zero_value = 0;
+ break;
+
+ case VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD:
+ /* internal computation: */
+ temp_fix1616 = CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD];
+ enable_zero_value = 0;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC:
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE:
+ status = VL53L0X_read_word(VL53L0X_REG_PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT,
+ &temp16);
+ if (status == VL53L0X_ERROR_NONE) {
+ temp_fix1616 = VL53L0X_FP97TOFP1616(temp16);
+ }
+
+ enable_zero_value = 0;
+ break;
+
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (enable_zero_value == 1) {
+
+ if (temp_fix1616 == 0) {
+ /* disabled: return value from memory */
+ temp_fix1616 = CurrentParameters.LimitChecksValue[limit_check_id];
+ *p_limit_check_value = temp_fix1616;
+ CurrentParameters.LimitChecksEnable[limit_check_id] = 0;
+ } else {
+ *p_limit_check_value = temp_fix1616;
+ CurrentParameters.LimitChecksValue[limit_check_id] = temp_fix1616;
+ CurrentParameters.LimitChecksEnable[limit_check_id] = 1;
+ }
+ } else { *p_limit_check_value = temp_fix1616; }
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_limit_check_enable( uint16_t limit_check_id,
+ uint8_t *p_limit_check_enable)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t temp8;
+
+ if (limit_check_id >= VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS) {
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ *p_limit_check_enable = 0;
+ } else {
+ temp8 = CurrentParameters.LimitChecksEnable[limit_check_id];
+ *p_limit_check_enable = temp8;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_wrap_around_check_enable(uint8_t *p_wrap_around_check_enable)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t data;
+
+ status = VL53L0X_read_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, &data);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = data;
+ if (data & (0x01 << 7)) {
+ *p_wrap_around_check_enable = 0x01;
+ } else {
+ *p_wrap_around_check_enable = 0x00;
+ }
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ CurrentParameters.WrapAroundCheckEnable = *p_wrap_around_check_enable;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::sequence_step_enabled(VL53L0X_SequenceStepId sequence_step_id, uint8_t sequence_config,
+ uint8_t *p_sequence_step_enabled)
+{ VL53L0X_Error Status = VL53L0X_ERROR_NONE;
+ *p_sequence_step_enabled = 0;
+
+ switch (sequence_step_id) {
+ case VL53L0X_SEQUENCESTEP_TCC:
+ *p_sequence_step_enabled = (sequence_config & 0x10) >> 4;
+ break;
+ case VL53L0X_SEQUENCESTEP_DSS:
+ *p_sequence_step_enabled = (sequence_config & 0x08) >> 3;
+ break;
+ case VL53L0X_SEQUENCESTEP_MSRC:
+ *p_sequence_step_enabled = (sequence_config & 0x04) >> 2;
+ break;
+ case VL53L0X_SEQUENCESTEP_PRE_RANGE:
+ *p_sequence_step_enabled = (sequence_config & 0x40) >> 6;
+ break;
+ case VL53L0X_SEQUENCESTEP_FINAL_RANGE:
+ *p_sequence_step_enabled = (sequence_config & 0x80) >> 7;
+ break;
+ default:
+ Status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ return Status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_sequence_step_enables(VL53L0X_SchedulerSequenceSteps_t *p_scheduler_sequence_steps)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t sequence_config = 0;
+
+ status = VL53L0X_read_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG,
+ &sequence_config);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = sequence_step_enabled(VL53L0X_SEQUENCESTEP_TCC, sequence_config,
+ &p_scheduler_sequence_steps->TccOn);
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ status = sequence_step_enabled(VL53L0X_SEQUENCESTEP_DSS, sequence_config,
+ &p_scheduler_sequence_steps->DssOn);
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ status = sequence_step_enabled(VL53L0X_SEQUENCESTEP_MSRC, sequence_config,
+ &p_scheduler_sequence_steps->MsrcOn);
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ status = sequence_step_enabled(VL53L0X_SEQUENCESTEP_PRE_RANGE, sequence_config,
+ &p_scheduler_sequence_steps->PreRangeOn);
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ status = sequence_step_enabled(VL53L0X_SEQUENCESTEP_FINAL_RANGE, sequence_config,
+ &p_scheduler_sequence_steps->FinalRangeOn);
+ }
+ return status;
+}
+
+uint8_t VL53L0X::VL53L0X_decode_vcsel_period(uint8_t vcsel_period_reg)
+{ /*! Converts the encoded VCSEL period register value into the real period in PLL clocks */
+ uint8_t vcsel_period_pclks = 0;
+
+ vcsel_period_pclks = (vcsel_period_reg + 1) << 1;
+
+ return vcsel_period_pclks;
+}
+
+uint8_t VL53L0X::lv53l0x_encode_vcsel_period(uint8_t vcsel_period_pclks)
+{ /*! Converts the encoded VCSEL period register value into the real period in PLL clocks */
+
+ uint8_t vcsel_period_reg = 0;
+
+ vcsel_period_reg = (vcsel_period_pclks >> 1) - 1;
+
+ return vcsel_period_reg;
+}
+
+VL53L0X_Error VL53L0X::wrapped_VL53L0X_set_vcsel_pulse_period(VL53L0X_VcselPeriod vcsel_period_type, uint8_t vcsel_pulse_period_pclk)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t vcsel_period_reg;
+ uint8_t min_pre_vcsel_period_pclk = 12;
+ uint8_t max_pre_vcsel_period_pclk = 18;
+ uint8_t min_final_vcsel_period_pclk = 8;
+ uint8_t max_final_vcsel_period_pclk = 14;
+ uint32_t measurement_timing_budget_us;
+ uint32_t final_range_timeout_us;
+ uint32_t pre_range_timeout_us;
+ uint32_t msrc_timeout_us;
+ uint8_t phase_cal_int = 0;
+
+ /* Check if valid clock period requested */
+
+ if ((vcsel_pulse_period_pclk % 2) != 0) {
+ /* Value must be an even number */
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ } else if (vcsel_period_type == VL53L0X_VCSEL_PERIOD_PRE_RANGE &&
+ (vcsel_pulse_period_pclk < min_pre_vcsel_period_pclk ||
+ vcsel_pulse_period_pclk > max_pre_vcsel_period_pclk)) {
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ } else if (vcsel_period_type == VL53L0X_VCSEL_PERIOD_FINAL_RANGE &&
+ (vcsel_pulse_period_pclk < min_final_vcsel_period_pclk ||
+ vcsel_pulse_period_pclk > max_final_vcsel_period_pclk)) {
+
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+
+ /* Apply specific settings for the requested clock period */
+
+ if (status != VL53L0X_ERROR_NONE) { return status; }
+
+ if (vcsel_period_type == VL53L0X_VCSEL_PERIOD_PRE_RANGE) {
+
+ /* Set phase check limits */
+ if (vcsel_pulse_period_pclk == 12) {
+
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH,
+ 0x18);
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW,
+ 0x08);
+ } else if (vcsel_pulse_period_pclk == 14) {
+
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH,
+ 0x30);
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW,
+ 0x08);
+ } else if (vcsel_pulse_period_pclk == 16) {
+
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH,
+ 0x40);
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW,
+ 0x08);
+ } else if (vcsel_pulse_period_pclk == 18) {
+
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH,
+ 0x50);
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW,
+ 0x08);
+ }
+ } else if (vcsel_period_type == VL53L0X_VCSEL_PERIOD_FINAL_RANGE) {
+ if (vcsel_pulse_period_pclk == 8) {
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH,0x10);
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,0x08);
+ status |= VL53L0X_write_byte(VL53L0X_REG_GLOBAL_CONFIG_VCSEL_WIDTH, 0x02);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x0C);
+ status |= VL53L0X_write_byte( 0xff, 0x01);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_LIM,0x30);
+ status |= VL53L0X_write_byte( 0xff, 0x00);
+ } else if (vcsel_pulse_period_pclk == 10) {
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH,0x28);
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,0x08);
+ status |= VL53L0X_write_byte(VL53L0X_REG_GLOBAL_CONFIG_VCSEL_WIDTH, 0x03);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x09);
+ status |= VL53L0X_write_byte( 0xff, 0x01);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_LIM,0x20);
+ status |= VL53L0X_write_byte( 0xff, 0x00);
+ } else if (vcsel_pulse_period_pclk == 12) {
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH, 0x38);
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW, 0x08);
+ status |= VL53L0X_write_byte(VL53L0X_REG_GLOBAL_CONFIG_VCSEL_WIDTH, 0x03);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x08);
+ status |= VL53L0X_write_byte( 0xff, 0x01);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_LIM,0x20);
+ status |= VL53L0X_write_byte( 0xff, 0x00);
+ } else if (vcsel_pulse_period_pclk == 14) {
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH,0x048);
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW,0x08);
+ status |= VL53L0X_write_byte(VL53L0X_REG_GLOBAL_CONFIG_VCSEL_WIDTH, 0x03);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_CONFIG_TIMEOUT, 0x07);
+ status |= VL53L0X_write_byte( 0xff, 0x01);
+ status |= VL53L0X_write_byte(VL53L0X_REG_ALGO_PHASECAL_LIM,0x20);
+ status |= VL53L0X_write_byte( 0xff, 0x00);
+ }
+ }
+
+ /* Re-calculate and apply timeouts, in macro periods */
+
+ if (status == VL53L0X_ERROR_NONE) {
+ vcsel_period_reg = lv53l0x_encode_vcsel_period((uint8_t) vcsel_pulse_period_pclk);
+
+ /* When the VCSEL period for the pre or final range is changed,
+ * the corresponding timeout must be read from the device using
+ * the current VCSEL period, then the new VCSEL period can be
+ * applied. The timeout then must be written back to the device
+ * using the new VCSEL period.
+ *
+ * For the MSRC timeout, the same applies - this timeout being
+ * dependant on the pre-range vcsel period.
+ */
+ switch (vcsel_period_type) {
+ case VL53L0X_VCSEL_PERIOD_PRE_RANGE:
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_PRE_RANGE,
+ &pre_range_timeout_us);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_MSRC,
+ &msrc_timeout_us);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_write_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VCSEL_PERIOD,
+ vcsel_period_reg);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = set_sequence_step_timeout(VL53L0X_SEQUENCESTEP_PRE_RANGE,
+ pre_range_timeout_us);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = set_sequence_step_timeout(VL53L0X_SEQUENCESTEP_MSRC,
+ msrc_timeout_us);
+
+ Data.PreRangeVcselPulsePeriod = vcsel_pulse_period_pclk;
+ break;
+ case VL53L0X_VCSEL_PERIOD_FINAL_RANGE:
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_FINAL_RANGE,
+ &final_range_timeout_us);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_write_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VCSEL_PERIOD,
+ vcsel_period_reg);
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = set_sequence_step_timeout(VL53L0X_SEQUENCESTEP_FINAL_RANGE,
+ final_range_timeout_us);
+
+ Data.FinalRangeVcselPulsePeriod = vcsel_pulse_period_pclk;
+ break;
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+
+ /* Finally, the timing budget must be re-applied */
+ if (status == VL53L0X_ERROR_NONE) {
+ measurement_timing_budget_us = CurrentParameters.MeasurementTimingBudget_us ;
+ status = VL53L0X_set_measurement_timing_budget_us(measurement_timing_budget_us);
+ }
+
+ /* Perform the phase calibration. This is needed after changing on
+ * vcsel period. get_data_enable = 0, restore_config = 1 */
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_perform_phase_calibration(&phase_cal_int, 0, 1);
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_vcsel_pulse_period(VL53L0X_VcselPeriod vcsel_period_type, uint8_t vcsel_pulse_period)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ status = wrapped_VL53L0X_set_vcsel_pulse_period( vcsel_period_type, vcsel_pulse_period);
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_vcsel_pulse_period(VL53L0X_VcselPeriod vcsel_period_type, uint8_t *p_vcsel_pulse_period_pclk)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t vcsel_period_reg;
+
+ switch (vcsel_period_type) {
+ case VL53L0X_VCSEL_PERIOD_PRE_RANGE:
+ status = VL53L0X_read_byte(VL53L0X_REG_PRE_RANGE_CONFIG_VCSEL_PERIOD,
+ &vcsel_period_reg);
+ break;
+ case VL53L0X_VCSEL_PERIOD_FINAL_RANGE:
+ status = VL53L0X_read_byte(VL53L0X_REG_FINAL_RANGE_CONFIG_VCSEL_PERIOD,
+ &vcsel_period_reg);
+ break;
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+
+ if (status == VL53L0X_ERROR_NONE)
+ *p_vcsel_pulse_period_pclk = VL53L0X_decode_vcsel_period(vcsel_period_reg);
+
+ return status;
+}
+
+uint32_t VL53L0X::VL53L0X_decode_timeout(uint16_t encoded_timeout)
+{ /*! Decode 16-bit timeout register value - format (LSByte * 2^MSByte) + 1 */
+ uint32_t timeout_macro_clks = 0;
+
+ timeout_macro_clks = ((uint32_t)(encoded_timeout & 0x00FF)
+ << (uint32_t)((encoded_timeout & 0xFF00) >> 8)) + 1;
+
+ return timeout_macro_clks;
+}
+
+uint32_t VL53L0X::VL53L0X_calc_macro_period_ps( uint8_t vcsel_period_pclks)
+{ uint64_t pll_period_ps;
+ uint32_t macro_period_vclks;
+ uint32_t macro_period_ps;
+
+ /* The above calculation will produce rounding errors, therefore set fixed value*/
+ pll_period_ps = 1655;
+ macro_period_vclks = 2304;
+ macro_period_ps = (uint32_t)(macro_period_vclks
+ * vcsel_period_pclks * pll_period_ps);
+ return macro_period_ps;
+}
+
+/* To convert register value into us */
+uint32_t VL53L0X::VL53L0X_calc_timeout_us(uint16_t timeout_period_mclks,
+ uint8_t vcsel_period_pclks)
+{ uint32_t macro_period_ps;
+ uint32_t macro_period_ns;
+ uint32_t actual_timeout_period_us = 0;
+
+ macro_period_ps = VL53L0X_calc_macro_period_ps( vcsel_period_pclks);
+ macro_period_ns = (macro_period_ps + 500) / 1000;
+
+ actual_timeout_period_us =
+ ((timeout_period_mclks * macro_period_ns) + 500) / 1000;
+
+ return actual_timeout_period_us;
+}
+
+VL53L0X_Error VL53L0X::get_sequence_step_timeout(VL53L0X_SequenceStepId sequence_step_id,
+ uint32_t *p_time_out_micro_secs)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t current_vcsel_pulse_period_p_clk;
+ uint8_t encoded_time_out_byte = 0;
+ uint32_t timeout_us = 0;
+ uint16_t pre_range_encoded_time_out = 0;
+ uint16_t msrc_time_out_m_clks;
+ uint16_t pre_range_time_out_m_clks;
+ uint16_t final_range_time_out_m_clks = 0;
+ uint16_t final_range_encoded_time_out;
+ VL53L0X_SchedulerSequenceSteps_t scheduler_sequence_steps;
+
+ if ((sequence_step_id == VL53L0X_SEQUENCESTEP_TCC) ||
+ (sequence_step_id == VL53L0X_SEQUENCESTEP_DSS) ||
+ (sequence_step_id == VL53L0X_SEQUENCESTEP_MSRC)) {
+
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_byte(VL53L0X_REG_MSRC_CONFIG_TIMEOUT_MACROP,
+ &encoded_time_out_byte);
+ }
+ msrc_time_out_m_clks = VL53L0X_decode_timeout(encoded_time_out_byte);
+
+ timeout_us = VL53L0X_calc_timeout_us(msrc_time_out_m_clks,
+ current_vcsel_pulse_period_p_clk);
+ } else if (sequence_step_id == VL53L0X_SEQUENCESTEP_PRE_RANGE) {
+ /* Retrieve PRE-RANGE VCSEL Period */
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+
+ /* Retrieve PRE-RANGE Timeout in Macro periods (MCLKS) */
+ if (status == VL53L0X_ERROR_NONE) {
+
+ /* Retrieve PRE-RANGE VCSEL Period */
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word(VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI,
+ &pre_range_encoded_time_out);
+ }
+
+ pre_range_time_out_m_clks = VL53L0X_decode_timeout(pre_range_encoded_time_out);
+
+ timeout_us = VL53L0X_calc_timeout_us(pre_range_time_out_m_clks,
+ current_vcsel_pulse_period_p_clk);
+ }
+ } else if (sequence_step_id == VL53L0X_SEQUENCESTEP_FINAL_RANGE) {
+
+ VL53L0X_get_sequence_step_enables( &scheduler_sequence_steps);
+ pre_range_time_out_m_clks = 0;
+
+ if (scheduler_sequence_steps.PreRangeOn) {
+ /* Retrieve PRE-RANGE VCSEL Period */
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+
+ /* Retrieve PRE-RANGE Timeout in Macro periods
+ * (MCLKS) */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word(VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI,
+ &pre_range_encoded_time_out);
+ pre_range_time_out_m_clks = VL53L0X_decode_timeout(pre_range_encoded_time_out);
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ /* Retrieve FINAL-RANGE VCSEL Period */
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_FINAL_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+ }
+
+ /* Retrieve FINAL-RANGE Timeout in Macro periods (MCLKS) */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word(VL53L0X_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI,
+ &final_range_encoded_time_out);
+ final_range_time_out_m_clks = VL53L0X_decode_timeout(final_range_encoded_time_out);
+ }
+
+ final_range_time_out_m_clks -= pre_range_time_out_m_clks;
+ timeout_us = VL53L0X_calc_timeout_us(final_range_time_out_m_clks,
+ current_vcsel_pulse_period_p_clk);
+ }
+
+ *p_time_out_micro_secs = timeout_us;
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_measurement_timing_budget_us(uint32_t *p_measurement_timing_budget_us)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ VL53L0X_SchedulerSequenceSteps_t scheduler_sequence_steps;
+ uint32_t final_range_timeout_us;
+ uint32_t msrc_dcc_tcc_timeout_us = 2000;
+ uint32_t start_overhead_us = 1910;
+ uint32_t end_overhead_us = 960;
+ uint32_t msrc_overhead_us = 660;
+ uint32_t tcc_overhead_us = 590;
+ uint32_t dss_overhead_us = 690;
+ uint32_t pre_range_overhead_us = 660;
+ uint32_t final_range_overhead_us = 550;
+ uint32_t pre_range_timeout_us = 0;
+
+ /* Start and end overhead times always present */
+ *p_measurement_timing_budget_us
+ = start_overhead_us + end_overhead_us;
+
+ status = VL53L0X_get_sequence_step_enables( &scheduler_sequence_steps);
+
+ if (status != VL53L0X_ERROR_NONE) { return status; }
+
+ if (scheduler_sequence_steps.TccOn ||
+ scheduler_sequence_steps.MsrcOn ||
+ scheduler_sequence_steps.DssOn) {
+
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_MSRC,
+ &msrc_dcc_tcc_timeout_us);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (scheduler_sequence_steps.TccOn) {
+ *p_measurement_timing_budget_us +=
+ msrc_dcc_tcc_timeout_us + tcc_overhead_us;
+ }
+
+ if (scheduler_sequence_steps.DssOn) {
+ *p_measurement_timing_budget_us +=
+ 2 * (msrc_dcc_tcc_timeout_us + dss_overhead_us);
+ } else if (scheduler_sequence_steps.MsrcOn) {
+ *p_measurement_timing_budget_us +=
+ msrc_dcc_tcc_timeout_us + msrc_overhead_us;
+ }
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (scheduler_sequence_steps.PreRangeOn) {
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_PRE_RANGE,
+ &pre_range_timeout_us);
+ *p_measurement_timing_budget_us +=
+ pre_range_timeout_us + pre_range_overhead_us;
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (scheduler_sequence_steps.FinalRangeOn) {
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_FINAL_RANGE,
+ &final_range_timeout_us);
+ *p_measurement_timing_budget_us +=
+ (final_range_timeout_us + final_range_overhead_us);
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ CurrentParameters.MeasurementTimingBudget_us = *p_measurement_timing_budget_us;}
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_device_parameters(VL53L0X_DeviceParameters_t *p_device_parameters)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ int i;
+
+ p_device_parameters->DeviceMode = CurrentParameters.DeviceMode;
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_get_inter_measurement_period_ms(&(p_device_parameters->InterMeasurementPeriod_ms));
+
+ if (status == VL53L0X_ERROR_NONE) {
+ p_device_parameters->XTalkCompensationEnable = 0;
+ }
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_get_x_talk_compensation_rate_MHz(&(p_device_parameters->XTalkCompensationRate_MHz));
+
+ if (status == VL53L0X_ERROR_NONE)
+ status = VL53L0X_get_offset_calibration_data_micro_meter(&(p_device_parameters->RangeOffset_um));
+
+ if (status == VL53L0X_ERROR_NONE) {
+ for (i = 0; i < VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS; i++) {
+ /* get first the values, then the enables.
+ * VL53L0X_GetLimitCheckValue will modify the enable
+ * flags
+ */
+ if (status == VL53L0X_ERROR_NONE) {
+ status |= VL53L0X_get_limit_check_value( i,
+ &(p_device_parameters->LimitChecksValue[i]));
+ } else {
+ break;
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ status |= VL53L0X_get_limit_check_enable( i,
+ &(p_device_parameters->LimitChecksEnable[i]));
+ } else {
+ break;
+ }
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_wrap_around_check_enable(&(p_device_parameters->WrapAroundCheckEnable));
+ }
+
+ /* Need to be done at the end as it uses VCSELPulsePeriod */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_measurement_timing_budget_us(&(p_device_parameters->MeasurementTimingBudget_us));
+ }
+
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_limit_check_value( uint16_t limit_check_id,
+ FixPoint1616_t limit_check_value)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t temp8;
+
+ temp8 = CurrentParameters.LimitChecksEnable[limit_check_id];
+
+ if (temp8 == 0) { /* disabled write only internal value */
+ CurrentParameters.LimitChecksValue[limit_check_id] = limit_check_value;
+ } else {
+
+ switch (limit_check_id) {
+
+ case VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE:/* internal computation: */
+ CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] = limit_check_value;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
+ status = VL53L0X_write_word(VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT,
+ VL53L0X_FP1616TOFP97(limit_check_value));
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP:/* internal computation: */
+ CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP] = limit_check_value;
+ break;
+
+ case VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD:/* internal computation: */
+ CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD] = limit_check_value;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC:
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE:
+ status = VL53L0X_write_word(VL53L0X_REG_PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT,
+ VL53L0X_FP1616TOFP97(limit_check_value));
+ break;
+
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ CurrentParameters.LimitChecksValue[limit_check_id] = limit_check_value;
+ }
+ }
+ return status;
+}
+
+// instead of passing VL53L0X_DeviceInfo_t *p_VL53L0X_device_info, directly fill Device_Info
+VL53L0X_Error VL53L0X::VL53L0X_get_device_info()
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t revision_id;
+ uint8_t revision;
+ char *product_id_tmp;
+
+ status = VL53L0X_get_info_from_device( 2);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (Data.ModuleId == 0) {
+ revision = 0;
+ VL53L0X_COPYSTRING(Device_Info.ProductId, "");
+ } else {
+ revision = Data.Revision;
+ product_id_tmp = Data.ProductId;
+ VL53L0X_COPYSTRING(Device_Info.ProductId, product_id_tmp);
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (revision == 0) {
+ VL53L0X_COPYSTRING(Device_Info.Name,
+ VL53L0X_STRING_DEVICE_INFO_NAME_TS0);
+ } else if ((revision <= 34) && (revision != 32)) {
+ VL53L0X_COPYSTRING(Device_Info.Name,
+ VL53L0X_STRING_DEVICE_INFO_NAME_TS1);
+ } else if (revision < 39) {
+ VL53L0X_COPYSTRING(Device_Info.Name,
+ VL53L0X_STRING_DEVICE_INFO_NAME_TS2);
+ } else {VL53L0X_COPYSTRING(Device_Info.Name,
+ VL53L0X_STRING_DEVICE_INFO_NAME_ES1);
+ }
+
+ VL53L0X_COPYSTRING(Device_Info.Type, VL53L0X_STRING_DEVICE_INFO_TYPE);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_byte( VL53L0X_REG_IDENTIFICATION_MODEL_ID,
+ &Device_Info.ProductType);}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_byte(VL53L0X_REG_IDENTIFICATION_REVISION_ID,
+ &revision_id);
+ Device_Info.ProductRevisionMajor = 1;
+ Device_Info.ProductRevisionMinor =
+ (revision_id & 0xF0) >> 4;
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_interrupt_mask_status(uint32_t *p_interrupt_mask_status)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t byte;
+
+ status = VL53L0X_read_byte( VL53L0X_REG_RESULT_INTERRUPT_STATUS, &byte);
+ *p_interrupt_mask_status = byte & 0x07;
+
+ if (byte & 0x18) { status = VL53L0X_ERROR_RANGE_ERROR;}
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_measurement_data_ready(uint8_t *p_measurement_data_ready)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t sys_range_status_register;
+ uint8_t interrupt_config;
+ uint32_t interrupt_mask;
+
+ interrupt_config = Data.Pin0GpioFunctionality;
+
+ if (interrupt_config ==
+ VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY) {
+ status = VL53L0X_get_interrupt_mask_status( &interrupt_mask);
+ if (interrupt_mask ==
+ VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY) {
+ *p_measurement_data_ready = 1;
+ } else {
+ *p_measurement_data_ready = 0;
+ }
+ } else {
+ status = VL53L0X_read_byte( VL53L0X_REG_RESULT_RANGE_STATUS,
+ &sys_range_status_register);
+ if (status == VL53L0X_ERROR_NONE) {
+ if (sys_range_status_register & 0x01) {
+ *p_measurement_data_ready = 1;
+ } else { *p_measurement_data_ready = 0; }
+ }
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_polling_delay(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ // do nothing
+ VL53L0X_OsDelay();
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_measurement_poll_for_completion(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t new_data_ready = 0;
+ uint32_t loop_nb;
+
+ loop_nb = 0;
+
+ do {
+ status = VL53L0X_get_measurement_data_ready( &new_data_ready);
+ if (status != 0) {
+ break; /* the error is set */
+ }
+
+ if (new_data_ready == 1) {
+ break; /* done note that status == 0 */
+ }
+
+ loop_nb++;
+ if (loop_nb >= VL53L0X_DEFAULT_MAX_LOOP) {
+ status = VL53L0X_ERROR_TIME_OUT;
+ break;
+ }
+
+ VL53L0X_polling_delay();
+ } while (1);
+
+ return status;
+}
+
+/* Group PAL Interrupt Functions */
+VL53L0X_Error VL53L0X::VL53L0X_clear_interrupt_mask( uint32_t interrupt_mask)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t loop_count;
+ uint8_t byte;
+
+ /* clear bit 0 range interrupt, bit 1 error interrupt */
+ loop_count = 0;
+ do {
+ status = VL53L0X_write_byte(VL53L0X_REG_SYSTEM_INTERRUPT_CLEAR, 0x01);
+ status |= VL53L0X_write_byte(VL53L0X_REG_SYSTEM_INTERRUPT_CLEAR, 0x00);
+ status |= VL53L0X_read_byte(VL53L0X_REG_RESULT_INTERRUPT_STATUS, &byte);
+ loop_count++;
+ } while (((byte & 0x07) != 0x00)
+ && (loop_count < 3)
+ && (status == VL53L0X_ERROR_NONE));
+
+ if (loop_count >= 3) {
+ status = VL53L0X_ERROR_INTERRUPT_NOT_CLEARED;
+ }
+
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_single_ref_calibration(uint8_t vhv_init_byte)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSRANGE_START,
+ VL53L0X_REG_SYSRANGE_MODE_START_STOP |
+ vhv_init_byte);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_measurement_poll_for_completion();}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_clear_interrupt_mask( 0);}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSRANGE_START, 0x00);
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_ref_calibration_io( uint8_t read_not_write,
+ uint8_t vhv_settings, uint8_t phase_cal,
+ uint8_t *p_vhv_settings, uint8_t *p_phase_cal,
+ const uint8_t vhv_enable, const uint8_t phase_enable)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t phase_calint = 0;
+
+ /* Read VHV from device */
+ status |= VL53L0X_write_byte( 0xFF, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x00);
+ status |= VL53L0X_write_byte( 0xFF, 0x00);
+
+ if (read_not_write) {
+ if (vhv_enable) {
+ status |= VL53L0X_read_byte( 0xCB, p_vhv_settings);}
+ if (phase_enable) {
+ status |= VL53L0X_read_byte( 0xEE, &phase_calint);}
+ } else {
+ if (vhv_enable) {
+ status |= VL53L0X_write_byte( 0xCB, vhv_settings);}
+ if (phase_enable) {
+ status |= VL53L0X_update_byte( 0xEE, 0x80, phase_cal);}
+ }
+
+ status |= VL53L0X_write_byte( 0xFF, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x01);
+ status |= VL53L0X_write_byte( 0xFF, 0x00);
+
+ *p_phase_cal = (uint8_t)(phase_calint & 0xEF);
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_vhv_calibration(uint8_t *p_vhv_settings, const uint8_t get_data_enable,
+ const uint8_t restore_config)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t sequence_config = 0;
+ uint8_t vhv_settings = 0;
+ uint8_t phase_cal = 0;
+ uint8_t phase_cal_int = 0;
+
+ /* store the value of the sequence config,
+ * this will be reset before the end of the function
+ */
+
+ if (restore_config) {
+ sequence_config = Data.SequenceConfig;
+ }
+
+ /* Run VHV */
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, 0x01);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_single_ref_calibration( 0x40);}
+
+ /* Read VHV from device */
+ if ((status == VL53L0X_ERROR_NONE) && (get_data_enable == 1)) {
+ status = VL53L0X_ref_calibration_io( 1, vhv_settings, phase_cal, /* Not used here */
+ p_vhv_settings, &phase_cal_int, 1, 0);
+ } else {*p_vhv_settings = 0; }
+
+ if ((status == VL53L0X_ERROR_NONE) && restore_config) {
+ /* restore the previous Sequence Config */
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG,
+ sequence_config);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = sequence_config; }
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_phase_calibration(uint8_t *p_phase_cal, const uint8_t get_data_enable,
+ const uint8_t restore_config)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t sequence_config = 0;
+ uint8_t vhv_settings = 0;
+ uint8_t phase_cal = 0;
+ uint8_t vhv_settingsint;
+
+ /* store the value of the sequence config,
+ * this will be reset before the end of the function */
+
+ if (restore_config) {
+ sequence_config = Data.SequenceConfig;
+ }
+
+ /* Run PhaseCal */
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, 0x02);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_single_ref_calibration( 0x0);
+ }
+
+ /* Read PhaseCal from device */
+ if ((status == VL53L0X_ERROR_NONE) && (get_data_enable == 1)) {
+ status = VL53L0X_ref_calibration_io( 1,
+ vhv_settings, phase_cal, /* Not used here */
+ &vhv_settingsint, p_phase_cal,
+ 0, 1);
+ } else {
+ *p_phase_cal = 0;
+ }
+
+ if ((status == VL53L0X_ERROR_NONE) && restore_config) {
+ /* restore the previous Sequence Config */
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG,
+ sequence_config);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = sequence_config;
+ }
+
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_ref_calibration(uint8_t *p_vhv_settings, uint8_t *p_phase_cal, uint8_t get_data_enable)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t sequence_config = 0;
+
+ /* store the value of the sequence config,
+ * this will be reset before the end of the function */
+
+ sequence_config = Data.SequenceConfig;
+
+ /* In the following function we don't save the config to optimize
+ * writes on device. Config is saved and restored only once. */
+ status = VL53L0X_perform_vhv_calibration(p_vhv_settings, get_data_enable, 0);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_phase_calibration(p_phase_cal, get_data_enable, 0); }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ /* restore the previous Sequence Config */
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG,
+ sequence_config);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = sequence_config; }
+ }
+
+ return status;
+}
+
+void VL53L0X::get_next_good_spad(uint8_t good_spad_array[], uint32_t size,
+ uint32_t curr, int32_t *p_next)
+{ uint32_t start_index;
+ uint32_t fine_offset;
+ uint32_t c_spads_per_byte = 8;
+ uint32_t coarse_index;
+ uint32_t fine_index;
+ uint8_t data_byte;
+ uint8_t success = 0;
+
+ /* Starting with the current good spad, loop through the array to find
+ * the next. i.e. the next bit set in the sequence.
+ *
+ * The coarse index is the byte index of the array and the fine index is
+ * the index of the bit within each byte. */
+
+ *p_next = -1;
+
+ start_index = curr / c_spads_per_byte;
+ fine_offset = curr % c_spads_per_byte;
+
+ for (coarse_index = start_index; ((coarse_index < size) && !success);
+ coarse_index++) {
+ fine_index = 0;
+ data_byte = good_spad_array[coarse_index];
+
+ if (coarse_index == start_index) {
+ /* locate the bit position of the provided current
+ * spad bit before iterating */
+ data_byte >>= fine_offset;
+ fine_index = fine_offset;
+ }
+
+ while (fine_index < c_spads_per_byte) {
+ if ((data_byte & 0x1) == 1) {
+ success = 1;
+ *p_next = coarse_index * c_spads_per_byte + fine_index;
+ break;
+ }
+ data_byte >>= 1;
+ fine_index++;
+ }
+ }
+}
+
+uint8_t VL53L0X::is_aperture(uint32_t spad_index)
+{ /* This function reports if a given spad index is an aperture SPAD by
+ * deriving the quadrant.*/
+ uint32_t quadrant;
+ uint8_t is_aperture = 1;
+ quadrant = spad_index >> 6;
+ if (refArrayQuadrants[quadrant] == REF_ARRAY_SPAD_0) {
+ is_aperture = 0;
+ }
+
+ return is_aperture;
+}
+
+VL53L0X_Error VL53L0X::enable_spad_bit(uint8_t spad_array[], uint32_t size,
+ uint32_t spad_index)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint32_t c_spads_per_byte = 8;
+ uint32_t coarse_index;
+ uint32_t fine_index;
+
+ coarse_index = spad_index / c_spads_per_byte;
+ fine_index = spad_index % c_spads_per_byte;
+ if (coarse_index >= size) {
+ status = VL53L0X_ERROR_REF_SPAD_INIT;
+ } else {
+ spad_array[coarse_index] |= (1 << fine_index);
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::set_ref_spad_map( uint8_t *p_ref_spad_array)
+{ VL53L0X_Error status = VL53L0X_i2c_write(VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_0,
+ p_ref_spad_array, 6);
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::get_ref_spad_map( uint8_t *p_ref_spad_array)
+{ VL53L0X_Error status = VL53L0X_read_multi(VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_0,
+ p_ref_spad_array,
+ 6);
+// VL53L0X_Error status = VL53L0X_ERROR_NONE;
+// uint8_t count=0;
+
+// for (count = 0; count < 6; count++)
+// status = VL53L0X_RdByte( (VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_0 + count), &refSpadArray[count]);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::enable_ref_spads(uint8_t aperture_spads,
+ uint8_t good_spad_array[],
+ uint8_t spad_array[],
+ uint32_t size,
+ uint32_t start,
+ uint32_t offset,
+ uint32_t spad_count,
+ uint32_t *p_last_spad)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint32_t index;
+ uint32_t i;
+ int32_t next_good_spad = offset;
+ uint32_t current_spad;
+ uint8_t check_spad_array[6];
+
+ /*
+ * This function takes in a spad array which may or may not have SPADS
+ * already enabled and appends from a given offset a requested number
+ * of new SPAD enables. The 'good spad map' is applied to
+ * determine the next SPADs to enable.
+ *
+ * This function applies to only aperture or only non-aperture spads.
+ * Checks are performed to ensure this.
+ */
+
+ current_spad = offset;
+ for (index = 0; index < spad_count; index++) {
+ get_next_good_spad(good_spad_array, size, current_spad,
+ &next_good_spad);
+
+ if (next_good_spad == -1) {
+ status = VL53L0X_ERROR_REF_SPAD_INIT;
+ break;
+ }
+
+ /* Confirm that the next good SPAD is non-aperture */
+ if (is_aperture(start + next_good_spad) != aperture_spads) {
+ /* if we can't get the required number of good aperture
+ * spads from the current quadrant then this is an error
+ */
+ status = VL53L0X_ERROR_REF_SPAD_INIT;
+ break;
+ }
+ current_spad = (uint32_t)next_good_spad;
+ enable_spad_bit(spad_array, size, current_spad);
+ current_spad++;
+ }
+ *p_last_spad = current_spad;
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = set_ref_spad_map( spad_array);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = get_ref_spad_map( check_spad_array);
+
+ i = 0;
+
+ /* Compare spad maps. If not equal report error. */
+ while (i < size) {
+ if (spad_array[i] != check_spad_array[i]) {
+ status = VL53L0X_ERROR_REF_SPAD_INIT;
+ break;
+ }
+ i++;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_device_mode( VL53L0X_DeviceModes device_mode)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ switch (device_mode) {
+ case VL53L0X_DEVICEMODE_SINGLE_RANGING:
+ case VL53L0X_DEVICEMODE_CONTINUOUS_RANGING:
+ case VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING:
+ case VL53L0X_DEVICEMODE_GPIO_DRIVE:
+ case VL53L0X_DEVICEMODE_GPIO_OSC:
+ /* Supported modes */
+ CurrentParameters.DeviceMode = device_mode;
+ break;
+ default:
+ /* Unsupported mode */
+ status = VL53L0X_ERROR_MODE_NOT_SUPPORTED;
+ }
+
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_interrupt_thresholds(VL53L0X_DeviceModes device_mode, FixPoint1616_t threshold_low,
+ FixPoint1616_t threshold_high)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint16_t threshold16;
+
+
+ /* no dependency on DeviceMode for Ewok */
+ /* Need to divide by 2 because the FW will apply a x2 */
+ threshold16 = (uint16_t)((threshold_low >> 17) & 0x00fff);
+ status = VL53L0X_write_word( VL53L0X_REG_SYSTEM_THRESH_LOW, threshold16);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ /* Need to divide by 2 because the FW will apply a x2 */
+ threshold16 = (uint16_t)((threshold_high >> 17) & 0x00fff);
+ status = VL53L0X_write_word( VL53L0X_REG_SYSTEM_THRESH_HIGH,
+ threshold16);
+ }
+
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_interrupt_thresholds(VL53L0X_DeviceModes device_mode, FixPoint1616_t *p_threshold_low,
+ FixPoint1616_t *p_threshold_high)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint16_t threshold16;
+
+
+ /* no dependency on DeviceMode for Ewok */
+
+ status = VL53L0X_read_word( VL53L0X_REG_SYSTEM_THRESH_LOW, &threshold16);
+ /* Need to multiply by 2 because the FW will apply a x2 */
+ *p_threshold_low = (FixPoint1616_t)((0x00fff & threshold16) << 17);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word( VL53L0X_REG_SYSTEM_THRESH_HIGH,
+ &threshold16);
+ /* Need to multiply by 2 because the FW will apply a x2 */
+ *p_threshold_high =
+ (FixPoint1616_t)((0x00fff & threshold16) << 17);
+ }
+
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_load_tuning_settings(uint8_t *p_tuning_setting_buffer)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ int i;
+ int index;
+ uint8_t msb;
+ uint8_t lsb;
+ uint8_t select_param;
+ uint16_t number_of_writes;
+ uint8_t address;
+ uint8_t local_buffer[4]; /* max */
+ uint16_t temp16;
+
+ index = 0;
+
+ while ((*(p_tuning_setting_buffer + index) != 0) &&
+ (status == VL53L0X_ERROR_NONE)) {
+ number_of_writes = *(p_tuning_setting_buffer + index);
+ index++;
+ if (number_of_writes == 0xFF) {
+ /* internal parameters */
+ select_param = *(p_tuning_setting_buffer + index);
+ index++;
+ switch (select_param) {
+ case 0: /* uint16_t SigmaEstRefArray -> 2 bytes */
+ msb = *(p_tuning_setting_buffer + index);
+ index++;
+ lsb = *(p_tuning_setting_buffer + index);
+ index++;
+ temp16 = VL53L0X_MAKEUINT16(lsb, msb);
+ Data.SigmaEstRefArray = temp16;
+ break;
+ case 1: /* uint16_t SigmaEstEffPulseWidth -> 2 bytes */
+ msb = *(p_tuning_setting_buffer + index);
+ index++;
+ lsb = *(p_tuning_setting_buffer + index);
+ index++;
+ temp16 = VL53L0X_MAKEUINT16(lsb, msb);
+ Data.SigmaEstEffPulseWidth = temp16;
+ break;
+ case 2: /* uint16_t SigmaEstEffAmbWidth -> 2 bytes */
+ msb = *(p_tuning_setting_buffer + index);
+ index++;
+ lsb = *(p_tuning_setting_buffer + index);
+ index++;
+ temp16 = VL53L0X_MAKEUINT16(lsb, msb);
+ Data.SigmaEstEffAmbWidth = temp16;
+ break;
+ case 3: /* uint16_t targetRefRate -> 2 bytes */
+ msb = *(p_tuning_setting_buffer + index);
+ index++;
+ lsb = *(p_tuning_setting_buffer + index);
+ index++;
+ temp16 = VL53L0X_MAKEUINT16(lsb, msb);
+ Data.targetRefRate = temp16;
+ break;
+ default: /* invalid parameter */
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+
+ } else if (number_of_writes <= 4) {
+ address = *(p_tuning_setting_buffer + index);
+ index++;
+
+ for (i = 0; i < number_of_writes; i++) {
+ local_buffer[i] = *(p_tuning_setting_buffer +
+ index);
+ index++;
+ }
+
+ status = VL53L0X_i2c_write( address, local_buffer, number_of_writes);
+
+ } else { status = VL53L0X_ERROR_INVALID_PARAMS; }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_check_and_load_interrupt_settings(uint8_t start_not_stopflag)
+{ uint8_t interrupt_config;
+ FixPoint1616_t threshold_low;
+ FixPoint1616_t threshold_high;
+ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ interrupt_config = Data.Pin0GpioFunctionality;
+
+ if ((interrupt_config ==
+ VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW) ||
+ (interrupt_config ==
+ VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH) ||
+ (interrupt_config ==
+ VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT)) {
+
+ status = VL53L0X_get_interrupt_thresholds(VL53L0X_DEVICEMODE_CONTINUOUS_RANGING,
+ &threshold_low, &threshold_high);
+
+ if (((threshold_low > 255 * 65536) ||
+ (threshold_high > 255 * 65536)) &&
+ (status == VL53L0X_ERROR_NONE)) {
+
+ if (start_not_stopflag != 0) {
+ status = VL53L0X_load_tuning_settings(InterruptThresholdSettings);
+ } else {
+ status |= VL53L0X_write_byte( 0xFF, 0x04);
+ status |= VL53L0X_write_byte( 0x70, 0x00);
+ status |= VL53L0X_write_byte( 0xFF, 0x00);
+ status |= VL53L0X_write_byte( 0x80, 0x00);
+ }
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_start_measurement(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ VL53L0X_DeviceModes device_mode;
+ uint8_t byte;
+ uint8_t start_stop_byte = VL53L0X_REG_SYSRANGE_MODE_START_STOP;
+ uint32_t loop_nb;
+
+
+ /* Get Current DeviceMode */
+ device_mode = CurrentParameters.DeviceMode;
+
+ status = VL53L0X_write_byte( 0x80, 0x01);
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+ status = VL53L0X_write_byte( 0x00, 0x00);
+ status = VL53L0X_write_byte( 0x91, Data.StopVariable);
+ status = VL53L0X_write_byte( 0x00, 0x01);
+ status = VL53L0X_write_byte( 0xFF, 0x00);
+ status = VL53L0X_write_byte( 0x80, 0x00);
+
+ switch (device_mode) {
+ case VL53L0X_DEVICEMODE_SINGLE_RANGING:
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSRANGE_START, 0x01);
+
+ byte = start_stop_byte;
+ if (status == VL53L0X_ERROR_NONE) {
+ /* Wait until start bit has been cleared */
+ loop_nb = 0;
+ do {
+ if (loop_nb > 0)
+ status = VL53L0X_read_byte(VL53L0X_REG_SYSRANGE_START, &byte);
+ loop_nb = loop_nb + 1;
+ } while (((byte & start_stop_byte) == start_stop_byte)
+ && (status == VL53L0X_ERROR_NONE)
+ && (loop_nb < VL53L0X_DEFAULT_MAX_LOOP));
+
+ if (loop_nb >= VL53L0X_DEFAULT_MAX_LOOP) {
+ status = VL53L0X_ERROR_TIME_OUT;
+ }
+ }
+
+ break;
+ case VL53L0X_DEVICEMODE_CONTINUOUS_RANGING: /* Back-to-back mode */
+
+ /* Check if need to apply interrupt settings */
+ if (status == VL53L0X_ERROR_NONE)
+ { status = VL53L0X_check_and_load_interrupt_settings( 1); }
+
+ status = VL53L0X_write_byte(VL53L0X_REG_SYSRANGE_START,
+ VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK);
+ if (status == VL53L0X_ERROR_NONE) {
+ /* Set PAL State to Running */
+ Data.PalState = VL53L0X_STATE_RUNNING;
+ }
+ break;
+ case VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING:
+ /* Continuous mode */
+ /* Check if need to apply interrupt settings */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_check_and_load_interrupt_settings( 1);
+ }
+
+ status = VL53L0X_write_byte(VL53L0X_REG_SYSRANGE_START,
+ VL53L0X_REG_SYSRANGE_MODE_TIMED);
+
+ if (status == VL53L0X_ERROR_NONE)/* Set PAL State to Running */
+ { Data.PalState = VL53L0X_STATE_RUNNING; }
+ break;
+ default:
+ /* Selected mode not supported */
+ status = VL53L0X_ERROR_MODE_NOT_SUPPORTED;
+ }
+
+ return status;
+}
+
+/* Group PAL Measurement Functions */
+VL53L0X_Error VL53L0X::VL53L0X_perform_single_measurement(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ VL53L0X_DeviceModes device_mode;
+
+ /* Get Current DeviceMode */
+ device_mode = CurrentParameters.DeviceMode;
+
+ /* Start immediately to run a single ranging measurement in case of
+ * single ranging or single histogram */
+ if (status == VL53L0X_ERROR_NONE && device_mode == VL53L0X_DEVICEMODE_SINGLE_RANGING) {
+ status = VL53L0X_start_measurement(); }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_measurement_poll_for_completion(); }
+
+ /* Change PAL State in case of single ranging or single histogram */
+ if (status == VL53L0X_ERROR_NONE && device_mode == VL53L0X_DEVICEMODE_SINGLE_RANGING) {
+ Data.PalState = VL53L0X_STATE_IDLE; }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_x_talk_compensation_enable(uint8_t *p_x_talk_compensation_enable)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t temp8;
+
+ temp8 = CurrentParameters.XTalkCompensationEnable ;
+ *p_x_talk_compensation_enable = temp8;
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_total_xtalk_rate(VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ FixPoint1616_t *p_total_xtalk_rate_MHz)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ uint8_t xtalk_comp_enable;
+ FixPoint1616_t total_xtalk_MHz;
+ FixPoint1616_t xtalk_per_spad_MHz;
+
+ *p_total_xtalk_rate_MHz = 0;
+
+ status = VL53L0X_get_x_talk_compensation_enable( &xtalk_comp_enable);
+ if (status == VL53L0X_ERROR_NONE) {
+
+ if (xtalk_comp_enable) {
+
+ xtalk_per_spad_MHz = CurrentParameters.XTalkCompensationRate_MHz ;
+
+ /* FixPoint1616 * FixPoint 8:8 = FixPoint0824 */
+ total_xtalk_MHz =
+ p_ranging_measurement_data->EffectiveSpadRtnCount *
+ xtalk_per_spad_MHz;
+
+ /* FixPoint0824 >> 8 = FixPoint1616 */
+ *p_total_xtalk_rate_MHz =
+ (total_xtalk_MHz + 0x80) >> 8;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_total_signal_rate(VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ FixPoint1616_t *p_total_signal_rate_MHz)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ FixPoint1616_t total_xtalk_MHz;
+
+ *p_total_signal_rate_MHz =
+ p_ranging_measurement_data->SignalRateRtn_MHz;
+
+ status = VL53L0X_get_total_xtalk_rate(p_ranging_measurement_data, &total_xtalk_MHz);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ *p_total_signal_rate_MHz += total_xtalk_MHz; }
+
+ return status;
+}
+
+/* To convert ms into register value */
+uint32_t VL53L0X::VL53L0X_calc_timeout_mclks(uint32_t timeout_period_us,
+ uint8_t vcsel_period_pclks)
+{ uint32_t macro_period_ps;
+ uint32_t macro_period_ns;
+ uint32_t timeout_period_mclks = 0;
+
+ macro_period_ps = VL53L0X_calc_macro_period_ps( vcsel_period_pclks);
+ macro_period_ns = (macro_period_ps + 500) / 1000;
+
+ timeout_period_mclks = (uint32_t)(((timeout_period_us * 1000)
+ + (macro_period_ns / 2)) / macro_period_ns);
+
+ return timeout_period_mclks;
+}
+
+uint32_t VL53L0X::VL53L0X_isqrt(uint32_t num)
+{ /* Implements an integer square root
+ * From: http://en.wikipedia.org/wiki/Methods_of_computing_square_roots */
+
+ uint32_t res = 0;
+ uint32_t bit = 1 << 30;
+ /* The second-to-top bit is set: 1 << 14 for 16-bits, 1 << 30 for 32 bits */
+
+ /* "bit" starts at the highest power of four <= the argument. */
+ while (bit > num) { bit >>= 2; }
+
+ while (bit != 0) {
+ if (num >= res + bit) {
+ num -= res + bit;
+ res = (res >> 1) + bit;
+ }
+ else { res >>= 1; }
+ bit >>= 2;
+ }
+ return res;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_calc_dmax(FixPoint1616_t total_signal_rate_MHz,
+ FixPoint1616_t total_corr_signal_rate_MHz,
+ FixPoint1616_t pw_mult,
+ uint32_t sigma_estimate_p1,
+ FixPoint1616_t sigma_estimate_p2,
+ uint32_t peak_vcsel_duration_us,
+ uint32_t *pd_max_mm)
+{ const uint32_t c_sigma_limit = 18;
+ const FixPoint1616_t c_signal_limit = 0x4000; /* 0.25 */
+ const FixPoint1616_t c_sigma_est_ref = 0x00000042; /* 0.001 */
+ const uint32_t c_amb_eff_width_sigma_est_ns = 6;
+ const uint32_t c_amb_eff_width_d_max_ns = 7;
+ uint32_t dmax_cal_range_mm;
+ FixPoint1616_t dmax_cal_signal_rate_rtn_MHz;
+ FixPoint1616_t min_signal_needed;
+ FixPoint1616_t min_signal_needed_p1;
+ FixPoint1616_t min_signal_needed_p2;
+ FixPoint1616_t min_signal_needed_p3;
+ FixPoint1616_t min_signal_needed_p4;
+ FixPoint1616_t sigma_limit_tmp;
+ FixPoint1616_t sigma_est_sq_tmp;
+ FixPoint1616_t signal_limit_tmp;
+ FixPoint1616_t signal_at0_mm;
+ FixPoint1616_t dmax_dark;
+ FixPoint1616_t dmax_ambient;
+ FixPoint1616_t dmax_dark_tmp;
+ FixPoint1616_t sigma_est_p2_tmp;
+ uint32_t signal_rate_temp_MHz;
+
+ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ dmax_cal_range_mm = Data.DmaxCalRange_mm;
+
+ dmax_cal_signal_rate_rtn_MHz = Data.DmaxCalSignalRateRtn_MHz;
+
+ /* uint32 * FixPoint1616 = FixPoint1616 */
+ signal_at0_mm = dmax_cal_range_mm * dmax_cal_signal_rate_rtn_MHz;
+
+ /* FixPoint1616 >> 8 = FixPoint2408 */
+ signal_at0_mm = (signal_at0_mm + 0x80) >> 8;
+ signal_at0_mm *= dmax_cal_range_mm;
+
+ min_signal_needed_p1 = 0;
+ if (total_corr_signal_rate_MHz > 0) {
+
+ /* Shift by 10 bits to increase resolution prior to the division */
+ signal_rate_temp_MHz = total_signal_rate_MHz << 10;
+
+ /* Add rounding value prior to division */
+ min_signal_needed_p1 = signal_rate_temp_MHz +
+ (total_corr_signal_rate_MHz / 2);
+
+ /* FixPoint0626/FixPoint1616 = FixPoint2210 */
+ min_signal_needed_p1 /= total_corr_signal_rate_MHz;
+
+ /* Apply a factored version of the speed of light.
+ Correction to be applied at the end */
+ min_signal_needed_p1 *= 3;
+
+ /* FixPoint2210 * FixPoint2210 = FixPoint1220 */
+ min_signal_needed_p1 *= min_signal_needed_p1;
+
+ /* FixPoint1220 >> 16 = FixPoint2804 */
+ min_signal_needed_p1 = (min_signal_needed_p1 + 0x8000) >> 16;
+ }
+ min_signal_needed_p2 = pw_mult * sigma_estimate_p1;
+
+ /* FixPoint1616 >> 16 = uint32 */
+ min_signal_needed_p2 = (min_signal_needed_p2 + 0x8000) >> 16;
+
+ /* uint32 * uint32 = uint32 */
+ min_signal_needed_p2 *= min_signal_needed_p2;
+
+ /* Check sigmaEstimateP2
+ * If this value is too high there is not enough signal rate
+ * to calculate dmax value so set a suitable value to ensure
+ * a very small dmax. */
+ sigma_est_p2_tmp = (sigma_estimate_p2 + 0x8000) >> 16;
+ sigma_est_p2_tmp = (sigma_est_p2_tmp + c_amb_eff_width_sigma_est_ns / 2) /
+ c_amb_eff_width_sigma_est_ns;
+ sigma_est_p2_tmp *= c_amb_eff_width_d_max_ns;
+
+ if (sigma_est_p2_tmp > 0xffff) {
+ min_signal_needed_p3 = 0xfff00000;
+ } else {
+ /* DMAX uses a different ambient width from sigma, so apply correction.
+ * Perform division before multiplication to prevent overflow. */
+ sigma_estimate_p2 = (sigma_estimate_p2 + c_amb_eff_width_sigma_est_ns / 2) /
+ c_amb_eff_width_sigma_est_ns;
+ sigma_estimate_p2 *= c_amb_eff_width_d_max_ns;
+
+ /* FixPoint1616 >> 16 = uint32 */
+ min_signal_needed_p3 = (sigma_estimate_p2 + 0x8000) >> 16;
+ min_signal_needed_p3 *= min_signal_needed_p3;
+ }
+
+ /* FixPoint1814 / uint32 = FixPoint1814 */
+ sigma_limit_tmp = ((c_sigma_limit << 14) + 500) / 1000;
+
+ /* FixPoint1814 * FixPoint1814 = FixPoint3628 := FixPoint0428 */
+ sigma_limit_tmp *= sigma_limit_tmp;
+
+ /* FixPoint1616 * FixPoint1616 = FixPoint3232 */
+ sigma_est_sq_tmp = c_sigma_est_ref * c_sigma_est_ref;
+
+ /* FixPoint3232 >> 4 = FixPoint0428 */
+ sigma_est_sq_tmp = (sigma_est_sq_tmp + 0x08) >> 4;
+
+ /* FixPoint0428 - FixPoint0428 = FixPoint0428 */
+ sigma_limit_tmp -= sigma_est_sq_tmp;
+
+ /* uint32_t * FixPoint0428 = FixPoint0428 */
+ min_signal_needed_p4 = 4 * 12 * sigma_limit_tmp;
+
+ /* FixPoint0428 >> 14 = FixPoint1814 */
+ min_signal_needed_p4 = (min_signal_needed_p4 + 0x2000) >> 14;
+
+ /* uint32 + uint32 = uint32 */
+ min_signal_needed = (min_signal_needed_p2 + min_signal_needed_p3);
+
+ /* uint32 / uint32 = uint32 */
+ min_signal_needed += (peak_vcsel_duration_us / 2);
+ min_signal_needed /= peak_vcsel_duration_us;
+
+ /* uint32 << 14 = FixPoint1814 */
+ min_signal_needed <<= 14;
+
+ /* FixPoint1814 / FixPoint1814 = uint32 */
+ min_signal_needed += (min_signal_needed_p4 / 2);
+ min_signal_needed /= min_signal_needed_p4;
+
+ /* FixPoint3200 * FixPoint2804 := FixPoint2804*/
+ min_signal_needed *= min_signal_needed_p1;
+
+ /* Apply correction by dividing by 1000000.
+ * This assumes 10E16 on the numerator of the equation
+ * and 10E-22 on the denominator.
+ * We do this because 32bit fix point calculation can't
+ * handle the larger and smaller elements of this equation,
+ * i.e. speed of light and pulse widths.
+ */
+ min_signal_needed = (min_signal_needed + 500) / 1000;
+ min_signal_needed <<= 4;
+
+ min_signal_needed = (min_signal_needed + 500) / 1000;
+
+ /* FixPoint1616 >> 8 = FixPoint2408 */
+ signal_limit_tmp = (c_signal_limit + 0x80) >> 8;
+
+ /* FixPoint2408/FixPoint2408 = uint32 */
+ if (signal_limit_tmp != 0) {
+ dmax_dark_tmp = (signal_at0_mm + (signal_limit_tmp / 2))
+ / signal_limit_tmp;
+ } else { dmax_dark_tmp = 0; }
+
+ dmax_dark = VL53L0X_isqrt(dmax_dark_tmp);
+
+ /* FixPoint2408/FixPoint2408 = uint32 */
+ if (min_signal_needed != 0) {
+ dmax_ambient = (signal_at0_mm + min_signal_needed / 2)
+ / min_signal_needed;
+ } else { dmax_ambient = 0; }
+
+ dmax_ambient = VL53L0X_isqrt(dmax_ambient);
+
+ *pd_max_mm = dmax_dark;
+ if (dmax_dark > dmax_ambient) { *pd_max_mm = dmax_ambient; }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_calc_sigma_estimate(VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ FixPoint1616_t *p_sigma_estimate, uint32_t *p_dmax_mm)
+{ /* Expressed in 100ths of a ns, i.e. centi-ns */
+ const uint32_t c_pulse_effective_width_centi_ns = 800;
+ /* Expressed in 100ths of a ns, i.e. centi-ns */
+ const uint32_t c_ambient_effective_width_centi_ns = 600;
+ const FixPoint1616_t c_dflt_final_range_integration_time_milli_secs = 0x00190000; /* 25ms */
+ const uint32_t c_vcsel_pulse_width_ps = 4700; /* pico secs */
+ const FixPoint1616_t c_sigma_est_max = 0x028F87AE;
+ const FixPoint1616_t c_sigma_est_rtn_max = 0xF000;
+ const FixPoint1616_t c_amb_to_signal_ratio_max = 0xF0000000 /
+ c_ambient_effective_width_centi_ns;
+ /* Time Of Flight per mm (6.6 pico secs) */
+ const FixPoint1616_t c_tof_per_mm_ps = 0x0006999A;
+ const uint32_t c_16bit_rounding_param = 0x00008000;
+ const FixPoint1616_t c_max_x_talk_kcps = 0x00320000;
+ const uint32_t c_pll_period_ps = 1655;
+
+ uint32_t vcsel_total_events_rtn;
+ uint32_t final_range_timeout_micro_secs;
+ uint32_t pre_range_timeout_micro_secs;
+ uint32_t final_range_integration_time_milli_secs;
+ FixPoint1616_t sigma_estimate_p1;
+ FixPoint1616_t sigma_estimate_p2;
+ FixPoint1616_t sigma_estimate_p3;
+ FixPoint1616_t delta_t_ps;
+ FixPoint1616_t pw_mult;
+ FixPoint1616_t sigma_est_rtn;
+ FixPoint1616_t sigma_estimate;
+ FixPoint1616_t x_talk_correction;
+ FixPoint1616_t ambient_rate_kcps;
+ FixPoint1616_t peak_signal_rate_kcps;
+ FixPoint1616_t x_talk_comp_rate_MHz;
+ uint32_t x_talk_comp_rate_kcps;
+ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ FixPoint1616_t diff1_MHz;
+ FixPoint1616_t diff2_MHz;
+ FixPoint1616_t sqr1;
+ FixPoint1616_t sqr2;
+ FixPoint1616_t sqr_sum;
+ FixPoint1616_t sqrt_result_centi_ns;
+ FixPoint1616_t sqrt_result;
+ FixPoint1616_t total_signal_rate_MHz;
+ FixPoint1616_t corrected_signal_rate_MHz;
+ FixPoint1616_t sigma_est_ref;
+ uint32_t vcsel_width;
+ uint32_t final_range_macro_pclks;
+ uint32_t pre_range_macro_pclks;
+ uint32_t peak_vcsel_duration_us;
+ uint8_t final_range_vcsel_pclks;
+ uint8_t pre_range_vcsel_pclks;
+ /*! \addtogroup calc_sigma_estimate
+ * @{
+ *
+ * Estimates the range sigma
+ */
+
+ x_talk_comp_rate_MHz = CurrentParameters.XTalkCompensationRate_MHz ;
+
+ /*
+ * We work in kcps rather than MHz as this helps keep within the
+ * confines of the 32 Fix1616 type.
+ */
+
+ ambient_rate_kcps = (p_ranging_measurement_data->AmbientRateRtn_MHz * 1000) >> 16;
+
+ corrected_signal_rate_MHz = p_ranging_measurement_data->SignalRateRtn_MHz;
+
+ status = VL53L0X_get_total_signal_rate(p_ranging_measurement_data, &total_signal_rate_MHz);
+ status = VL53L0X_get_total_xtalk_rate(p_ranging_measurement_data, &x_talk_comp_rate_MHz);
+
+ /* Signal rate measurement provided by device is the
+ * peak signal rate, not average.
+ */
+ peak_signal_rate_kcps = (total_signal_rate_MHz * 1000);
+ peak_signal_rate_kcps = (peak_signal_rate_kcps + 0x8000) >> 16;
+
+ x_talk_comp_rate_kcps = x_talk_comp_rate_MHz * 1000;
+
+ if (x_talk_comp_rate_kcps > c_max_x_talk_kcps) {
+ x_talk_comp_rate_kcps = c_max_x_talk_kcps;
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+
+ /* Calculate final range macro periods */
+ final_range_timeout_micro_secs = Data.FinalRangeTimeout_us;
+ final_range_vcsel_pclks = Data.FinalRangeVcselPulsePeriod;
+ final_range_macro_pclks = VL53L0X_calc_timeout_mclks( final_range_timeout_micro_secs, final_range_vcsel_pclks);
+
+ /* Calculate pre-range macro periods */
+ pre_range_timeout_micro_secs = Data.PreRangeTimeout_us;
+ pre_range_vcsel_pclks = Data.PreRangeVcselPulsePeriod;
+
+ pre_range_macro_pclks = VL53L0X_calc_timeout_mclks(pre_range_timeout_micro_secs, pre_range_vcsel_pclks);
+
+ vcsel_width = 3;
+ if (final_range_vcsel_pclks == 8) {
+ vcsel_width = 2;
+ }
+
+ peak_vcsel_duration_us = vcsel_width * 2048 *
+ (pre_range_macro_pclks + final_range_macro_pclks);
+ peak_vcsel_duration_us = (peak_vcsel_duration_us + 500) / 1000;
+ peak_vcsel_duration_us *= c_pll_period_ps;
+ peak_vcsel_duration_us = (peak_vcsel_duration_us + 500) / 1000;
+
+ /* Fix1616 >> 8 = Fix2408 */
+ total_signal_rate_MHz = (total_signal_rate_MHz + 0x80) >> 8;
+
+ /* Fix2408 * uint32 = Fix2408 */
+ vcsel_total_events_rtn = total_signal_rate_MHz *
+ peak_vcsel_duration_us;
+
+ /* Fix2408 >> 8 = uint32 */
+ vcsel_total_events_rtn = (vcsel_total_events_rtn + 0x80) >> 8;
+
+ /* Fix2408 << 8 = Fix1616 = */
+ total_signal_rate_MHz <<= 8;
+ }
+
+ if (status != VL53L0X_ERROR_NONE) { return status; }
+
+ if (peak_signal_rate_kcps == 0) {
+ *p_sigma_estimate = c_sigma_est_max;
+ p_ranging_measurement_data->SigmaEstimate = c_sigma_est_max;
+ *p_dmax_mm = 0;
+ } else {
+ if (vcsel_total_events_rtn < 1) { vcsel_total_events_rtn = 1; }
+
+ sigma_estimate_p1 = c_pulse_effective_width_centi_ns;
+
+ /* ((FixPoint1616 << 16)* uint32)/uint32 = FixPoint1616 */
+ sigma_estimate_p2 = (ambient_rate_kcps << 16) / peak_signal_rate_kcps;
+ if (sigma_estimate_p2 > c_amb_to_signal_ratio_max) {
+ /* Clip to prevent overflow. Will ensure safe
+ * max result. */
+ sigma_estimate_p2 = c_amb_to_signal_ratio_max;
+ }
+ sigma_estimate_p2 *= c_ambient_effective_width_centi_ns;
+
+ sigma_estimate_p3 = 2 * VL53L0X_isqrt(vcsel_total_events_rtn * 12);
+
+ /* uint32 * FixPoint1616 = FixPoint1616 */
+ delta_t_ps = p_ranging_measurement_data->Range_mm * c_tof_per_mm_ps;
+
+ /* vcselRate - xtalkCompRate
+ * (uint32 << 16) - FixPoint1616 = FixPoint1616.
+ * Divide result by 1000 to convert to MHz.
+ * 500 is added to ensure rounding when integer division truncates. */
+ diff1_MHz = (((peak_signal_rate_kcps << 16) -
+ 2 * x_talk_comp_rate_kcps) + 500) / 1000;
+
+ /* vcselRate + xtalkCompRate */
+ diff2_MHz = ((peak_signal_rate_kcps << 16) + 500) / 1000;
+
+ /* Shift by 8 bits to increase resolution prior to the division */
+ diff1_MHz <<= 8;
+
+ /* FixPoint0824/FixPoint1616 = FixPoint2408 */
+ x_talk_correction = diff1_MHz / diff2_MHz;
+
+ /* FixPoint2408 << 8 = FixPoint1616 */
+ x_talk_correction <<= 8;
+
+ if (p_ranging_measurement_data->RangeStatus != 0) {
+ pw_mult = 1 << 16;
+ } else {
+ /* FixPoint1616/uint32 = FixPoint1616 */
+ pw_mult = delta_t_ps / c_vcsel_pulse_width_ps; /* smaller than 1.0f */
+
+ /* FixPoint1616 * FixPoint1616 = FixPoint3232, however both
+ * values are small enough such that32 bits will not be exceeded. */
+ pw_mult *= ((1 << 16) - x_talk_correction);
+
+ /* (FixPoint3232 >> 16) = FixPoint1616 */
+ pw_mult = (pw_mult + c_16bit_rounding_param) >> 16;
+
+ /* FixPoint1616 + FixPoint1616 = FixPoint1616 */
+ pw_mult += (1 << 16);
+
+ /* At this point the value will be 1.xx, therefore if we square
+ * the value this will exceed 32 bits. To address this perform
+ * a single shift to the right before the multiplication. */
+ pw_mult >>= 1;
+ /* FixPoint1715 * FixPoint1715 = FixPoint3430 */
+ pw_mult = pw_mult * pw_mult;
+
+ /* (FixPoint3430 >> 14) = Fix1616 */
+ pw_mult >>= 14;
+ }
+
+ /* FixPoint1616 * uint32 = FixPoint1616 */
+ sqr1 = pw_mult * sigma_estimate_p1;
+
+ /* (FixPoint1616 >> 16) = FixPoint3200 */
+ sqr1 = (sqr1 + 0x8000) >> 16;
+
+ /* FixPoint3200 * FixPoint3200 = FixPoint6400 */
+ sqr1 *= sqr1;
+
+ sqr2 = sigma_estimate_p2;
+
+ /* (FixPoint1616 >> 16) = FixPoint3200 */
+ sqr2 = (sqr2 + 0x8000) >> 16;
+
+ /* FixPoint3200 * FixPoint3200 = FixPoint6400 */
+ sqr2 *= sqr2;
+
+ /* FixPoint64000 + FixPoint6400 = FixPoint6400 */
+ sqr_sum = sqr1 + sqr2;
+
+ /* SQRT(FixPoin6400) = FixPoint3200 */
+ sqrt_result_centi_ns = VL53L0X_isqrt(sqr_sum);
+
+ /* (FixPoint3200 << 16) = FixPoint1616 */
+ sqrt_result_centi_ns <<= 16;
+
+ /* Note that the Speed Of Light is expressed in um per 1E-10
+ * seconds (2997) Therefore to get mm/ns we have to divide by
+ * 10000
+ */
+ sigma_est_rtn = (((sqrt_result_centi_ns + 50) / 100) /
+ sigma_estimate_p3);
+ sigma_est_rtn *= VL53L0X_SPEED_OF_LIGHT_IN_AIR;
+
+ /* Add 5000 before dividing by 10000 to ensure rounding. */
+ sigma_est_rtn += 5000;
+ sigma_est_rtn /= 10000;
+
+ if (sigma_est_rtn > c_sigma_est_rtn_max) {
+ /* Clip to prevent overflow. Will ensure safe
+ * max result. */
+ sigma_est_rtn = c_sigma_est_rtn_max;
+ }
+ final_range_integration_time_milli_secs =
+ (final_range_timeout_micro_secs + pre_range_timeout_micro_secs + 500) / 1000;
+
+ /* sigmaEstRef = 1mm * 25ms/final range integration time (inc pre-range)
+ * sqrt(FixPoint1616/int) = FixPoint2408)
+ */
+ sigma_est_ref =
+ VL53L0X_isqrt((c_dflt_final_range_integration_time_milli_secs +
+ final_range_integration_time_milli_secs / 2) /
+ final_range_integration_time_milli_secs);
+
+ /* FixPoint2408 << 8 = FixPoint1616 */
+ sigma_est_ref <<= 8;
+ sigma_est_ref = (sigma_est_ref + 500) / 1000;
+
+ /* FixPoint1616 * FixPoint1616 = FixPoint3232 */
+ sqr1 = sigma_est_rtn * sigma_est_rtn;
+ /* FixPoint1616 * FixPoint1616 = FixPoint3232 */
+ sqr2 = sigma_est_ref * sigma_est_ref;
+
+ /* sqrt(FixPoint3232) = FixPoint1616 */
+ sqrt_result = VL53L0X_isqrt((sqr1 + sqr2));
+ /*
+ * Note that the Shift by 4 bits increases resolution prior to
+ * the sqrt, therefore the result must be shifted by 2 bits to
+ * the right to revert back to the FixPoint1616 format.
+ */
+
+ sigma_estimate = 1000 * sqrt_result;
+
+ if ((peak_signal_rate_kcps < 1) || (vcsel_total_events_rtn < 1) ||
+ (sigma_estimate > c_sigma_est_max)) {
+ sigma_estimate = c_sigma_est_max;
+ }
+
+ *p_sigma_estimate = (uint32_t)(sigma_estimate);
+ p_ranging_measurement_data->SigmaEstimate = *p_sigma_estimate;
+ status = VL53L0X_calc_dmax(total_signal_rate_MHz,
+ corrected_signal_rate_MHz,
+ pw_mult,
+ sigma_estimate_p1,
+ sigma_estimate_p2,
+ peak_vcsel_duration_us,
+ p_dmax_mm);
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_pal_range_status(uint8_t device_range_status,
+ FixPoint1616_t signal_rate,
+ uint16_t effective_spad_rtn_count,
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ uint8_t *p_pal_range_status)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t none_flag;
+ uint8_t sigma_limitflag = 0;
+ uint8_t signal_ref_clipflag = 0;
+ uint8_t range_ignore_thresholdflag = 0;
+ uint8_t sigma_limit_check_enable = 0;
+ uint8_t signal_rate_final_range_limit_check_enable = 0;
+ uint8_t signal_ref_clip_limit_check_enable = 0;
+ uint8_t range_ignore_threshold_limit_check_enable = 0;
+ FixPoint1616_t sigma_estimate;
+ FixPoint1616_t sigma_limit_value;
+ FixPoint1616_t signal_ref_clip_value;
+ FixPoint1616_t range_ignore_threshold_value;
+ FixPoint1616_t signal_rate_per_spad;
+ uint8_t device_range_status_internal = 0;
+ uint16_t tmp_word = 0;
+ uint8_t temp8;
+ uint32_t dmax_mm = 0;
+ FixPoint1616_t last_signal_ref_MHz;
+
+ /* VL53L0X has a good ranging when the value of the
+ * DeviceRangeStatus = 11. This function will replace the value 0 with
+ * the value 11 in the DeviceRangeStatus.
+ * In addition, the SigmaEstimator is not included in the VL53L0X
+ * DeviceRangeStatus, this will be added in the PalRangeStatus. */
+
+ device_range_status_internal = ((device_range_status & 0x78) >> 3);
+
+ if (device_range_status_internal == 0 ||
+ device_range_status_internal == 5 ||
+ device_range_status_internal == 7 ||
+ device_range_status_internal == 12 ||
+ device_range_status_internal == 13 ||
+ device_range_status_internal == 14 ||
+ device_range_status_internal == 15
+ ) {
+ none_flag = 1;
+ } else {
+ none_flag = 0;
+ }
+
+ /* Check if Sigma limit is enabled, if yes then do comparison with limit
+ * value and put the result back into pPalRangeStatus. */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_limit_check_enable(VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE,
+ &sigma_limit_check_enable);
+ }
+
+ if ((sigma_limit_check_enable != 0) && (status == VL53L0X_ERROR_NONE)) {
+ /* compute the Sigma and check with limit */
+ status = VL53L0X_calc_sigma_estimate(p_ranging_measurement_data, &sigma_estimate, &dmax_mm);
+ if (status == VL53L0X_ERROR_NONE) { p_ranging_measurement_data->RangeDMax_mm = dmax_mm; }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_limit_check_value(VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE,
+ &sigma_limit_value);
+
+ if ((sigma_limit_value > 0) && (sigma_estimate > sigma_limit_value))
+ { sigma_limitflag = 1; } /* Limit Fail */
+ }
+ }
+
+ /* Check if Signal ref clip limit is enabled, if yes then do comparison
+ * with limit value and put the result back into pPalRangeStatus. */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_limit_check_enable(VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP,
+ &signal_ref_clip_limit_check_enable);
+ }
+
+ if ((signal_ref_clip_limit_check_enable != 0) &&
+ (status == VL53L0X_ERROR_NONE)) {
+
+ status = VL53L0X_get_limit_check_value(VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP,
+ &signal_ref_clip_value);
+
+ /* Read LastSignalRef_MHz from device */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word(VL53L0X_REG_RESULT_PEAK_SIGNAL_RATE_REF,
+ &tmp_word);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x00);
+ }
+
+ last_signal_ref_MHz = VL53L0X_FP97TOFP1616(tmp_word);
+ Data.LastSignalRef_MHz = last_signal_ref_MHz;
+
+ if ((signal_ref_clip_value > 0) &&
+ (last_signal_ref_MHz > signal_ref_clip_value)) {
+ /* Limit Fail */
+ signal_ref_clipflag = 1;
+ }
+ }
+
+ /*
+ * Check if Signal ref clip limit is enabled, if yes then do comparison
+ * with limit value and put the result back into pPalRangeStatus.
+ * EffectiveSpadRtnCount has a format 8.8
+ * If (Return signal rate < (1.5 x Xtalk x number of Spads)) : FAIL
+ */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_limit_check_enable(VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD,
+ &range_ignore_threshold_limit_check_enable);
+ }
+
+ if ((range_ignore_threshold_limit_check_enable != 0) &&
+ (status == VL53L0X_ERROR_NONE)) {
+
+ /* Compute the signal rate per spad */
+ if (effective_spad_rtn_count == 0) {
+ signal_rate_per_spad = 0;
+ } else {
+ signal_rate_per_spad = (FixPoint1616_t)((256 * signal_rate)
+ / effective_spad_rtn_count);
+ }
+
+ status = VL53L0X_get_limit_check_value(VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD,
+ &range_ignore_threshold_value);
+
+ if ((range_ignore_threshold_value > 0) &&
+ (signal_rate_per_spad < range_ignore_threshold_value)) {
+ /* Limit Fail add 2^6 to range status */
+ range_ignore_thresholdflag = 1;
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (none_flag == 1) {
+ *p_pal_range_status = 255; /* NONE */
+ } else if (device_range_status_internal == 1 ||
+ device_range_status_internal == 2 ||
+ device_range_status_internal == 3) {
+ *p_pal_range_status = 5; /* HW fail */
+ } else if (device_range_status_internal == 6 ||
+ device_range_status_internal == 9) {
+ *p_pal_range_status = 4; /* Phase fail */
+ } else if (device_range_status_internal == 8 ||
+ device_range_status_internal == 10 ||
+ signal_ref_clipflag == 1) {
+ *p_pal_range_status = 3; /* Min range */
+ } else if (device_range_status_internal == 4 ||
+ range_ignore_thresholdflag == 1) {
+ *p_pal_range_status = 2; /* Signal Fail */
+ } else if (sigma_limitflag == 1) {
+ *p_pal_range_status = 1; /* Sigma Fail */
+ } else {
+ *p_pal_range_status = 0; /* Range Valid */
+ }
+ }
+
+ /* DMAX only relevant during range error */
+ if (*p_pal_range_status == 0) {
+ p_ranging_measurement_data->RangeDMax_mm = 0;
+ }
+
+ /* fill the Limit Check Status */
+
+ status = VL53L0X_get_limit_check_enable(VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE,
+ &signal_rate_final_range_limit_check_enable);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if ((sigma_limit_check_enable == 0) || (sigma_limitflag == 1)) {
+ temp8 = 1;
+ } else {
+ temp8 = 0;
+ }
+ CurrentParameters.LimitChecksStatus[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] = temp8;
+
+ if ((device_range_status_internal == 4) ||
+ (signal_rate_final_range_limit_check_enable == 0)) {
+ temp8 = 1;
+ } else {
+ temp8 = 0;
+ }
+ CurrentParameters.LimitChecksStatus[VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE] = temp8;
+
+ if ((signal_ref_clip_limit_check_enable == 0) ||
+ (signal_ref_clipflag == 1)) {
+ temp8 = 1;
+ } else {
+ temp8 = 0;
+ }
+
+ CurrentParameters.LimitChecksStatus[VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP] = temp8;
+
+ if ((range_ignore_threshold_limit_check_enable == 0) ||
+ (range_ignore_thresholdflag == 1)) {
+ temp8 = 1;
+ } else {
+ temp8 = 0;
+ }
+
+ CurrentParameters.LimitChecksStatus[VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD] = temp8;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_ranging_measurement_data(VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t device_range_status;
+ uint8_t range_fractional_enable;
+ uint8_t pal_range_status;
+ uint8_t x_talk_compensation_enable;
+ uint16_t ambient_rate;
+ FixPoint1616_t signal_rate;
+ uint16_t x_talk_compensation_rate_MHz;
+ uint16_t effective_spad_rtn_count;
+ uint16_t tmpuint16;
+ uint16_t xtalk_range_milli_meter;
+ uint16_t linearity_corrective_gain;
+ uint8_t localBuffer[12];
+
+ /* use multi read even if some registers are not useful, result will
+ * be more efficient start reading at 0x14 dec20
+ * end reading at 0x21 dec33 total 14 bytes to read */
+ status = VL53L0X_read_multi( 0x14, localBuffer, 12);
+
+ if (status == VL53L0X_ERROR_NONE) {
+
+ tmpuint16 = VL53L0X_MAKEUINT16(localBuffer[11], localBuffer[10]);
+ /* cut1.1 if SYSTEM__RANGE_CONFIG if 1 range is 2bits fractional
+ *(format 11.2) else no fractional */
+
+ signal_rate = VL53L0X_FP97TOFP1616(VL53L0X_MAKEUINT16(localBuffer[7], localBuffer[6]));
+ /* peak_signal_count_rate_rtn_MHz */
+ p_ranging_measurement_data->SignalRateRtn_MHz = signal_rate;
+
+ ambient_rate = VL53L0X_MAKEUINT16(localBuffer[9], localBuffer[8]);
+ p_ranging_measurement_data->AmbientRateRtn_MHz =
+ VL53L0X_FP97TOFP1616(ambient_rate);
+
+ effective_spad_rtn_count = VL53L0X_MAKEUINT16(localBuffer[3],
+ localBuffer[2]);
+ /* EffectiveSpadRtnCount is 8.8 format */
+ p_ranging_measurement_data->EffectiveSpadRtnCount =
+ effective_spad_rtn_count;
+
+ device_range_status = localBuffer[0];
+
+ /* Get Linearity Corrective Gain */
+ linearity_corrective_gain = Data.LinearityCorrectiveGain;
+
+ /* Get ranging configuration */
+ range_fractional_enable = Data.RangeFractionalEnable;
+
+ if (linearity_corrective_gain != 1000) {
+
+ tmpuint16 = (uint16_t)((linearity_corrective_gain * tmpuint16 + 500) / 1000);
+
+ /* Implement Xtalk */
+ x_talk_compensation_rate_MHz = CurrentParameters.XTalkCompensationRate_MHz ;
+ x_talk_compensation_enable = CurrentParameters.XTalkCompensationEnable ;
+
+ if (x_talk_compensation_enable) {
+
+ if ((signal_rate
+ - ((x_talk_compensation_rate_MHz
+ * effective_spad_rtn_count) >> 8))
+ <= 0) {
+ if (range_fractional_enable) {
+ xtalk_range_milli_meter = 8888;
+ } else {
+ xtalk_range_milli_meter = 8888 << 2;
+ }
+ } else {
+ xtalk_range_milli_meter =
+ (tmpuint16 * signal_rate)
+ / (signal_rate
+ - ((x_talk_compensation_rate_MHz
+ * effective_spad_rtn_count)
+ >> 8));
+ }
+ tmpuint16 = xtalk_range_milli_meter;
+ }
+ }
+
+ if (range_fractional_enable) {
+ p_ranging_measurement_data->Range_mm =
+ (uint16_t)((tmpuint16) >> 2);
+ p_ranging_measurement_data->RangeFractionalPart =
+ (uint8_t)((tmpuint16 & 0x03) << 6);
+ } else {
+ p_ranging_measurement_data->Range_mm = tmpuint16;
+ p_ranging_measurement_data->RangeFractionalPart = 0;
+ }
+
+ /* For a standard definition of RangeStatus, this should
+ * return 0 in case of good result after a ranging
+ * The range status depends on the device so call a device
+ * specific function to obtain the right Status.
+ */
+ status |= VL53L0X_get_pal_range_status( device_range_status,
+ signal_rate, effective_spad_rtn_count,
+ p_ranging_measurement_data, &pal_range_status);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ p_ranging_measurement_data->RangeStatus = pal_range_status;}
+
+ }
+
+ if (status == VL53L0X_ERROR_NONE) { /* Copy last read data into Device buffer */
+ LastRangeMeasure.Range_mm = p_ranging_measurement_data->Range_mm;
+ LastRangeMeasure.RangeFractionalPart = p_ranging_measurement_data->RangeFractionalPart;
+ LastRangeMeasure.RangeDMax_mm = p_ranging_measurement_data->RangeDMax_mm;
+ LastRangeMeasure.SignalRateRtn_MHz = p_ranging_measurement_data->SignalRateRtn_MHz;
+ LastRangeMeasure.AmbientRateRtn_MHz = p_ranging_measurement_data->AmbientRateRtn_MHz;
+ LastRangeMeasure.EffectiveSpadRtnCount = p_ranging_measurement_data->EffectiveSpadRtnCount;
+ LastRangeMeasure.RangeStatus = p_ranging_measurement_data->RangeStatus;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_single_ranging_measurement(VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ /* This function will do a complete single ranging
+ * Here we fix the mode! */
+ CurrentParameters.DeviceMode = VL53L0X_DEVICEMODE_SINGLE_RANGING;
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_single_measurement(); }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_ranging_measurement_data(p_ranging_measurement_data); }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_clear_interrupt_mask( 0);}
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::perform_ref_signal_measurement(uint16_t *p_ref_signal_rate)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ VL53L0X_RangingMeasurementData_t ranging_measurement_data;
+
+ uint8_t sequence_config = 0;
+
+ /* store the value of the sequence config,
+ * this will be reset before the end of the function*/
+ sequence_config = Data.SequenceConfig;
+
+ /*
+ * This function performs a reference signal rate measurement.
+ */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, 0xC0);}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_single_ranging_measurement(&ranging_measurement_data); }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x01); }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word(VL53L0X_REG_RESULT_PEAK_SIGNAL_RATE_REF,
+ p_ref_signal_rate);}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x00);}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ /* restore the previous Sequence Config */
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG,
+ sequence_config);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = sequence_config;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::wrapped_VL53L0X_perform_ref_spad_management(uint32_t *ref_spad_count,
+ uint8_t *is_aperture_spads)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t last_spad_array[6];
+ uint8_t start_select = 0xB4;
+ uint32_t minimum_spad_count = 3;
+ uint32_t max_spad_count = 44;
+ uint32_t current_spad_index = 0;
+ uint32_t last_spad_index = 0;
+ int32_t next_good_spad = 0;
+ uint16_t target_ref_rate = 0x0A00; /* 20 MHz in 9:7 format */
+ uint16_t peak_signal_rate_ref;
+ uint32_t need_apt_spads = 0;
+ uint32_t index = 0;
+ uint32_t spad_array_size = 6;
+ uint32_t signal_rate_diff = 0;
+ uint32_t last_signal_rate_diff = 0;
+ uint8_t complete = 0;
+ uint8_t vhv_settings = 0;
+ uint8_t phase_cal = 0;
+ uint32_t ref_spad_count_int = 0;
+ uint8_t is_aperture_spads_int = 0;
+
+ /*
+ * The reference SPAD initialization procedure determines the minimum
+ * amount of reference spads to be enables to achieve a target reference
+ * signal rate and should be performed once during initialization.
+ *
+ * Either aperture or non-aperture spads are applied but never both.
+ * Firstly non-aperture spads are set, begining with 5 spads, and
+ * increased one spad at a time until the closest measurement to the
+ * target rate is achieved.
+ *
+ * If the target rate is exceeded when 5 non-aperture spads are enabled,
+ * initialization is performed instead with aperture spads.
+ *
+ * When setting spads, a 'Good Spad Map' is applied.
+ *
+ * This procedure operates within a SPAD window of interest of a maximum
+ * 44 spads.
+ * The start point is currently fixed to 180, which lies towards the end
+ * of the non-aperture quadrant and runs in to the adjacent aperture
+ * quadrant.
+ */
+ target_ref_rate = Data.targetRefRate;
+
+ /*
+ * Initialize Spad arrays.
+ * Currently the good spad map is initialised to 'All good'.
+ * This is a short term implementation. The good spad map will be
+ * provided as an input.
+ * Note that there are 6 bytes. Only the first 44 bits will be used to
+ * represent spads.
+ */
+ for (index = 0; index < spad_array_size; index++) {
+ Data.RefSpadEnables[index] = 0;
+ }
+
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_DYNAMIC_SPAD_REF_EN_START_OFFSET, 0x00);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD, 0x2C);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x00);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_GLOBAL_CONFIG_REF_EN_START_SELECT,
+ start_select);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_POWER_MANAGEMENT_GO1_POWER_FORCE, 0);
+ }
+
+ /* Perform ref calibration */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_perform_ref_calibration( &vhv_settings,
+ &phase_cal, 0);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ /* Enable Minimum NON-APERTURE Spads */
+ current_spad_index = 0;
+ last_spad_index = current_spad_index;
+ need_apt_spads = 0;
+ status = enable_ref_spads(need_apt_spads,
+ Data.RefGoodSpadMap,
+ Data.RefSpadEnables,
+ spad_array_size,
+ start_select,
+ current_spad_index,
+ minimum_spad_count,
+ &last_spad_index);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ current_spad_index = last_spad_index;
+
+ status = perform_ref_signal_measurement(&peak_signal_rate_ref);
+ if ((status == VL53L0X_ERROR_NONE) &&
+ (peak_signal_rate_ref > target_ref_rate)) {
+ /* Signal rate measurement too high,
+ * switch to APERTURE SPADs */
+
+ for (index = 0; index < spad_array_size; index++) {
+ Data.RefSpadEnables[index] = 0;
+ }
+
+ /* Increment to the first APERTURE spad */
+ while ((is_aperture(start_select + current_spad_index)
+ == 0) && (current_spad_index < max_spad_count)) {
+ current_spad_index++;
+ }
+
+ need_apt_spads = 1;
+
+ status = enable_ref_spads(need_apt_spads,
+ Data.RefGoodSpadMap,
+ Data.RefSpadEnables,
+ spad_array_size,
+ start_select,
+ current_spad_index,
+ minimum_spad_count,
+ &last_spad_index);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ current_spad_index = last_spad_index;
+ status = perform_ref_signal_measurement(&peak_signal_rate_ref);
+
+ if ((status == VL53L0X_ERROR_NONE) &&
+ (peak_signal_rate_ref > target_ref_rate)) {
+ /* Signal rate still too high after
+ * setting the minimum number of
+ * APERTURE spads. Can do no more
+ * therefore set the min number of
+ * aperture spads as the result.
+ */
+ is_aperture_spads_int = 1;
+ ref_spad_count_int = minimum_spad_count;
+ }
+ }
+ } else {
+ need_apt_spads = 0;
+ }
+ }
+
+ if ((status == VL53L0X_ERROR_NONE) &&
+ (peak_signal_rate_ref < target_ref_rate)) {
+ /* At this point, the minimum number of either aperture
+ * or non-aperture spads have been set. Proceed to add
+ * spads and perform measurements until the target
+ * reference is reached.
+ */
+ is_aperture_spads_int = need_apt_spads;
+ ref_spad_count_int = minimum_spad_count;
+
+ memcpy(last_spad_array, Data.RefSpadEnables,
+ spad_array_size);
+ last_signal_rate_diff = abs(peak_signal_rate_ref -
+ target_ref_rate);
+ complete = 0;
+
+ while (!complete) {
+ get_next_good_spad(Data.RefGoodSpadMap,
+ spad_array_size, current_spad_index,
+ &next_good_spad);
+
+ if (next_good_spad == -1) {
+ status = VL53L0X_ERROR_REF_SPAD_INIT;
+ break;
+ }
+
+ /* Cannot combine Aperture and Non-Aperture spads, so
+ * ensure the current spad is of the correct type.
+ */
+ if (is_aperture((uint32_t)start_select + next_good_spad) !=
+ need_apt_spads) {
+ /* At this point we have enabled the maximum
+ * number of Aperture spads.
+ */
+ complete = 1;
+ break;
+ }
+
+ (ref_spad_count_int)++;
+
+ current_spad_index = next_good_spad;
+ status = enable_spad_bit(Data.RefSpadEnables,
+ spad_array_size, current_spad_index);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ current_spad_index++;
+ /* Proceed to apply the additional spad and
+ * perform measurement. */
+ status = set_ref_spad_map(Data.RefSpadEnables);
+ }
+
+ if (status != VL53L0X_ERROR_NONE) {
+ break;
+ }
+
+ status = perform_ref_signal_measurement(&peak_signal_rate_ref);
+
+ if (status != VL53L0X_ERROR_NONE) {
+ break;
+ }
+
+ signal_rate_diff = abs(peak_signal_rate_ref - target_ref_rate);
+
+ if (peak_signal_rate_ref > target_ref_rate) {
+ /* Select the spad map that provides the
+ * measurement closest to the target rate,
+ * either above or below it.
+ */
+ if (signal_rate_diff > last_signal_rate_diff) {
+ /* Previous spad map produced a closer
+ * measurement, so choose this. */
+ status = set_ref_spad_map(last_spad_array);
+ memcpy(Data.RefSpadEnables,
+ last_spad_array, spad_array_size);
+ (ref_spad_count_int)--;
+ }
+ complete = 1;
+ } else {
+ /* Continue to add spads */
+ last_signal_rate_diff = signal_rate_diff;
+ memcpy(last_spad_array,
+ Data.RefSpadEnables,
+ spad_array_size);
+ }
+
+ } /* while */
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ *ref_spad_count = ref_spad_count_int;
+ *is_aperture_spads = is_aperture_spads_int;
+ Data.RefSpadsInitialised = 1;
+ Data.ReferenceSpadCount = (uint8_t)(*ref_spad_count);
+ Data.ReferenceSpadType = *is_aperture_spads;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_reference_spads(uint32_t count, uint8_t is_aperture_spads)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint32_t current_spad_index = 0;
+ uint8_t start_select = 0xB4;
+ uint32_t spad_array_size = 6;
+ uint32_t max_spad_count = 44;
+ uint32_t last_spad_index;
+ uint32_t index;
+
+ /*
+ * This function applies a requested number of reference spads, either
+ * aperture or
+ * non-aperture, as requested.
+ * The good spad map will be applied.
+ */
+
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_DYNAMIC_SPAD_REF_EN_START_OFFSET, 0x00);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( VL53L0X_REG_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD, 0x2C);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x00);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_GLOBAL_CONFIG_REF_EN_START_SELECT,
+ start_select);
+ }
+
+ for (index = 0; index < spad_array_size; index++) {
+ Data.RefSpadEnables[index] = 0;
+ }
+
+ if (is_aperture_spads) {
+ /* Increment to the first APERTURE spad */
+ while ((is_aperture(start_select + current_spad_index) == 0) &&
+ (current_spad_index < max_spad_count)) {
+ current_spad_index++;
+ }
+ }
+ status = enable_ref_spads(is_aperture_spads,
+ Data.RefGoodSpadMap,
+ Data.RefSpadEnables,
+ spad_array_size,
+ start_select,
+ current_spad_index,
+ count,
+ &last_spad_index);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.RefSpadsInitialised = 1;
+ Data.ReferenceSpadCount = (uint8_t)(count);
+ Data.ReferenceSpadType = is_aperture_spads;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_ref_calibration( uint8_t *p_vhv_settings,
+ uint8_t *p_phase_cal)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ status = VL53L0X_perform_ref_calibration( p_vhv_settings, p_phase_cal, 1);
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_perform_ref_spad_management(uint32_t *ref_spad_count, uint8_t *is_aperture_spads)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ status = wrapped_VL53L0X_perform_ref_spad_management( ref_spad_count,
+ is_aperture_spads);
+
+ return status;
+}
+
+/* Group PAL Init Functions */
+VL53L0X_Error VL53L0X::VL53L0X_set_device_address( uint8_t device_address)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ status = VL53L0X_write_byte( VL53L0X_REG_I2C_SLAVE_DEVICE_ADDRESS,
+ device_address / 2);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_gpio_config( uint8_t pin,
+ VL53L0X_DeviceModes device_mode, VL53L0X_GpioFunctionality functionality,
+ VL53L0X_InterruptPolarity polarity)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t data;
+
+ if (pin != 0) {
+ status = VL53L0X_ERROR_GPIO_NOT_EXISTING;
+ } else if (device_mode == VL53L0X_DEVICEMODE_GPIO_DRIVE) {
+ if (polarity == VL53L0X_INTERRUPTPOLARITY_LOW) {
+ data = 0x10;
+ } else {data = 1;}
+
+ status = VL53L0X_write_byte(VL53L0X_REG_GPIO_HV_MUX_ACTIVE_HIGH, data);
+
+ } else {
+ if (device_mode == VL53L0X_DEVICEMODE_GPIO_OSC) {
+
+ status |= VL53L0X_write_byte( 0xff, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x00);
+ status |= VL53L0X_write_byte( 0xff, 0x00);
+ status |= VL53L0X_write_byte( 0x80, 0x01);
+ status |= VL53L0X_write_byte( 0x85, 0x02);
+ status |= VL53L0X_write_byte( 0xff, 0x04);
+ status |= VL53L0X_write_byte( 0xcd, 0x00);
+ status |= VL53L0X_write_byte( 0xcc, 0x11);
+ status |= VL53L0X_write_byte( 0xff, 0x07);
+ status |= VL53L0X_write_byte( 0xbe, 0x00);
+ status |= VL53L0X_write_byte( 0xff, 0x06);
+ status |= VL53L0X_write_byte( 0xcc, 0x09);
+ status |= VL53L0X_write_byte( 0xff, 0x00);
+ status |= VL53L0X_write_byte( 0xff, 0x01);
+ status |= VL53L0X_write_byte( 0x00, 0x00);
+
+ } else {
+
+ if (status == VL53L0X_ERROR_NONE) {
+ switch (functionality) {
+ case VL53L0X_GPIOFUNCTIONALITY_OFF:
+ data = 0x00;
+ break;
+ case VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW:
+ data = 0x01;
+ break;
+ case VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH:
+ data = 0x02;
+ break;
+ case VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT:
+ data = 0x03;
+ break;
+ case VL53L0X_GPIOFUNCTIONALITY_NEW_MEASURE_READY:
+ data = 0x04;
+ break;
+ default:
+ status = VL53L0X_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED;
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_SYSTEM_INTERRUPT_CONFIG_GPIO, data);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (polarity == VL53L0X_INTERRUPTPOLARITY_LOW) {
+ data = 0;
+ } else { data = (uint8_t)(1 << 4); }
+ status = VL53L0X_update_byte(VL53L0X_REG_GPIO_HV_MUX_ACTIVE_HIGH, 0xEF, data);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.Pin0GpioFunctionality = functionality; }
+
+ if (status == VL53L0X_ERROR_NONE) { status = VL53L0X_clear_interrupt_mask( 0); }
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_fraction_enable( uint8_t *p_enabled)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ status = VL53L0X_read_byte( VL53L0X_REG_SYSTEM_RANGE_CONFIG, p_enabled);
+ if (status == VL53L0X_ERROR_NONE) { *p_enabled = (*p_enabled & 1); }
+ return status;
+}
+
+uint16_t VL53L0X::VL53L0X_encode_timeout(uint32_t timeout_macro_clks)
+{ /*!Encode timeout in macro periods in (LSByte * 2^MSByte) + 1 format*/
+
+ uint16_t encoded_timeout = 0;
+ uint32_t ls_byte = 0;
+ uint16_t ms_byte = 0;
+
+ if (timeout_macro_clks > 0) {
+ ls_byte = timeout_macro_clks - 1;
+
+ while ((ls_byte & 0xFFFFFF00) > 0) {
+ ls_byte = ls_byte >> 1;
+ ms_byte++;
+ }
+ encoded_timeout = (ms_byte << 8) + (uint16_t)(ls_byte & 0x000000FF);
+ }
+ return encoded_timeout;
+}
+
+VL53L0X_Error VL53L0X::set_sequence_step_timeout(VL53L0X_SequenceStepId sequence_step_id,
+ uint32_t timeout_micro_secs)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t current_vcsel_pulse_period_p_clk;
+ uint8_t msrc_encoded_time_out;
+ uint16_t pre_range_encoded_time_out;
+ uint16_t pre_range_time_out_m_clks;
+ uint16_t msrc_range_time_out_m_clks;
+ uint32_t final_range_time_out_m_clks;
+ uint16_t final_range_encoded_time_out;
+ VL53L0X_SchedulerSequenceSteps_t scheduler_sequence_steps;
+
+ if ((sequence_step_id == VL53L0X_SEQUENCESTEP_TCC) ||
+ (sequence_step_id == VL53L0X_SEQUENCESTEP_DSS) ||
+ (sequence_step_id == VL53L0X_SEQUENCESTEP_MSRC)) {
+
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ msrc_range_time_out_m_clks = VL53L0X_calc_timeout_mclks(timeout_micro_secs,
+ (uint8_t)current_vcsel_pulse_period_p_clk);
+
+ if (msrc_range_time_out_m_clks > 256) {
+ msrc_encoded_time_out = 255;
+ } else {
+ msrc_encoded_time_out =
+ (uint8_t)msrc_range_time_out_m_clks - 1;
+ }
+ Data.LastEncodedTimeout = msrc_encoded_time_out;
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_MSRC_CONFIG_TIMEOUT_MACROP,
+ msrc_encoded_time_out);
+ }
+ } else {
+
+ if (sequence_step_id == VL53L0X_SEQUENCESTEP_PRE_RANGE) {
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+ pre_range_time_out_m_clks =
+ VL53L0X_calc_timeout_mclks(timeout_micro_secs,
+ (uint8_t)current_vcsel_pulse_period_p_clk);
+ pre_range_encoded_time_out = VL53L0X_encode_timeout(pre_range_time_out_m_clks);
+ Data.LastEncodedTimeout = pre_range_encoded_time_out;
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_word(VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI,
+ pre_range_encoded_time_out);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.PreRangeTimeout_us = timeout_micro_secs;
+ }
+ } else if (sequence_step_id == VL53L0X_SEQUENCESTEP_FINAL_RANGE) {
+
+ /* For the final range timeout, the pre-range timeout
+ * must be added. To do this both final and pre-range
+ * timeouts must be expressed in macro periods MClks
+ * because they have different vcsel periods. */
+
+ VL53L0X_get_sequence_step_enables(&scheduler_sequence_steps);
+ pre_range_time_out_m_clks = 0;
+ if (scheduler_sequence_steps.PreRangeOn) {
+
+ /* Retrieve PRE-RANGE VCSEL Period */
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+
+ /* Retrieve PRE-RANGE Timeout in Macro periods
+ * (MCLKS) */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_word( 0x51, &pre_range_encoded_time_out);
+ pre_range_time_out_m_clks =
+ VL53L0X_decode_timeout( pre_range_encoded_time_out);
+ }
+ }
+
+ /* Calculate FINAL RANGE Timeout in Macro Periods
+ * (MCLKS) and add PRE-RANGE value
+ */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_vcsel_pulse_period( VL53L0X_VCSEL_PERIOD_FINAL_RANGE,
+ ¤t_vcsel_pulse_period_p_clk);
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ final_range_time_out_m_clks =
+ VL53L0X_calc_timeout_mclks( timeout_micro_secs,
+ (uint8_t) current_vcsel_pulse_period_p_clk);
+
+ final_range_time_out_m_clks += pre_range_time_out_m_clks;
+ final_range_encoded_time_out =
+ VL53L0X_encode_timeout(final_range_time_out_m_clks);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_word( 0x71, final_range_encoded_time_out);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.FinalRangeTimeout_us = timeout_micro_secs;
+ }
+ }
+ } else {
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::wrapped_VL53L0X_set_measurement_timing_budget_us(uint32_t measurement_timing_budget_us)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint32_t final_range_timing_budget_us;
+ VL53L0X_SchedulerSequenceSteps_t scheduler_sequence_steps;
+ uint32_t msrc_dcc_tcc_timeout_us = 2000;
+ uint32_t start_overhead_us = 1910;
+ uint32_t end_overhead_us = 960;
+ uint32_t msrc_overhead_us = 660;
+ uint32_t tcc_overhead_us = 590;
+ uint32_t dss_overhead_us = 690;
+ uint32_t pre_range_overhead_us = 660;
+ uint32_t final_range_overhead_us = 550;
+ uint32_t pre_range_timeout_us = 0;
+ uint32_t c_min_timing_budget_us = 20000;
+ uint32_t sub_timeout = 0;
+
+ if (measurement_timing_budget_us < c_min_timing_budget_us)
+ { status = VL53L0X_ERROR_INVALID_PARAMS;
+ return status;
+ }
+
+ final_range_timing_budget_us =
+ measurement_timing_budget_us - (start_overhead_us + end_overhead_us);
+
+ status = VL53L0X_get_sequence_step_enables( &scheduler_sequence_steps);
+
+ if (status == VL53L0X_ERROR_NONE &&
+ (scheduler_sequence_steps.TccOn ||
+ scheduler_sequence_steps.MsrcOn ||
+ scheduler_sequence_steps.DssOn)) {
+
+ /* TCC, MSRC and DSS all share the same timeout */
+ status = get_sequence_step_timeout( VL53L0X_SEQUENCESTEP_MSRC,
+ &msrc_dcc_tcc_timeout_us);
+
+ /* Subtract the TCC, MSRC and DSS timeouts if they are
+ * enabled. */
+
+ if (status != VL53L0X_ERROR_NONE) {
+ return status;
+ }
+
+ /* TCC */
+ if (scheduler_sequence_steps.TccOn) {
+
+ sub_timeout = msrc_dcc_tcc_timeout_us
+ + tcc_overhead_us;
+
+ if (sub_timeout <
+ final_range_timing_budget_us) {
+ final_range_timing_budget_us -=
+ sub_timeout;
+ } else {
+ /* Requested timeout too big. */
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+
+ if (status != VL53L0X_ERROR_NONE) {return status;}
+
+ /* DSS */
+ if (scheduler_sequence_steps.DssOn) {
+
+ sub_timeout = 2 * (msrc_dcc_tcc_timeout_us +
+ dss_overhead_us);
+
+ if (sub_timeout < final_range_timing_budget_us) {
+ final_range_timing_budget_us
+ -= sub_timeout;
+ } else {
+ /* Requested timeout too big. */
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ } else if (scheduler_sequence_steps.MsrcOn) {
+ /* MSRC */
+ sub_timeout = msrc_dcc_tcc_timeout_us +
+ msrc_overhead_us;
+
+ if (sub_timeout < final_range_timing_budget_us) {
+ final_range_timing_budget_us
+ -= sub_timeout;
+ } else {
+ /* Requested timeout too big. */
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+ }
+
+ if (status != VL53L0X_ERROR_NONE) { return status; }
+
+ if (scheduler_sequence_steps.PreRangeOn) {
+
+ /* Subtract the Pre-range timeout if enabled. */
+
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_PRE_RANGE,
+ &pre_range_timeout_us);
+
+ sub_timeout = pre_range_timeout_us +
+ pre_range_overhead_us;
+
+ if (sub_timeout < final_range_timing_budget_us) {
+ final_range_timing_budget_us -= sub_timeout;
+ } else {
+ /* Requested timeout too big. */
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE &&
+ scheduler_sequence_steps.FinalRangeOn) {
+
+ final_range_timing_budget_us -=
+ final_range_overhead_us;
+
+ /* Final Range Timeout
+ * Note that the final range timeout is determined by the timing
+ * budget and the sum of all other timeouts within the sequence.
+ * If there is no room for the final range timeout, then an error
+ * will be set. Otherwise the remaining time will be applied to
+ * the final range.
+ */
+ status = set_sequence_step_timeout(VL53L0X_SEQUENCESTEP_FINAL_RANGE,
+ final_range_timing_budget_us);
+ CurrentParameters.MeasurementTimingBudget_us = measurement_timing_budget_us;
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_measurement_timing_budget_us(uint32_t measurement_timing_budget_us)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ status = wrapped_VL53L0X_set_measurement_timing_budget_us(measurement_timing_budget_us);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_sequence_step_enable(VL53L0X_SequenceStepId sequence_step_id, uint8_t sequence_step_enabled)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t sequence_config = 0;
+ uint8_t sequence_config_new = 0;
+ uint32_t measurement_timing_budget_us;
+
+ status = VL53L0X_read_byte( VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, &sequence_config);
+
+ sequence_config_new = sequence_config;
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (sequence_step_enabled == 1) {
+
+ /* Enable requested sequence step
+ */
+ switch (sequence_step_id) {
+ case VL53L0X_SEQUENCESTEP_TCC:
+ sequence_config_new |= 0x10;
+ break;
+ case VL53L0X_SEQUENCESTEP_DSS:
+ sequence_config_new |= 0x28;
+ break;
+ case VL53L0X_SEQUENCESTEP_MSRC:
+ sequence_config_new |= 0x04;
+ break;
+ case VL53L0X_SEQUENCESTEP_PRE_RANGE:
+ sequence_config_new |= 0x40;
+ break;
+ case VL53L0X_SEQUENCESTEP_FINAL_RANGE:
+ sequence_config_new |= 0x80;
+ break;
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ } else {
+ /* Disable requested sequence step */
+ switch (sequence_step_id) {
+ case VL53L0X_SEQUENCESTEP_TCC:
+ sequence_config_new &= 0xef;
+ break;
+ case VL53L0X_SEQUENCESTEP_DSS:
+ sequence_config_new &= 0xd7;
+ break;
+ case VL53L0X_SEQUENCESTEP_MSRC:
+ sequence_config_new &= 0xfb;
+ break;
+ case VL53L0X_SEQUENCESTEP_PRE_RANGE:
+ sequence_config_new &= 0xbf;
+ break;
+ case VL53L0X_SEQUENCESTEP_FINAL_RANGE:
+ sequence_config_new &= 0x7f;
+ break;
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+ }
+
+ if (sequence_config_new != sequence_config) {
+ /* Apply New Setting */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte(VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, sequence_config_new);
+ }
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = sequence_config_new;}
+
+ /* Recalculate timing budget */
+ if (status == VL53L0X_ERROR_NONE) {
+ measurement_timing_budget_us = CurrentParameters.MeasurementTimingBudget_us ;
+ VL53L0X_set_measurement_timing_budget_us(measurement_timing_budget_us);
+ }
+ }
+
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_set_limit_check_enable( uint16_t limit_check_id,
+ uint8_t limit_check_enable)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ FixPoint1616_t temp_fix1616 = 0;
+ uint8_t limit_check_enable_int = 0;
+ uint8_t limit_check_disable = 0;
+ uint8_t temp8;
+
+ if (limit_check_id >= VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS) {
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ } else {
+ if (limit_check_enable == 0) {
+ temp_fix1616 = 0;
+ limit_check_enable_int = 0;
+ limit_check_disable = 1;
+ } else {
+ temp_fix1616 = CurrentParameters.LimitChecksValue[limit_check_id];
+ limit_check_disable = 0;
+ /* this to be sure to have either 0 or 1 */
+ limit_check_enable_int = 1;
+ }
+
+ switch (limit_check_id) {
+
+ case VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE:
+ /* internal computation: */
+ CurrentParameters.LimitChecksEnable[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] = limit_check_enable_int;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE:
+ status = VL53L0X_write_word( VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT,
+ VL53L0X_FP1616TOFP97(temp_fix1616));
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP:/* internal computation: */
+ CurrentParameters.LimitChecksEnable[VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP] = limit_check_enable_int;
+ break;
+
+ case VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD:/* internal computation: */
+ CurrentParameters.LimitChecksEnable[VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD] = limit_check_enable_int;
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC:
+ temp8 = (uint8_t)(limit_check_disable << 1);
+ status = VL53L0X_update_byte(VL53L0X_REG_MSRC_CONFIG_CONTROL,
+ 0xFE, temp8);
+ break;
+
+ case VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE:
+
+ temp8 = (uint8_t)(limit_check_disable << 4);
+ status = VL53L0X_update_byte(VL53L0X_REG_MSRC_CONFIG_CONTROL,
+ 0xEF, temp8);
+ break;
+
+ default:
+ status = VL53L0X_ERROR_INVALID_PARAMS;
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ if (limit_check_enable == 0) {
+ CurrentParameters.LimitChecksEnable[limit_check_id] = 0;
+ } else {
+ CurrentParameters.LimitChecksEnable[limit_check_id] = 1;
+ }
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_static_init(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ VL53L0X_DeviceParameters_t current_parameters = {0};
+ uint8_t *p_tuning_setting_buffer;
+ uint16_t tempword = 0;
+ uint8_t tempbyte = 0;
+ uint8_t use_internal_tuning_settings = 0;
+ uint32_t count = 0;
+ uint8_t is_aperture_spads = 0;
+ uint32_t ref_spad_count = 0;
+ uint8_t aperture_spads = 0;
+ uint8_t vcsel_pulse_period_pclk;
+ uint32_t seq_timeout_micro_secs;
+
+ status = VL53L0X_get_info_from_device( 1);
+
+ /* set the ref spad from NVM */
+ count = (uint32_t)Data.ReferenceSpadCount;
+ aperture_spads = Data.ReferenceSpadType;
+
+ /* NVM value invalid */
+ if ((aperture_spads > 1) ||
+ ((aperture_spads == 1) && (count > 32)) ||
+ ((aperture_spads == 0) && (count > 12))) {
+ status = wrapped_VL53L0X_perform_ref_spad_management( &ref_spad_count,
+ &is_aperture_spads);
+ } else {
+ status = VL53L0X_set_reference_spads( count, aperture_spads);
+ }
+
+ /* Initialize tuning settings buffer to prevent compiler warning. */
+ p_tuning_setting_buffer = DefaultTuningSettings;
+
+ if (status == VL53L0X_ERROR_NONE) {
+ use_internal_tuning_settings = Data.UseInternalTuningSettings;
+
+ if (use_internal_tuning_settings == 0) {
+ p_tuning_setting_buffer = Data.pTuningSettingsPointer; }
+ else { p_tuning_setting_buffer = DefaultTuningSettings; }
+
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_load_tuning_settings( p_tuning_setting_buffer); }
+
+ /* Set interrupt config to new sample ready */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_gpio_config( 0, 0,
+ VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY,
+ VL53L0X_INTERRUPTPOLARITY_LOW);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+ status |= VL53L0X_read_word ( 0x84, &tempword);
+ status |= VL53L0X_write_byte( 0xFF, 0x00);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.OscFrequency_MHz = VL53L0X_FP412TOFP1616(tempword) ;
+ }
+
+ /* After static init, some device parameters may be changed,
+ * so update them */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_device_parameters( ¤t_parameters);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_fraction_enable( &tempbyte);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.RangeFractionalEnable = tempbyte;
+ }
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ CurrentParameters = current_parameters;
+ }
+
+ /* read the sequence config and save it */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_byte(VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG, &tempbyte);
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.SequenceConfig = tempbyte;
+ }
+ }
+
+ /* Disable MSRC and TCC by default */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_sequence_step_enable(VL53L0X_SEQUENCESTEP_TCC, 0);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_set_sequence_step_enable(VL53L0X_SEQUENCESTEP_MSRC, 0);
+ }
+
+ /* Set PAL State to standby */
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.PalState = VL53L0X_STATE_IDLE;
+ }
+
+ /* Store pre-range vcsel period */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_PRE_RANGE,&vcsel_pulse_period_pclk);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.PreRangeVcselPulsePeriod = vcsel_pulse_period_pclk;
+ }
+
+ /* Store final-range vcsel period */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_get_vcsel_pulse_period(VL53L0X_VCSEL_PERIOD_FINAL_RANGE,
+ &vcsel_pulse_period_pclk);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.FinalRangeVcselPulsePeriod = vcsel_pulse_period_pclk;
+ }
+
+ /* Store pre-range timeout */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_PRE_RANGE,&seq_timeout_micro_secs);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.PreRangeTimeout_us = seq_timeout_micro_secs;
+ }
+
+ /* Store final-range timeout */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = get_sequence_step_timeout(VL53L0X_SEQUENCESTEP_FINAL_RANGE,&seq_timeout_micro_secs);
+ }
+
+ if (status == VL53L0X_ERROR_NONE) {
+ Data.FinalRangeTimeout_us = seq_timeout_micro_secs;
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_stop_measurement(void)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+
+ status = VL53L0X_write_byte( VL53L0X_REG_SYSRANGE_START,
+ VL53L0X_REG_SYSRANGE_MODE_SINGLESHOT);
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+ status = VL53L0X_write_byte( 0x00, 0x00);
+ status = VL53L0X_write_byte( 0x91, 0x00);
+ status = VL53L0X_write_byte( 0x00, 0x01);
+ status = VL53L0X_write_byte( 0xFF, 0x00);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ /* Set PAL State to Idle */
+ Data.PalState = VL53L0X_STATE_IDLE;
+ }
+
+ /* Check if need to apply interrupt settings */
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_check_and_load_interrupt_settings( 0);
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_get_stop_completed_status(uint32_t *p_stop_status)
+{ VL53L0X_Error status = VL53L0X_ERROR_NONE;
+ uint8_t byte = 0;
+
+
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_read_byte( 0x04, &byte);}
+
+ if (status == VL53L0X_ERROR_NONE) {
+ status = VL53L0X_write_byte( 0xFF, 0x0); }
+
+ *p_stop_status = byte;
+
+ if (byte == 0) {
+ status = VL53L0X_write_byte( 0x80, 0x01);
+ status = VL53L0X_write_byte( 0xFF, 0x01);
+ status = VL53L0X_write_byte( 0x00, 0x00);
+ status = VL53L0X_write_byte( 0x91,Data.StopVariable);
+ status = VL53L0X_write_byte( 0x00, 0x01);
+ status = VL53L0X_write_byte( 0xFF, 0x00);
+ status = VL53L0X_write_byte( 0x80, 0x00);
+ }
+ return status;
+}
+
+/******************************************************************************/
+
+/****************** Write and read functions from I2C *************************/
+
+VL53L0X_Error VL53L0X::VL53L0X_read_multi( uint8_t index, uint8_t *p_data, uint32_t count)
+{ if (count >= VL53L0X_MAX_I2C_XFER_SIZE) {
+ return VL53L0X_ERROR_INVALID_PARAMS;}
+ else { return VL53L0X_i2c_read(index, p_data, (uint16_t)count); }
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_write_byte( uint8_t index, uint8_t data)
+{ return VL53L0X_i2c_write(index, &data, 1);
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_write_word( uint8_t index, uint16_t data)
+{ int status;
+ uint8_t buffer[2];
+
+ buffer[0] = data >> 8;
+ buffer[1] = data & 0x00FF;
+ status = VL53L0X_i2c_write(index, (uint8_t *)buffer, 2);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_write_dword( uint8_t index, uint32_t data)
+{ int status;
+ uint8_t buffer[4];
+
+ buffer[0] = (data >> 24) & 0xFF;
+ buffer[1] = (data >> 16) & 0xFF;
+ buffer[2] = (data >> 8) & 0xFF;
+ buffer[3] = (data >> 0) & 0xFF;
+ status = VL53L0X_i2c_write(index, (uint8_t *)buffer, 4);
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_read_byte( uint8_t index, uint8_t *p_data)
+{ return VL53L0X_i2c_read(index, p_data, 1); }
+
+VL53L0X_Error VL53L0X::VL53L0X_read_word( uint8_t index, uint16_t *p_data)
+{ int status;
+ uint8_t buffer[2] = {0, 0};
+
+ status = VL53L0X_i2c_read(index, buffer, 2);
+ if (!status) {*p_data = (buffer[0] << 8) + buffer[1];}
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_read_dword( uint8_t index, uint32_t *p_data)
+{ int status;
+ uint8_t buffer[4] = {0, 0, 0, 0};
+
+ status = VL53L0X_i2c_read(index, buffer, 4);
+ if (!status) { *p_data = (buffer[0] << 24) + (buffer[1] << 16) + (buffer[2] << 8) + buffer[3]; }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_update_byte( uint8_t index, uint8_t and_data, uint8_t or_data)
+{ int status;
+ uint8_t buffer = 0;
+
+ /* read data direct onto buffer */
+ status = VL53L0X_i2c_read(index, &buffer, 1);
+ if (!status) {
+ buffer = (buffer & and_data) | or_data;
+ status = VL53L0X_i2c_write(index, &buffer, (uint8_t)1);
+ }
+ return status;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_i2c_write(uint8_t RegisterAddr, uint8_t *p_data,
+ uint16_t NumByteToWrite)
+{ /** Writes a buffer towards the I2C peripheral device. */
+ static uint8_t tmp[VL53L0X_MAX_I2C_XFER_SIZE];
+
+ if(NumByteToWrite >= VL53L0X_MAX_I2C_XFER_SIZE) return -2;
+
+ /* First, send device address. Then, send data and STOP condition */
+ tmp[0] = RegisterAddr;
+ memcpy(tmp+1, p_data, NumByteToWrite);
+
+ if (_dev_i2c->write(I2cDevAddr, (const char*)tmp, NumByteToWrite+1, false) != 0 )
+ { return -1; }
+ return 0;
+}
+
+VL53L0X_Error VL53L0X::VL53L0X_i2c_read(uint8_t RegisterAddr, uint8_t *p_data, uint16_t NumByteToRead)
+{ /** Reads a buffer from the I2C peripheral device. */
+
+ /* First Send device address, with no STOP condition */
+ int ret = _dev_i2c->write(I2cDevAddr, (const char*)&RegisterAddr, 1, true);
+
+ /* all ok ? then Read data, with STOP condition */
+ if (ret == 0) { ret = _dev_i2c->read(I2cDevAddr, (char*)p_data, NumByteToRead, false); }
+
+ if (ret != 0 ){ return -1; }
+ return 0;
+}
+
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/VL53L0X.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,1824 @@
+/*******************************************************************************
+ Copyright © 2016, 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.
+ *****************************************************************************/
+
+#ifndef __VL53L0X_CLASS_H
+#define __VL53L0X_CLASS_H
+
+
+/* Includes ------------------------------------------------------------------*/
+#include "mbed.h"
+#include "pinmap.h"
+#include "PinNames.h"
+#include "VL53L0X_def.h"
+
+/* Classes -------------------------------------------------------------------*/
+/** Class representing a VL53L0 sensor component */
+class VL53L0X
+{
+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] dev_addr device address, 0x29 by default
+ */
+ VL53L0X(I2C *i2c, DigitalOut *pin, PinName pin_gpio1, uint8_t dev_addr = VL53L0X_DEFAULT_ADDRESS) : _gpio0(pin), _dev_i2c(i2c)
+ { I2cDevAddr = dev_addr;
+ comms_type = 1; // VL53L0X_COMMS_I2C
+ comms_speed_khz = 400;
+ if (pin_gpio1 != NC) { _gpio1Int = new InterruptIn(pin_gpio1); }
+ else { _gpio1Int = NULL; }
+ }
+
+ /** Destructor
+ */
+ virtual ~VL53L0X()
+ { if (_gpio1Int != NULL) { delete _gpio1Int; } }
+
+ /*** Interface Methods High level API ***/
+ /**
+ * @brief PowerOn the sensor
+ * @return void
+ */
+ /* turns on the sensor */
+ void VL53L0X_on(void)
+ {
+ if (_gpio0) { *_gpio0 = 1; }
+ wait_ms(10);
+ }
+
+ /**
+ * @brief PowerOff the sensor
+ * @return void
+ */
+ /* turns off the sensor */
+ void VL53L0X_off(void)
+ {
+ if (_gpio0) { *_gpio0 = 0; }
+ wait_ms(10);
+ }
+
+
+ /**
+ * @brief Initialize the sensor with default values
+ * @return "0" on success
+ */
+ int init_sensor(uint8_t new_addr = VL53L0X_DEFAULT_ADDRESS);
+
+ /**
+ * @brief Start the measure indicated by operating mode
+ * @param[in] operating_mode specifies requested measure
+ * @param[in] fptr specifies call back function must be !NULL in case of interrupt measure
+ * @return "0" on success
+ */
+ int start_measurement(OperatingMode operating_mode, void (*fptr)(void),
+ VL53L0X_RangingConfig rangingConfig );
+
+ /**
+ * @brief Get results for the measure indicated by operating mode
+ * @param[in] operating_mode specifies requested measure results
+ * @param[out] p_data pointer to the MeasureData_t structure to read data in to
+ * @return "0" on success
+ */
+ int get_measurement(OperatingMode operating_mode, VL53L0X_RangingMeasurementData_t *p_data);
+
+ /**
+ * @brief Stop the currently running measure indicate by operating_mode
+ * @param[in] operating_mode specifies requested measure to stop
+ * @return "0" on success
+ */
+ int stop_measurement(OperatingMode operating_mode);
+
+ /**
+ * @brief Interrupt handling func to be called by user after an INT is occourred
+ * @param[in] opeating_mode indicating the in progress measure
+ * @param[out] Data pointer to the MeasureData_t structure to read data in to
+ * @return "0" on success
+ */
+ int handle_irq(OperatingMode operating_mode, VL53L0X_RangingMeasurementData_t *data);
+
+ /**
+ * @brief Enable interrupt measure IRQ
+ * @return "0" on success
+ */
+ void enable_interrupt_measure_detection_irq(void)
+ { if (_gpio1Int != NULL) { _gpio1Int->enable_irq();} }
+
+ /**
+ * @brief Disable interrupt measure IRQ
+ * @return "0" on success
+ */
+ void disable_interrupt_measure_detection_irq(void)
+ { if (_gpio1Int != NULL) { _gpio1Int->disable_irq(); } }
+
+ /**
+ * @brief Attach a function to call when an interrupt is detected, i.e. measurement is ready
+ * @param[in] fptr pointer to call back function to be called whenever an interrupt occours
+ * @return "0" on success
+ */
+ void attach_interrupt_measure_detection_irq(void (*fptr)(void))
+ { if (_gpio1Int != NULL) { _gpio1Int->rise(fptr); } }
+
+ /** Wrapper functions */
+ /** @defgroup api_init Init functions
+ * @brief API init functions
+ * @ingroup api_hl
+ * @{
+ */
+
+ /**
+ * @brief Prepare device for operation
+ * @par Function Description
+ * Does static initialization and reprogram common default settings \n
+ * Device is prepared for new measure, ready single shot ranging or ALS typical polling operation\n
+ * After prepare user can : \n
+ * @li Call other API function to set other settings\n
+ * @li Configure the interrupt pins, etc... \n
+ * @li Then start ranging or ALS operations in single shot or continuous mode
+ *
+ * @param void
+ * @return "0" on success
+ */
+ int prepare();
+
+ /**
+ * @brief Start continuous ranging mode
+ *
+ * @details End user should ensure device is in idle state and not already running
+ * @return "0" on success
+ */
+ int range_start_continuous_mode();
+
+ /**
+ * @brief Get ranging result and only that
+ *
+ * @par Function Description
+ * Unlike @a VL53L0X_get_ranging_measurement_data() this function only retrieves the range in _mm \n
+ * It does any required up-scale translation\n
+ * It can be called after success status polling or in interrupt mode \n
+ * @warning these function is not doing wrap around filtering \n
+ * This function doesn't perform any data ready check!
+ *
+ * @param p_data Pointer to range distance
+ * @return "0" on success
+ */
+ int get_distance(uint32_t *p_data);
+
+ /** @} */
+
+ /** @brief Set new device i2c address
+ *
+ * After completion the device will answer to the new address programmed.
+ *
+ * @param new_addr The new i2c address (7bit)
+ * @return "0" on success
+ */
+ int set_device_address(int new_addr)
+ {
+ int status;
+
+ status = VL53L0X_set_device_address(new_addr);
+ if (!status) { I2cDevAddr = new_addr; }
+ return status;
+ }
+
+ /**
+ * @brief Clear given system interrupt condition
+ *
+ * @par Function Description
+ * Clear given interrupt cause by writing into register #SYSTEM_INTERRUPT_CLEAR register.
+ * @param int_clear Which interrupt source to clear. Use any combinations of #INTERRUPT_CLEAR_RANGING , #INTERRUPT_CLEAR_ALS , #INTERRUPT_CLEAR_ERROR.
+ * @return "0" on success
+ */
+ int clear_interrupt(uint8_t int_clear)
+ { return VL53L0X_clear_interrupt_mask(int_clear); }
+
+ /** @brief One time device initialization
+ *
+ * To be called once and only once after device is brought out of reset
+ * (Chip enable) and booted see @a VL53L0X_WaitDeviceBooted()
+ *
+ * @par Function Description
+ * When not used after a fresh device "power up" or reset, it may return
+ * @a #VL53L0X_ERROR_CALIBRATION_WARNING meaning wrong calibration data
+ * may have been fetched from device that can result in ranging offset error\n
+ * If application cannot execute device reset or need to run VL53L0X_DataInit
+ * multiple time then it must ensure proper offset calibration saving and
+ * restore on its own by using @a VL53L0X_GetOffsetCalibrationData() on first
+ * power up and then @a VL53L0X_SetOffsetCalibrationData() in all subsequent init
+ * This function will change the VL53L0X_State from VL53L0X_STATE_POWERDOWN to
+ * VL53L0X_STATE_WAIT_STATICINIT.
+ *
+ * @note This function accesses to the device
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_data_init(void);
+
+ /**
+ * @brief Do basic device init (and eventually patch loading)
+ * This function will change the VL53L0X_State from
+ * VL53L0X_STATE_WAIT_STATICINIT to VL53L0X_STATE_IDLE.
+ * In this stage all default setting will be applied.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_static_init(void);
+
+ /**
+ * @brief Perform Reference Calibration
+ *
+ * @details Perform a reference calibration of the Device.
+ * This function should be run from time to time before doing
+ * a ranging measurement.
+ * This function will launch a special ranging measurement, so
+ * if interrupt are enable an interrupt will be done.
+ * This function will clear the interrupt generated automatically.
+ *
+ * @warning This function is a blocking function
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_vhv_settings Pointer to vhv settings parameter.
+ * @param p_phase_cal Pointer to PhaseCal parameter.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_perform_ref_calibration( uint8_t *p_vhv_settings,
+ uint8_t *p_phase_cal);
+
+ /**
+ * @brief Get Reference Calibration Parameters
+ *
+ * @par Function Description
+ * Get Reference Calibration Parameters.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_vhv_settings Pointer to VHV parameter
+ * @param p_phase_cal Pointer to PhaseCal Parameter
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_ref_calibration(
+ uint8_t *p_vhv_settings, uint8_t *p_phase_cal);
+
+ VL53L0X_Error VL53L0X_set_ref_calibration(
+ uint8_t vhv_settings, uint8_t phase_cal);
+
+ /**
+ * @brief Performs Reference Spad Management
+ *
+ * @par Function Description
+ * The reference SPAD initialization procedure determines the minimum amount
+ * of reference spads to be enables to achieve a target reference signal rate
+ * and should be performed once during initialization.
+ *
+ * @note This function Access to the device
+ *
+ * @note This function change the device mode to VL53L0X_DEVICEMODE_SINGLE_RANGING
+ *
+ * @param ref_spad_count Reports ref Spad Count
+ * @param is_aperture_spads Reports if spads are of type
+ * aperture or non-aperture.
+ * 1:=aperture, 0:=Non-Aperture
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_REF_SPAD_INIT Error in the Ref Spad procedure.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_perform_ref_spad_management(
+ uint32_t *ref_spad_count, uint8_t *is_aperture_spads);
+
+ /**
+ * @brief Applies Reference SPAD configuration
+ *
+ * @par Function Description
+ * This function applies a given number of reference spads, identified as
+ * either Aperture or Non-Aperture.
+ * The requested spad count and type are stored within the device specific
+ * parameters data for access by the host.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param refSpadCount Number of ref spads.
+ * @param is_aperture_spads Defines if spads are of type
+ * aperture or non-aperture.
+ * 1:=aperture, 0:=Non-Aperture
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_REF_SPAD_INIT Error in the in the reference
+ * spad configuration.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_reference_spads(
+ uint32_t refSpadCount, uint8_t is_aperture_spads);
+
+ /**
+ * @brief Retrieves SPAD configuration
+ *
+ * @par Function Description
+ * This function retrieves the current number of applied reference spads
+ * and also their type : Aperture or Non-Aperture.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_spad_count Number ref Spad Count
+ * @param p_is_aperture_spads Reports if spads are of type
+ * aperture or non-aperture.
+ * 1:=aperture, 0:=Non-Aperture
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_REF_SPAD_INIT Error in the in the reference
+ * spad configuration.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_reference_spads(
+ uint32_t *p_spad_count, uint8_t *p_is_aperture_spads);
+
+ /**
+ * @brief Get part to part calibration offset
+ *
+ * @par Function Description
+ * Should only be used after a successful call to @a VL53L0X_DataInit to backup
+ * device NVM value
+ *
+ * @note This function Access to the device
+ *
+ * @param p_offset_calibration_data_micro_meter Return part to part
+ * calibration offset from device (microns)
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_offset_calibration_data_micro_meter(
+ int32_t *p_offset_calibration_data_micro_meter);
+ /**
+ * Set or over-hide part to part calibration offset
+ * \sa VL53L0X_DataInit() VL53L0X_GetOffsetCalibrationData_um()
+ *
+ * @note This function Access to the device
+ *
+ * @param p_offset_calibration_data_micro_meter Offset (microns)
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_offset_calibration_data_micro_meter(
+ int32_t offset_calibration_data_micro_meter);
+
+ VL53L0X_Error VL53L0X_perform_offset_calibration(
+ FixPoint1616_t cal_distance_milli_meter,
+ int32_t *p_offset_micro_meter);
+
+ VL53L0X_Error VL53L0X_perform_xtalk_calibration(
+ FixPoint1616_t xtalk_cal_distance,
+ FixPoint1616_t *p_xtalk_compensation_rate_MHz);
+
+ /**
+ * @brief Set Cross talk compensation rate
+ *
+ * @par Function Description
+ * Set Cross talk compensation rate.
+ *
+ * @note This function Access to the device
+ *
+ * @param x_talk_compensation_rate_MHz Compensation rate in
+ * Mega counts per second
+ * (16.16 fix point) see
+ * datasheet for details
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_x_talk_compensation_rate_MHz(
+ FixPoint1616_t x_talk_compensation_rate_MHz);
+
+ /**
+ * @brief Get Cross talk compensation rate
+ *
+ * @par Function Description
+ * Get Cross talk compensation rate.
+ *
+ * @note This function Access to the device
+ *
+ * @param p_xtalk_compensation_rate_MHz Pointer to Compensation rate
+ * in Mega counts per second
+ * (16.16 fix point) see
+ * datasheet for details
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_x_talk_compensation_rate_MHz(
+ FixPoint1616_t *p_xtalk_compensation_rate_MHz);
+
+ /**
+ * @brief Get Cross talk enable
+ *
+ * Enable/Disable Cross Talk by set to zero the Cross Talk value by
+ * using @a VL53L0X_SetXTalkCompensationRate_MHz().
+ *
+ * @param dev Device Handle
+ * @param p_x_talk_compensation_enable Pointer to the Cross talk compensation
+ * state 0=disabled or 1 = enabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_x_talk_compensation_enable(uint8_t *p_x_talk_compensation_enable);
+
+ /**
+ * @brief Set a new device mode
+ * @par Function Description
+ * Set device to a new mode (ranging, histogram ...)
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @param device_mode New device mode to apply
+ * Valid values are:
+ * VL53L0X_DEVICEMODE_SINGLE_RANGING
+ * VL53L0X_DEVICEMODE_CONTINUOUS_RANGING
+ * VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING
+ *
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_MODE_NOT_SUPPORTED This error occurs when
+ * DeviceMode is not in the
+ * supported list
+ */
+ VL53L0X_Error VL53L0X_set_device_mode( VL53L0X_DeviceModes device_mode);
+
+
+ /**
+ * @brief Get current configuration for GPIO pin for a given device
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param pin ID of the GPIO Pin
+ * @param p_device_mode Pointer to Device Mode associated to the Gpio.
+ * @param p_functionality Pointer to Pin functionality.
+ * Refer to ::VL53L0X_GpioFunctionality
+ * @param p_polarity Pointer to interrupt polarity.
+ * Active high or active low see
+ * ::VL53L0X_InterruptPolarity
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_GPIO_NOT_EXISTING Only Pin=0 is accepted.
+ * @return VL53L0X_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED
+ * This error occurs
+ * when Funcionality programmed is not in the supported list:
+ * Supported value are:
+ * VL53L0X_GPIOFUNCTIONALITY_OFF,
+ * VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW,
+ * VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH,
+ * VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT,
+ * VL53L0X_GPIOFUNCTIONALITY_NEW_MEASURE_READY
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_gpio_config( uint8_t pin,
+ VL53L0X_DeviceModes *p_device_mode,
+ VL53L0X_GpioFunctionality *p_functionality,
+ VL53L0X_InterruptPolarity *p_polarity);
+
+ /**
+ * @brief Set the configuration of GPIO pin for a given device
+ *
+ * @note This function Access to the device
+ *
+ * @param pin ID of the GPIO Pin
+ * @param functionality Select Pin functionality.
+ * Refer to ::VL53L0X_GpioFunctionality
+ * @param device_mode Device Mode associated to the Gpio.
+ * @param polarity Set interrupt polarity. Active high
+ * or active low see ::VL53L0X_InterruptPolarity
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_GPIO_NOT_EXISTING Only Pin=0 is accepted.
+ * @return VL53L0X_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED This error occurs
+ * when Functionality programmed is not in the supported list:
+ * Supported value are:
+ * VL53L0X_GPIOFUNCTIONALITY_OFF,
+ * VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW,
+ * VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH,
+ VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT,
+ * VL53L0X_GPIOFUNCTIONALITY_NEW_MEASURE_READY
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_gpio_config( uint8_t pin,
+ VL53L0X_DeviceModes device_mode, VL53L0X_GpioFunctionality functionality,
+ VL53L0X_InterruptPolarity polarity);
+
+ /**
+ * @brief Start device measurement
+ *
+ * @details Started measurement will depend on device parameters set through
+ * @a VL53L0X_SetParameters()
+ * This is a non-blocking function.
+ * This function will change the VL53L0X_State from VL53L0X_STATE_IDLE to
+ * VL53L0X_STATE_RUNNING.
+ *
+ * @note This function Access to the device
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_MODE_NOT_SUPPORTED This error occurs when
+ * DeviceMode programmed with @a VL53L0X_SetDeviceMode is not in the supported
+ * list:
+ * Supported mode are:
+ * VL53L0X_DEVICEMODE_SINGLE_RANGING,
+ * VL53L0X_DEVICEMODE_CONTINUOUS_RANGING,
+ * VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING
+ * @return VL53L0X_ERROR_TIME_OUT Time out on start measurement
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_start_measurement(void);
+
+ /**
+ * @brief Stop device measurement
+ *
+ * @details Will set the device in standby mode at end of current measurement\n
+ * Not necessary in single mode as device shall return automatically
+ * in standby mode at end of measurement.
+ * This function will change the VL53L0X_State from VL53L0X_STATE_RUNNING
+ * to VL53L0X_STATE_IDLE.
+ *
+ * @note This function Access to the device
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_stop_measurement(void);
+
+ /**
+ * @brief Return device stop completion status
+ *
+ * @par Function Description
+ * Returns stop completiob status.
+ * User shall call this function after a stop command
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_stop_status Pointer to status variable to update
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_stop_completed_status(
+ uint32_t *p_stop_status);
+
+ /**
+ * @brief Return Measurement Data Ready
+ *
+ * @par Function Description
+ * This function indicate that a measurement data is ready.
+ * This function check if interrupt mode is used then check is done accordingly.
+ * If perform function clear the interrupt, this function will not work,
+ * like in case of @a VL53L0X_PerformSingleRangingMeasurement().
+ * The previous function is blocking function, VL53L0X_GetMeasurementDataReady
+ * is used for non-blocking capture.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_measurement_data_ready Pointer to Measurement Data Ready.
+ * 0=data not ready, 1 = data ready
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_measurement_data_ready(
+ uint8_t *p_measurement_data_ready);
+
+ /**
+ * @brief Retrieve the measurements from device for a given setup
+ *
+ * @par Function Description
+ * Get data from last successful Ranging measurement
+ * @warning USER should take care about @a VL53L0X_GetNumberOfROIZones()
+ * before get data.
+ * PAL will fill a NumberOfROIZones times the corresponding data
+ * structure used in the measurement function.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_ranging_measurement_data Pointer to the data structure to fill up.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_ranging_measurement_data(
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data);
+
+ /**
+ * @brief Clear given system interrupt condition
+ *
+ * @par Function Description
+ * Clear given interrupt(s).
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param interrupt_mask Mask of interrupts to clear
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INTERRUPT_NOT_CLEARED Cannot clear interrupts
+ *
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_clear_interrupt_mask( uint32_t interrupt_mask);
+
+ /**
+ * @brief Return device interrupt status
+ *
+ * @par Function Description
+ * Returns currently raised interrupts by the device.
+ * User shall be able to activate/deactivate interrupts through
+ * @a VL53L0X_SetGpioConfig()
+ *
+ * @note This function Access to the device
+ *
+ * @param p_interrupt_mask_status Pointer to status variable to update
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_interrupt_mask_status(
+ uint32_t *p_interrupt_mask_status);
+
+ /**
+ * @brief Performs a single ranging measurement and retrieve the ranging
+ * measurement data
+ *
+ * @par Function Description
+ * This function will change the device mode to VL53L0X_DEVICEMODE_SINGLE_RANGING
+ * with @a VL53L0X_SetDeviceMode(),
+ * It performs measurement with @a VL53L0X_PerformSingleMeasurement()
+ * It get data from last successful Ranging measurement with
+ * @a VL53L0X_GetRangingMeasurementData.
+ * Finally it clear the interrupt with @a VL53L0X_ClearInterruptMask().
+ *
+ * @note This function Access to the device
+ *
+ * @param p_ranging_measurement_data Pointer to the data structure to fill up.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_perform_single_ranging_measurement(
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data);
+
+ /**
+ * @brief Single shot measurement.
+ *
+ * @par Function Description
+ * Perform simple measurement sequence (Start measure, Wait measure to end,
+ * and returns when measurement is done).
+ * Once function returns, user can get valid data by calling
+ * VL53L0X_GetRangingMeasurement or VL53L0X_GetHistogramMeasurement
+ * depending on defined measurement mode
+ * User should Clear the interrupt in case this are enabled by using the
+ * function VL53L0X_ClearInterruptMask().
+ *
+ * @warning This function is a blocking function
+ *
+ * @note This function Access to the device
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_perform_single_measurement(void);
+
+ VL53L0X_Error VL53L0X_get_total_signal_rate(
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ FixPoint1616_t *p_total_signal_rate_MHz);
+
+ VL53L0X_Error VL53L0X_get_total_xtalk_rate(
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ FixPoint1616_t *p_total_xtalk_rate_MHz);
+
+ /**
+ * @brief Get Ranging Timing Budget in us
+ *
+ * @par Function Description
+ * Returns the programmed the maximum time allowed by the user to the
+ * device to run a full ranging sequence for the current mode
+ * (ranging, histogram, ASL ...)
+ *
+ * @note This function Access to the device
+ *
+ * @param p_measurement_timing_budget_us Max measurement time in
+ *us.
+ * Valid values are:
+ * >= 17000us when wraparound enabled
+ * >= 12000us when wraparound disabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_measurement_timing_budget_us(
+ uint32_t *p_measurement_timing_budget_us);
+
+ /**
+ * @brief Set Ranging Timing Budget in us
+ *
+ * @par Function Description
+ * Defines the maximum time allowed by the user to the device to run a
+ * full ranging sequence for the current mode (ranging, histogram, ASL ...)
+ *
+ * @note This function Access to the device
+ *
+ * @param measurement_timing_budget_us Max measurement time in us.
+ * Valid values are:
+ * >= 17000us when wraparound enabled
+ * >= 12000us when wraparound disabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is returned if
+ MeasurementTimingBudget_us out of range
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_measurement_timing_budget_us(
+ uint32_t measurement_timing_budget_us);
+
+ /**
+ * @brief Get specific limit check enable state
+ *
+ * @par Function Description
+ * This function get the enable state of a specific limit check.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ * (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param p_limit_check_enable Pointer to the check limit enable
+ * value.
+ * if 1 the check limit
+ * corresponding to LimitCheckId is Enabled
+ * if 0 the check limit
+ * corresponding to LimitCheckId is disabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is returned
+ * when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_limit_check_enable( uint16_t limit_check_id,
+ uint8_t *p_limit_check_enable);
+
+ /**
+ * @brief Enable/Disable a specific limit check
+ *
+ * @par Function Description
+ * This function Enable/Disable a specific limit check.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function doesn't Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ * (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param limit_check_enable if 1 the check limit
+ * corresponding to LimitCheckId is Enabled
+ * if 0 the check limit
+ * corresponding to LimitCheckId is disabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is returned
+ * when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_limit_check_enable( uint16_t limit_check_id,
+ uint8_t limit_check_enable);
+
+ /**
+ * @brief Get a specific limit check value
+ *
+ * @par Function Description
+ * This function get a specific limit check value from device then it updates
+ * internal values and check enables.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ * (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param p_limit_check_value Pointer to Limit
+ * check Value for a given LimitCheckId.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is returned
+ * when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_limit_check_value( uint16_t limit_check_id,
+ FixPoint1616_t *p_limit_check_value);
+
+ /**
+ * @brief Set a specific limit check value
+ *
+ * @par Function Description
+ * This function set a specific limit check value.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ * (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param limit_check_value Limit check Value for a given
+ * LimitCheckId
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is returned when either
+ * LimitCheckId or LimitCheckValue value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_limit_check_value( uint16_t limit_check_id,
+ FixPoint1616_t limit_check_value);
+
+ /**
+ * @brief Get the current value of the signal used for the limit check
+ *
+ * @par Function Description
+ * This function get a the current value of the signal used for the limit check.
+ * To obtain the latest value you should run a ranging before.
+ * The value reported is linked to the limit check identified with the
+ * LimitCheckId.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ * (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param p_limit_check_current Pointer to current Value for a
+ * given LimitCheckId.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is returned when
+ * LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_limit_check_current( uint16_t limit_check_id,
+ FixPoint1616_t *p_limit_check_current);
+
+ /**
+ * @brief Return a the Status of the specified check limit
+ *
+ * @par Function Description
+ * This function returns the Status of the specified check limit.
+ * The value indicate if the check is fail or not.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function doesn't Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param p_limit_check_status Pointer to the
+ Limit Check Status of the given check limit.
+ * LimitCheckStatus :
+ * 0 the check is not fail
+ * 1 the check if fail or not enabled
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is
+ returned when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_limit_check_status(
+ uint16_t limit_check_id, uint8_t *p_limit_check_status);
+
+ /**
+ * Get continuous mode Inter-Measurement period in _ms
+ *
+ * @par Function Description
+ * When trying to set too short time return INVALID_PARAMS minimal value
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_inter_measurement_period_ms Pointer to programmed
+ * Inter-Measurement Period in _ms.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_inter_measurement_period_ms(
+ uint32_t *p_inter_measurement_period_ms);
+
+ /**
+ * Program continuous mode Inter-Measurement period in _ms
+ *
+ * @par Function Description
+ * When trying to set too short time return INVALID_PARAMS minimal value
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param inter_measurement_period_ms Inter-Measurement Period in ms.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_inter_measurement_period_ms(
+ uint32_t inter_measurement_period_ms);
+
+ /**
+ * @brief Set new device address
+ *
+ * After completion the device will answer to the new address programmed.
+ * This function should be called when several devices are used in parallel
+ * before start programming the sensor.
+ * When a single device us used, there is no need to call this function.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param device_address The new Device address
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_device_address( uint8_t device_address);
+
+ /**
+ * @brief Do an hard reset or soft reset (depending on implementation) of the
+ * device \nAfter call of this function, device must be in same state as right
+ * after a power-up sequence.This function will change the VL53L0X_State to
+ * VL53L0X_STATE_POWERDOWN.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_reset_device(void);
+
+ /**
+ * @brief Get setup of Wrap around Check
+ *
+ * @par Function Description
+ * This function get the wrapAround check enable parameters
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_wrap_around_check_enable Pointer to the Wrap around Check state
+ * 0=disabled or 1 = enabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_wrap_around_check_enable(
+ uint8_t *p_wrap_around_check_enable);
+
+ /**
+ * @brief Enable (or disable) Wrap around Check
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param wrap_around_check_enable Wrap around Check to be set
+ * 0=disabled, other = enabled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_wrap_around_check_enable(
+ uint8_t wrap_around_check_enable);
+
+ /**
+ * @brief Gets the VCSEL pulse period.
+ *
+ * @par Function Description
+ * This function retrieves the VCSEL pulse period for the given period type.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param vcsel_period_type VCSEL period identifier (pre-range|final).
+ * @param p_vcsel_pulse_period_pclk Pointer to VCSEL period value.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS Error VcselPeriodType parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_vcsel_pulse_period(
+ VL53L0X_VcselPeriod vcsel_period_type, uint8_t *p_vcsel_pulse_period_pclk);
+
+ /**
+ * @brief Sets the VCSEL pulse period.
+ *
+ * @par Function Description
+ * This function retrieves the VCSEL pulse period for the given period type.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param vcsel_period_type VCSEL period identifier (pre-range|final).
+ * @param vcsel_pulse_period VCSEL period value
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS Error VcselPeriodType parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_vcsel_pulse_period(
+ VL53L0X_VcselPeriod vcsel_period_type, uint8_t vcsel_pulse_period);
+
+ /**
+ * @brief Set low and high Interrupt thresholds for a given mode
+ * (ranging, ALS, ...) for a given device
+ *
+ * @par Function Description
+ * Set low and high Interrupt thresholds for a given mode (ranging, ALS, ...)
+ * for a given device
+ *
+ * @note This function Access to the device
+ *
+ * @note DeviceMode is ignored for the current device
+ *
+ *
+ * @param device_mode Device Mode for which change thresholds
+ * @param threshold_low Low threshold (mm, lux ..., depending on the mode)
+ * @param threshold_high High threshold (mm, lux ..., depending on the mode)
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_interrupt_thresholds(
+ VL53L0X_DeviceModes device_mode, FixPoint1616_t threshold_low,
+ FixPoint1616_t threshold_high);
+
+ /**
+ * @brief Get high and low Interrupt thresholds for a given mode
+ * (ranging, ALS, ...) for a given device
+ *
+ * @par Function Description
+ * Get high and low Interrupt thresholds for a given mode (ranging, ALS, ...)
+ * for a given device
+ *
+ * @note This function Access to the device
+ *
+ * @note DeviceMode is ignored for the current device
+ *
+ *
+ * @param device_mode Device Mode from which read thresholds
+ * @param p_threshold_low Low threshold (mm, lux ..., depending on the mode)
+ * @param p_threshold_high High threshold (mm, lux ..., depending on the mode)
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_interrupt_thresholds(
+ VL53L0X_DeviceModes device_mode, FixPoint1616_t *p_threshold_low,
+ FixPoint1616_t *p_threshold_high);
+
+ /**
+ * @brief Reads the Device information for given Device
+ *
+ * @note This function Access to the device
+ * _device_info structure is directly filled
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_device_info( );
+
+ /**
+ * @brief Gets the (on/off) state of all sequence steps.
+ *
+ * @par Function Description
+ * This function retrieves the state of all sequence step in the scheduler.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param p_scheduler_sequence_steps Pointer to struct containing result.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_sequence_step_enables(
+ VL53L0X_SchedulerSequenceSteps_t *p_scheduler_sequence_steps);
+
+ /**
+ * @brief Sets the (on/off) state of a requested sequence step.
+ *
+ * @par Function Description
+ * This function enables/disables a requested sequence step.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param sequence_step_id Sequence step identifier.
+ * @param sequence_step_enabled Demanded state {0=Off,1=On}
+ * is enabled.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS Error SequenceStepId parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_sequence_step_enable(
+ VL53L0X_SequenceStepId sequence_step_id, uint8_t sequence_step_enabled);
+
+ /**
+ * @brief Gets the fraction enable parameter indicating the resolution of
+ * range measurements.
+ *
+ * @par Function Description
+ * Gets the fraction enable state, which translates to the resolution of
+ * range measurements as follows :Enabled:=0.25mm resolution,
+ * Not Enabled:=1mm resolution.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param p_enabled Output Parameter reporting the fraction enable state.
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_fraction_enable( uint8_t *p_enabled);
+
+ /**
+ * @brief Sets the resolution of range measurements.
+ * @par Function Description
+ * Set resolution of range measurements to either 0.25mm if
+ * fraction enabled or 1mm if not enabled.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param enable Enable high resolution
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_range_fraction_enable(uint8_t enable);
+
+ /**
+ * @brief Retrieve current device parameters
+ * @par Function Description
+ * Get actual parameters of the device
+ * @li Then start ranging operation.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_device_parameters Pointer to store current device parameters.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_device_parameters(
+ VL53L0X_DeviceParameters_t *p_device_parameters);
+
+
+ /*** End High level API ***/
+public:
+ /* api.h functions */
+
+ VL53L0X_Error sequence_step_enabled(VL53L0X_SequenceStepId sequence_step_id, uint8_t sequence_config,
+ uint8_t *p_sequence_step_enabled);
+
+ VL53L0X_Error VL53L0X_check_and_load_interrupt_settings(
+ uint8_t start_not_stopflag);
+
+
+ /* api_core.h functions */
+
+ VL53L0X_Error VL53L0X_get_info_from_device( uint8_t option);
+
+ VL53L0X_Error VL53L0X_device_read_strobe(void);
+
+ uint8_t VL53L0X_decode_vcsel_period(uint8_t vcsel_period_reg);
+
+ uint32_t VL53L0X_decode_timeout(uint16_t encoded_timeout);
+
+ uint32_t VL53L0X_calc_timeout_us(
+ uint16_t timeout_period_mclks,
+ uint8_t vcsel_period_pclks);
+
+ uint32_t VL53L0X_calc_macro_period_ps( uint8_t vcsel_period_pclks);
+
+ VL53L0X_Error VL53L0X_measurement_poll_for_completion(void);
+
+ VL53L0X_Error VL53L0X_load_tuning_settings(
+ uint8_t *p_tuning_setting_buffer);
+
+ VL53L0X_Error VL53L0X_get_pal_range_status( uint8_t device_range_status,
+ FixPoint1616_t signal_rate, uint16_t effective_spad_rtn_count,
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ uint8_t *p_pal_range_status);
+ VL53L0X_Error VL53L0X_calc_sigma_estimate(
+ VL53L0X_RangingMeasurementData_t *p_ranging_measurement_data,
+ FixPoint1616_t *p_sigma_estimate,
+ uint32_t *p_dmax_mm);
+ uint32_t VL53L0X_calc_timeout_mclks( uint32_t timeout_period_us,
+ uint8_t vcsel_period_pclks);
+ uint32_t VL53L0X_isqrt(uint32_t num);
+
+ uint32_t VL53L0X_quadrature_sum(uint32_t a, uint32_t b);
+
+ VL53L0X_Error VL53L0X_calc_dmax(
+ FixPoint1616_t total_signal_rate_MHz,
+ FixPoint1616_t total_corr_signal_rate_MHz,
+ FixPoint1616_t pw_mult,
+ uint32_t sigma_estimate_p1,
+ FixPoint1616_t sigma_estimate_p2,
+ uint32_t peak_vcsel_duration_us,
+ uint32_t *pd_max_mm);
+ VL53L0X_Error wrapped_VL53L0X_set_measurement_timing_budget_us(
+ uint32_t measurement_timing_budget_us);
+ VL53L0X_Error get_sequence_step_timeout(VL53L0X_SequenceStepId sequence_step_id,
+ uint32_t *p_time_out_micro_secs);
+ VL53L0X_Error set_sequence_step_timeout(VL53L0X_SequenceStepId sequence_step_id,
+ uint32_t timeout_micro_secs);
+ uint16_t VL53L0X_encode_timeout(uint32_t timeout_macro_clks);
+ VL53L0X_Error wrapped_VL53L0X_set_vcsel_pulse_period(
+ VL53L0X_VcselPeriod vcsel_period_type, uint8_t vcsel_pulse_period_pclk);
+ uint8_t lv53l0x_encode_vcsel_period(uint8_t vcsel_period_pclks);
+
+ /* api_calibration.h functions */
+ VL53L0X_Error VL53L0X_apply_offset_adjustment(void);
+ VL53L0X_Error wrapped_VL53L0X_perform_ref_spad_management(
+ uint32_t *ref_spad_count,
+ uint8_t *is_aperture_spads);
+ VL53L0X_Error VL53L0X_perform_ref_calibration(
+ uint8_t *p_vhv_settings, uint8_t *p_phase_cal, uint8_t get_data_enable);
+ VL53L0X_Error VL53L0X_perform_vhv_calibration(
+ uint8_t *p_vhv_settings, const uint8_t get_data_enable,
+ const uint8_t restore_config);
+ VL53L0X_Error VL53L0X_perform_single_ref_calibration(
+ uint8_t vhv_init_byte);
+ VL53L0X_Error VL53L0X_ref_calibration_io( uint8_t read_not_write,
+ uint8_t vhv_settings, uint8_t phase_cal,
+ uint8_t *p_vhv_settings, uint8_t *p_phase_cal,
+ const uint8_t vhv_enable, const uint8_t phase_enable);
+ VL53L0X_Error VL53L0X_perform_phase_calibration(
+ uint8_t *p_phase_cal, const uint8_t get_data_enable,
+ const uint8_t restore_config);
+ VL53L0X_Error enable_ref_spads(uint8_t aperture_spads,
+ uint8_t good_spad_array[],
+ uint8_t spad_array[],
+ uint32_t size,
+ uint32_t start,
+ uint32_t offset,
+ uint32_t spad_count,
+ uint32_t *p_last_spad);
+ void get_next_good_spad(uint8_t good_spad_array[], uint32_t size,
+ uint32_t curr, int32_t *p_next);
+ uint8_t is_aperture(uint32_t spad_index);
+ VL53L0X_Error enable_spad_bit(uint8_t spad_array[], uint32_t size,
+ uint32_t spad_index);
+ VL53L0X_Error set_ref_spad_map( uint8_t *p_ref_spad_array);
+ VL53L0X_Error get_ref_spad_map( uint8_t *p_ref_spad_array);
+ VL53L0X_Error perform_ref_signal_measurement(
+ uint16_t *p_ref_signal_rate);
+ VL53L0X_Error wrapped_VL53L0X_set_reference_spads(
+ uint32_t count, uint8_t is_aperture_spads);
+
+ /* api_strings.h functions */
+ VL53L0X_Error VL53L0X_check_part_used(uint8_t *revision);
+
+ /* Read function of the ID device */
+ // virtual int read_id();
+ virtual int read_id(uint8_t *id);
+
+ VL53L0X_Error wait_measurement_data_ready(void);
+
+ VL53L0X_Error wait_stop_completed(void);
+
+
+ /**
+ * @brief execute delay in all polling API call
+ *
+ * A typical multi-thread or RTOs implementation is to sleep the task for some 5ms (with 100Hz max rate faster polling is not needed)
+ * if nothing specific is need you can define it as an empty/void macro
+ * @code
+ * #define VL53L0X_PollingDelay(...) (void)0
+ * @endcode
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_polling_delay(void); /* usually best implemented as a real function */
+
+ ///////////////////////////////////////////////////////////////////////////////////////////////////////
+ //Added functions //
+ ///////////////////////////////////////////////////////////////////////////////////////////////////////
+
+ /**
+ * @brief Cycle Power to Device
+ *
+ * @return status - status 0 = ok, 1 = error
+ *
+ */
+ int32_t VL53L0X_cycle_power(void);
+
+ uint8_t VL53L0X_encode_vcsel_period(uint8_t vcsel_period_pclks);
+
+ VL53L0X_Error wrapped_VL53L0X_get_limit_check_info( uint16_t limit_check_id,
+ char *p_limit_check_string);
+
+ VL53L0X_Error wrapped_VL53L0X_get_ref_calibration(
+ uint8_t *p_vhv_settings, uint8_t *p_phase_cal);
+
+
+ VL53L0X_Error count_enabled_spads(uint8_t spad_array[],
+ uint32_t byte_count, uint32_t max_spads,
+ uint32_t *p_total_spads_enabled, uint8_t *p_is_aperture);
+
+ VL53L0X_Error wrapped_VL53L0X_get_sequence_steps_info(VL53L0X_SequenceStepId sequence_step_id,
+ char *p_sequence_steps_string);
+
+
+ /**
+ * @brief Gets the name of a given sequence step.
+ *
+ * @par Function Description
+ * This function retrieves the name of sequence steps corresponding to
+ * SequenceStepId.
+ *
+ * @note This function doesn't Accesses the device
+ *
+ * @param sequence_step_id Sequence step identifier.
+ * @param p_sequence_steps_string Pointer to Info string
+ *
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_sequence_steps_info(VL53L0X_SequenceStepId sequence_step_id,
+ char *p_sequence_steps_string);
+
+ /**
+ * @brief Get the frequency of the timer used for ranging results time stamps
+ *
+ * @param[out] p_timer_freq_hz : pointer for timer frequency
+ *
+ * @return status : 0 = ok, 1 = error
+ *
+ */
+ int32_t VL53L0X_get_timer_frequency(int32_t *p_timer_freq_hz);
+
+ /**
+ * @brief Get the timer value in units of timer_freq_hz (see VL53L0X_get_timestamp_frequency())
+ *
+ * @param[out] p_timer_count : pointer for timer count value
+ *
+ * @return status : 0 = ok, 1 = error
+ *
+ */
+ int32_t VL53L0X_get_timer_value(int32_t *p_timer_count);
+
+ /**
+ * @brief Get Dmax Calibration Parameters for a given device
+ *
+ * @note This function Access to the device
+ *
+ * @param p_range_milli_meter Pointer to Calibration Distance
+ * @param p_signal_rate_rtn_MHz Pointer to Signal rate return
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_dmax_cal_parameters(
+ uint16_t *p_range_milli_meter, FixPoint1616_t *p_signal_rate_rtn_MHz);
+
+ /**
+ * @brief Set Dmax Calibration Parameters for a given device
+ * When one of the parameter is zero, this function will get parameter
+ * from NVM.
+ * @note This function doesn't Access to the device
+ *
+ *
+ * @param range_milli_meter Calibration Distance
+ * @param signal_rate_rtn_MHz Signal rate return read at CalDistance
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_dmax_cal_parameters(
+ uint16_t range_milli_meter, FixPoint1616_t signal_rate_rtn_MHz);
+
+
+
+ /**
+ * @brief Return a description string for a given limit check number
+ *
+ * @par Function Description
+ * This function returns a description string for a given limit check number.
+ * The limit check is identified with the LimitCheckId.
+ *
+ * @note This function doesn't Access to the device
+ *
+ *
+ * @param limit_check_id Limit Check ID
+ (0<= LimitCheckId < VL53L0X_GetNumberOfLimitCheck() ).
+ * @param p_limit_check_string Pointer to the
+ description string of the given check limit.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS This error is
+ returned when LimitCheckId value is out of range.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_limit_check_info(
+ uint16_t limit_check_id, char *p_limit_check_string);
+
+ /**
+ * @brief Get the linearity corrective gain
+ *
+ * @par Function Description
+ * Should only be used after a successful call to @a VL53L0X_DataInit to backup
+ * device NVM value
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_linearity_corrective_gain Pointer to the linearity
+ * corrective gain in x1000
+ * if value is 1000 then no modification is applied.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_linearity_corrective_gain(
+ uint16_t *p_linearity_corrective_gain);
+
+ /**
+ * Set the linearity corrective gain
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param linearity_corrective_gain Linearity corrective
+ * gain in x1000
+ * if value is 1000 then no modification is applied.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_linearity_corrective_gain(
+ int16_t linearity_corrective_gain);
+
+ /**
+ * @brief Get the Maximum number of ROI Zones managed by the Device
+ *
+ * @par Function Description
+ * Get Maximum number of ROI Zones managed by the Device.
+ *
+ * @note This function doesn't Access to the device
+ *
+ *
+ * @param p_max_number_of_roi_zones Pointer to the Maximum Number
+ * of ROI Zones value.
+ * @return VL53L0X_ERROR_NONE Success
+ */
+ VL53L0X_Error VL53L0X_get_max_number_of_roi_zones(
+ uint8_t *p_max_number_of_roi_zones);
+
+ /**
+ * @brief Retrieve the Reference Signal after a measurements
+ *
+ * @par Function Description
+ * Get Reference Signal from last successful Ranging measurement
+ * This function return a valid value after that you call the
+ * @a VL53L0X_GetRangingMeasurementData().
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_measurement_ref_signal Pointer to the Ref Signal to fill up.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_measurement_ref_signal(
+ FixPoint1616_t *p_measurement_ref_signal);
+
+ /**
+ * @brief Get the number of the check limit managed by a given Device
+ *
+ * @par Function Description
+ * This function give the number of the check limit managed by the Device
+ *
+ * @note This function doesn't Access to the device
+ *
+ * @param p_number_of_limit_check Pointer to the number of check limit.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_number_of_limit_check(
+ uint16_t *p_number_of_limit_check);
+
+ /**
+ * @brief Gets number of sequence steps managed by the API.
+ *
+ * @par Function Description
+ * This function retrieves the number of sequence steps currently managed
+ * by the API
+ *
+ * @note This function Accesses the device
+ *
+ * @param p_number_of_sequence_steps Out parameter reporting the number of
+ * sequence steps.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_number_of_sequence_steps(
+ uint8_t *p_number_of_sequence_steps);
+ /**
+ * @brief Get the power mode for a given Device
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_power_mode Pointer to the current value of the power
+ * mode. see ::VL53L0X_PowerModes
+ * Valid values are:
+ * VL53L0X_POWERMODE_STANDBY_LEVEL1,
+ * VL53L0X_POWERMODE_IDLE_LEVEL1
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_power_mode(
+ VL53L0X_PowerModes *p_power_mode);
+
+ /**
+ * @brief Set the power mode for a given Device
+ * The power mode can be Standby or Idle. Different level of both Standby and
+ * Idle can exists.
+ * This function should not be used when device is in Ranging state.
+ *
+ * @note This function Access to the device
+ *
+ * @param power_mode The value of the power mode to set.
+ * see ::VL53L0X_PowerModes
+ * Valid values are:
+ * VL53L0X_POWERMODE_STANDBY_LEVEL1,
+ * VL53L0X_POWERMODE_IDLE_LEVEL1
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_MODE_NOT_SUPPORTED This error occurs when PowerMode
+ * is not in the supported list
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_power_mode(VL53L0X_PowerModes power_mode);
+
+ /**
+ * @brief Retrieves SPAD configuration
+ *
+ * @par Function Description
+ * This function retrieves the current number of applied reference spads
+ * and also their type : Aperture or Non-Aperture.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_spad_count Number ref Spad Count
+ * @param p_is_aperture_spads Reports if spads are of type
+ * aperture or non-aperture.
+ * 1:=aperture, 0:=Non-Aperture
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_REF_SPAD_INIT Error in the in the reference
+ * spad configuration.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error wrapped_VL53L0X_get_reference_spads(
+ uint32_t *p_spad_count, uint8_t *p_is_aperture_spads);
+
+ /**
+ * @brief Gets the (on/off) state of a requested sequence step.
+ *
+ * @par Function Description
+ * This function retrieves the state of a requested sequence step, i.e. on/off.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param sequence_step_id Sequence step identifier.
+ * @param p_sequence_step_enabled Out parameter reporting if the sequence step
+ * is enabled {0=Off,1=On}.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS Error SequenceStepId parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_sequence_step_enable(
+ VL53L0X_SequenceStepId sequence_step_id, uint8_t *p_sequence_step_enabled);
+
+ /**
+ * @brief Gets the timeout of a requested sequence step.
+ *
+ * @par Function Description
+ * This function retrieves the timeout of a requested sequence step.
+ *
+ * @note This function Accesses the device
+ *
+ * @param sequence_step_id Sequence step identifier.
+ * @param p_time_out_milli_secs Timeout value.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS Error SequenceStepId parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_sequence_step_timeout(VL53L0X_SequenceStepId sequence_step_id,
+ FixPoint1616_t *p_time_out_milli_secs);
+
+ /**
+ * @brief Sets the timeout of a requested sequence step.
+ *
+ * @par Function Description
+ * This function sets the timeout of a requested sequence step.
+ *
+ * @note This function Accesses the device
+ *
+ *
+ * @param sequence_step_id Sequence step identifier.
+ * @param time_out_milli_secs Demanded timeout
+ * @return VL53L0X_ERROR_NONE Success
+ * @return VL53L0X_ERROR_INVALID_PARAMS Error SequenceStepId parameter not
+ * supported.
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_sequence_step_timeout(
+ VL53L0X_SequenceStepId sequence_step_id, FixPoint1616_t time_out_milli_secs);
+
+ /**
+ * @brief Get the tuning settings pointer and the internal external switch
+ * value.
+ *
+ * This function is used to get the Tuning settings buffer pointer and the
+ * value.
+ * of the switch to select either external or internal tuning settings.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param pp_tuning_setting_buffer Pointer to tuning settings buffer.
+ * @param p_use_internal_tuning_settings Pointer to store Use internal tuning
+ * settings value.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_get_tuning_setting_buffer(
+ uint8_t **pp_tuning_setting_buffer, uint8_t *p_use_internal_tuning_settings);
+
+ /**
+ * @brief Set the tuning settings pointer
+ *
+ * This function is used to specify the Tuning settings buffer to be used
+ * for a given device. The buffer contains all the necessary data to permit
+ * the API to write tuning settings.
+ * This function permit to force the usage of either external or internal
+ * tuning settings.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param p_tuning_setting_buffer Pointer to tuning settings buffer.
+ * @param use_internal_tuning_settings Use internal tuning settings value.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error VL53L0X_set_tuning_setting_buffer(
+ uint8_t *p_tuning_setting_buffer, uint8_t use_internal_tuning_settings);
+
+ /**
+ * @defgroup VL53L0X_registerAccess_group PAL Register Access Functions
+ * @brief PAL Register Access Functions
+ * @{
+ */
+
+ /**
+ * @brief Prepare device for operation
+ * @par Function Description
+ * Update device with provided parameters
+ * @li Then start ranging operation.
+ *
+ * @note This function Access to the device
+ *
+ *
+ * @param pDeviceParameters Pointer to store current device parameters.
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error
+ */
+ VL53L0X_Error vl53L0x_set_device_parameters(
+ const VL53L0X_DeviceParameters_t *pDeviceParameters);
+
+ VL53L0X_Error VL53L0X_reverse_bytes(uint8_t *data, uint32_t size);
+
+ int range_meas_int_continuous_mode(void (*fptr)(void));
+
+ /* Digital out pin */
+ DigitalOut *_gpio0;
+ /* Measure detection IRQ */
+ InterruptIn *_gpio1Int;
+
+ VL53L0X_DevData_t Data;
+ VL53L0X_DeviceInfo_t Device_Info;
+ VL53L0X_DeviceParameters_t CurrentParameters; /*!< Current Device Parameter */
+ VL53L0X_RangingMeasurementData_t LastRangeMeasure; /*!< Last Performed Ranging Data */
+
+public:
+ /* IO Device */
+ I2C *_dev_i2c;
+ uint8_t I2cDevAddr; /*!< i2c device address user specific field */
+ uint8_t comms_type; /*!< Type of comms : VL53L0X_COMMS_I2C or VL53L0X_COMMS_SPI */
+ uint16_t comms_speed_khz; /*!< Comms speed [kHz] : typically 400kHz for I2C */
+
+ /* Write and read functions from I2C */
+ /** Write single byte register
+ *
+ * @param index The register index
+ * @param data 8 bit register data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+
+ VL53L0X_Error VL53L0X_write_byte( uint8_t index, uint8_t data);
+ /** Write word register
+ *
+ * @param index The register index
+ * @param data 16 bit register data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+
+ VL53L0X_Error VL53L0X_write_word( uint8_t index, uint16_t data);
+ /** Write double word (4 byte) register
+ *
+ * @param index The register index
+ * @param data 32 bit register data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+
+ VL53L0X_Error VL53L0X_write_dword( uint8_t index, uint32_t data);
+ /** Read single byte register
+ *
+ * @param index The register index
+ * @param data pointer to 8 bit data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+
+ VL53L0X_Error VL53L0X_read_byte( uint8_t index, uint8_t *p_data);
+ /** Read word (2byte) register
+ *
+ * @param index The register index
+ * @param data pointer to 16 bit data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+
+ VL53L0X_Error VL53L0X_read_word( uint8_t index, uint16_t *p_data);
+ /** Read dword (4byte) register
+ *
+ * @param index The register index
+ * @param data pointer to 32 bit data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+ VL53L0X_Error VL53L0X_read_dword( uint8_t index, uint32_t *p_data);
+
+ /** Thread safe Update (read/modify/write) single byte register
+ *
+ * Final_reg = (Initial_reg & and_data) |or_data
+ *
+ * @param index The register index
+ * @param and_data 8 bit and data
+ * @param or_data 8 bit or data
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+ VL53L0X_Error VL53L0X_update_byte( uint8_t index, uint8_t and_data, uint8_t or_data);
+
+ /** Reads the requested number of bytes from the device
+ *
+ * @param index The register index
+ * @param p_data Pointer to the uint8_t buffer to store read data
+ * @param count Number of uint8_t's to read
+ * @return VL53L0X_ERROR_NONE Success
+ * @return "Other error code" See ::VL53L0X_Error */
+ VL53L0X_Error VL53L0X_read_multi( uint8_t index, uint8_t *p_data, uint32_t count);
+
+ /** @brief Writes a buffer towards the I2C peripheral device.
+ *
+ * @param p_data pointer to the byte-array data to send
+ * @param number_of_bytes number of bytes to be written.
+ * @retval 0 if ok,
+ * @retval -1 if an I2C error has occured
+ * @note On some devices if NumByteToWrite is greater
+ * than one, the RegisterAddr must be masked correctly! */
+ VL53L0X_Error VL53L0X_i2c_write(uint8_t index, uint8_t *p_data, uint16_t number_of_bytes);
+
+ /** @brief Reads a buffer from the I2C peripheral device.
+ *
+ * @param p_data pointer to the byte-array to read data in to
+ * @param number_of_bytes number of bytes to be read.
+ * @retval 0 if ok,
+ * @retval -1 if an I2C error has occured
+ * @note On some devices if NumByteToWrite is greater
+ * than one, the RegisterAddr must be masked correctly! */
+ VL53L0X_Error VL53L0X_i2c_read(uint8_t index, uint8_t *p_data, uint16_t number_of_bytes);
+};
+
+void Report_Deep_Infos (VL53L0X TOF1, Serial *aSerial);
+void Report_Range_Infos(VL53L0X_RangingMeasurementData_t RangeResults, Serial *aSerial);
+
+#endif /* _VL53L0X_CLASS_H_ */
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/VL53L0X_def.h Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,752 @@
+/*******************************************************************************
+Copyright © 2016, 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 VL53L0X_def.h
+ *
+ * @brief Type definitions for VL53L0X API. */
+
+#ifndef _VL53L0X_DEF_H_
+#define _VL53L0X_DEF_H_
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/** @defgroup VL53L0X_globaldefine_group VL53L0X Defines
+ * @brief VL53L0X Defines
+ * @{ */
+/** PAL SPECIFICATION major version */
+#define VL53L0X10_SPECIFICATION_VER_MAJOR 1
+/** PAL SPECIFICATION minor version */
+#define VL53L0X10_SPECIFICATION_VER_MINOR 2
+/** PAL SPECIFICATION sub version */
+#define VL53L0X10_SPECIFICATION_VER_SUB 7
+/** PAL SPECIFICATION sub version */
+#define VL53L0X10_SPECIFICATION_VER_REVISION 1440
+
+/** VL53L0X PAL IMPLEMENTATION major version */
+#define VL53L0X10_IMPLEMENTATION_VER_MAJOR 1
+/** VL53L0X PAL IMPLEMENTATION minor version */
+#define VL53L0X10_IMPLEMENTATION_VER_MINOR 0
+/** VL53L0X PAL IMPLEMENTATION sub version */
+#define VL53L0X10_IMPLEMENTATION_VER_SUB 9
+/** VL53L0X PAL IMPLEMENTATION sub version */
+#define VL53L0X10_IMPLEMENTATION_VER_REVISION 3673
+
+/** PAL SPECIFICATION major version */
+#define VL53L0X_SPECIFICATION_VER_MAJOR 1
+/** PAL SPECIFICATION minor version */
+#define VL53L0X_SPECIFICATION_VER_MINOR 2
+/** PAL SPECIFICATION sub version */
+#define VL53L0X_SPECIFICATION_VER_SUB 7
+/** PAL SPECIFICATION sub version */
+#define VL53L0X_SPECIFICATION_VER_REVISION 1440
+
+/** VL53L0X PAL IMPLEMENTATION major version */
+#define VL53L0X_IMPLEMENTATION_VER_MAJOR 1
+/** VL53L0X PAL IMPLEMENTATION minor version */
+#define VL53L0X_IMPLEMENTATION_VER_MINOR 1
+/** VL53L0X PAL IMPLEMENTATION sub version */
+#define VL53L0X_IMPLEMENTATION_VER_SUB 21
+/** VL53L0X PAL IMPLEMENTATION sub version */
+#define VL53L0X_IMPLEMENTATION_VER_REVISION 4823
+
+/** FixPoint1616_t is used where fractional values are needed
+ * Given a floating point value f it's .16 bit point is (int)(f*(1<<16))*/
+typedef uint32_t FixPoint1616_t;
+#define VL53L0X_FP1616TOFP97(Value) (uint16_t)((Value>>9)&0xFFFF)
+#define VL53L0X_FP97TOFP1616(Value) (FixPoint1616_t)(Value<<9)
+#define VL53L0X_FP1616TOFP88(Value) (uint16_t)((Value>>8)&0xFFFF)
+#define VL53L0X_FP88TOFP1616(Value) (FixPoint1616_t)(Value<<8)
+#define VL53L0X_FP1616TOFP412(Value) (uint16_t)((Value>>4)&0xFFFF)
+#define VL53L0X_FP412TOFP1616(Value) (FixPoint1616_t)(Value<<4)
+#define VL53L0X_FP1616TOFP313(Value) (uint16_t)((Value>>3)&0xFFFF)
+#define VL53L0X_FP313TOFP1616(Value) (FixPoint1616_t)(Value<<3)
+#define VL53L0X_FP1616TOFP08(Value) (uint8_t)((Value>>8)&0x00FF)
+#define VL53L0X_FP08TOFP1616(Value) (FixPoint1616_t)(Value<<8)
+#define VL53L0X_FP1616TOFP53(Value) (uint8_t)((Value>>13)&0x00FF)
+#define VL53L0X_FP53TOFP1616(Value) (FixPoint1616_t)(Value<<13)
+#define VL53L0X_FP1616TOFP102(Value) (uint16_t)((Value>>14)&0x0FFF)
+#define VL53L0X_FP102TOFP1616(Value) (FixPoint1616_t)(Value<<12)
+#define VL53L0X_MAKEUINT16(lsb, msb) (uint16_t)((((uint16_t)msb)<<8) + (uint16_t)lsb)
+
+
+/** The device model ID */
+#define IDENTIFICATION_MODEL_ID 0x000
+
+#define VL53L0X_OsDelay(...) wait_ms(2) // 2 msec delay. can also use wait(float secs)/wait_us(int)
+
+/** Maximum buffer size to be used in i2c */
+#define VL53L0X_MAX_I2C_XFER_SIZE 64
+
+#define VL53L0X_COPYSTRING(str, ...) strcpy(str, ##__VA_ARGS__)
+
+/* Speed of light in um per 1E-10 Seconds */
+#define VL53L0X_SPEED_OF_LIGHT_IN_AIR 2997
+
+/** default device address */
+#define VL53L0X_DEFAULT_ADDRESS 0x52 /* (8-bit) */
+
+#define VL53L0X_DEFAULT_MAX_LOOP 2000
+
+#define VL53L0X_MAX_STRING_LENGTH 32
+
+/* equivalent to a range sigma of 655.35mm */
+#define VL53L0X_SIGMA_ESTIMATE_MAX_VALUE 65535
+
+#define REF_ARRAY_SPAD_0 0
+#define REF_ARRAY_SPAD_5 5
+#define REF_ARRAY_SPAD_10 10
+
+static uint32_t refArrayQuadrants[4] = {REF_ARRAY_SPAD_10, REF_ARRAY_SPAD_5,
+ REF_ARRAY_SPAD_0, REF_ARRAY_SPAD_5 };
+
+#define VL53L0X_STRING_DEVICE_INFO_NAME "VL53L0X cut1.0"
+#define VL53L0X_STRING_DEVICE_INFO_NAME_TS0 "VL53L0X TS0"
+#define VL53L0X_STRING_DEVICE_INFO_NAME_TS1 "VL53L0X TS1"
+#define VL53L0X_STRING_DEVICE_INFO_NAME_TS2 "VL53L0X TS2"
+#define VL53L0X_STRING_DEVICE_INFO_NAME_ES1 "VL53L0X ES1 or later"
+#define VL53L0X_STRING_DEVICE_INFO_TYPE "VL53L0X"
+
+/* sensor operating modes */
+typedef enum {
+ range_single_shot_polling = 1,
+ range_continuous_polling,
+ range_continuous_interrupt,
+ range_continuous_polling_low_threshold,
+ range_continuous_polling_high_threshold,
+ range_continuous_polling_out_of_window,
+ range_continuous_interrupt_low_threshold,
+ range_continuous_interrupt_high_threshold,
+ range_continuous_interrupt_out_of_window,
+} OperatingMode;
+
+/** @defgroup VL53L0X_DeviceError_group Device Error
+ * @brief Device Error code
+ *
+ * This enum is Device specific it should be updated in the implementation
+ * Use @a VL53L0X_GetStatusErrorString() to get the string.
+ * It is related to Status Register of the Device.
+ * @{ */
+typedef uint8_t VL53L0X_DeviceError;
+#define VL53L0X_DEVICEERROR_NONE ((VL53L0X_DeviceError) 0) /*!< 0 NoError */
+#define VL53L0X_DEVICEERROR_VCSELCONTINUITYTESTFAILURE ((VL53L0X_DeviceError) 1)
+#define VL53L0X_DEVICEERROR_VCSELWATCHDOGTESTFAILURE ((VL53L0X_DeviceError) 2)
+#define VL53L0X_DEVICEERROR_NOVHVVALUEFOUND ((VL53L0X_DeviceError) 3)
+#define VL53L0X_DEVICEERROR_MSRCNOTARGET ((VL53L0X_DeviceError) 4)
+#define VL53L0X_DEVICEERROR_SNRCHECK ((VL53L0X_DeviceError) 5)
+#define VL53L0X_DEVICEERROR_RANGEPHASECHECK ((VL53L0X_DeviceError) 6)
+#define VL53L0X_DEVICEERROR_SIGMATHRESHOLDCHECK ((VL53L0X_DeviceError) 7)
+#define VL53L0X_DEVICEERROR_TCC ((VL53L0X_DeviceError) 8)
+#define VL53L0X_DEVICEERROR_PHASECONSISTENCY ((VL53L0X_DeviceError) 9)
+#define VL53L0X_DEVICEERROR_MINCLIP ((VL53L0X_DeviceError) 10)
+#define VL53L0X_DEVICEERROR_RANGECOMPLETE ((VL53L0X_DeviceError) 11)
+#define VL53L0X_DEVICEERROR_ALGOUNDERFLOW ((VL53L0X_DeviceError) 12)
+#define VL53L0X_DEVICEERROR_ALGOOVERFLOW ((VL53L0X_DeviceError) 13)
+#define VL53L0X_DEVICEERROR_RANGEIGNORETHRESHOLD ((VL53L0X_DeviceError) 14)
+/** @} end of VL53L0X_DeviceError_group */
+
+
+/* PAL ERROR strings */
+#define VL53L0X_STRING_ERROR_NONE "No Error"
+#define VL53L0X_STRING_ERROR_CALIBRATION_WARNING "Calibration Warning Error"
+#define VL53L0X_STRING_ERROR_MIN_CLIPPED "Min clipped error"
+#define VL53L0X_STRING_ERROR_UNDEFINED "Undefined error"
+#define VL53L0X_STRING_ERROR_INVALID_PARAMS "Invalid parameters error"
+#define VL53L0X_STRING_ERROR_NOT_SUPPORTED "Not supported error"
+#define VL53L0X_STRING_ERROR_RANGE_ERROR "Range error"
+#define VL53L0X_STRING_ERROR_TIME_OUT "Time out error"
+#define VL53L0X_STRING_ERROR_MODE_NOT_SUPPORTED "Mode not supported error"
+#define VL53L0X_STRING_ERROR_BUFFER_TOO_SMALL "Buffer too small"
+#define VL53L0X_STRING_ERROR_GPIO_NOT_EXISTING "GPIO not existing"
+#define VL53L0X_STRING_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED "GPIO funct not supported"
+#define VL53L0X_STRING_ERROR_INTERRUPT_NOT_CLEARED "Interrupt not Cleared"
+#define VL53L0X_STRING_ERROR_CONTROL_INTERFACE "Control Interface Error"
+#define VL53L0X_STRING_ERROR_INVALID_COMMAND "Invalid Command Error"
+#define VL53L0X_STRING_ERROR_DIVISION_BY_ZERO "Division by zero Error"
+#define VL53L0X_STRING_ERROR_REF_SPAD_INIT "Reference Spad Init Error"
+#define VL53L0X_STRING_UNKNOW_ERROR_CODE "Unknown Error Code"
+
+/* Range Status */
+#define VL53L0X_STRING_RANGESTATUS_NONE "No Update"
+#define VL53L0X_STRING_RANGESTATUS_RANGEVALID "Range Valid"
+#define VL53L0X_STRING_RANGESTATUS_SIGMA "Sigma Fail"
+#define VL53L0X_STRING_RANGESTATUS_SIGNAL "Signal Fail"
+#define VL53L0X_STRING_RANGESTATUS_MINRANGE "Min Range Fail"
+#define VL53L0X_STRING_RANGESTATUS_PHASE "Phase Fail"
+#define VL53L0X_STRING_RANGESTATUS_HW "Hardware Fail"
+
+/* Range Status */
+#define VL53L0X_STRING_STATE_POWERDOWN "POWERDOWN State"
+#define VL53L0X_STRING_STATE_WAIT_STATICINIT "Wait for staticinit State"
+#define VL53L0X_STRING_STATE_STANDBY "STANDBY State"
+#define VL53L0X_STRING_STATE_IDLE "IDLE State"
+#define VL53L0X_STRING_STATE_RUNNING "RUNNING State"
+#define VL53L0X_STRING_STATE_UNKNOWN "UNKNOWN State"
+#define VL53L0X_STRING_STATE_ERROR "ERROR State"
+
+/* Device Specific */
+#define VL53L0X_STRING_DEVICEERROR_NONE "No Update"
+#define VL53L0X_STRING_DEVICEERROR_VCSELCONTINUITYTESTFAILURE "VCSEL Continuity Test Failure"
+#define VL53L0X_STRING_DEVICEERROR_VCSELWATCHDOGTESTFAILURE "VCSEL Watchdog Test Failure"
+#define VL53L0X_STRING_DEVICEERROR_NOVHVVALUEFOUND "No VHV Value found"
+#define VL53L0X_STRING_DEVICEERROR_MSRCNOTARGET "MSRC No Target Error"
+#define VL53L0X_STRING_DEVICEERROR_SNRCHECK "SNR Check Exit"
+#define VL53L0X_STRING_DEVICEERROR_RANGEPHASECHECK "Range Phase Check Error"
+#define VL53L0X_STRING_DEVICEERROR_SIGMATHRESHOLDCHECK "Sigma Threshold Check Error"
+#define VL53L0X_STRING_DEVICEERROR_TCC "TCC Error"
+#define VL53L0X_STRING_DEVICEERROR_PHASECONSISTENCY "Phase Consistency Error"
+#define VL53L0X_STRING_DEVICEERROR_MINCLIP "Min Clip Error"
+#define VL53L0X_STRING_DEVICEERROR_RANGECOMPLETE "Range Complete"
+#define VL53L0X_STRING_DEVICEERROR_ALGOUNDERFLOW "Range Algo Underflow Error"
+#define VL53L0X_STRING_DEVICEERROR_ALGOOVERFLOW "Range Algo Overlow Error"
+#define VL53L0X_STRING_DEVICEERROR_RANGEIGNORETHRESHOLD "Range Ignore Threshold Error"
+#define VL53L0X_STRING_DEVICEERROR_UNKNOWN "Unknown error code"
+
+/* Check Enable */
+#define VL53L0X_STRING_CHECKENABLE_SIGMA_FINAL_RANGE "SIGMA FINAL RANGE"
+#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE "SIGNAL RATE FINAL RANGE"
+#define VL53L0X_STRING_CHECKENABLE_SIGNAL_REF_CLIP "SIGNAL REF CLIP"
+#define VL53L0X_STRING_CHECKENABLE_RANGE_IGNORE_THRESHOLD "RANGE IGNORE THRESHOLD"
+#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_MSRC "SIGNAL RATE MSRC"
+#define VL53L0X_STRING_CHECKENABLE_SIGNAL_RATE_PRE_RANGE "SIGNAL RATE PRE RANGE"
+
+/* Sequence Step */
+#define VL53L0X_STRING_SEQUENCESTEP_TCC "TCC"
+#define VL53L0X_STRING_SEQUENCESTEP_DSS "DSS"
+#define VL53L0X_STRING_SEQUENCESTEP_MSRC "MSRC"
+#define VL53L0X_STRING_SEQUENCESTEP_PRE_RANGE "PRE RANGE"
+#define VL53L0X_STRING_SEQUENCESTEP_FINAL_RANGE "FINAL RANGE"
+
+
+/** @defgroup VL53L0X_CheckEnable_group Check Enable list
+ * @brief Check Enable code
+ *
+ * Define used to specify the LimitCheckId.
+ * Use @a VL53L0X_GetLimitCheckInfo() to get the string.
+ * @{ */
+#define VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE 0
+#define VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE 1
+#define VL53L0X_CHECKENABLE_SIGNAL_REF_CLIP 2
+#define VL53L0X_CHECKENABLE_RANGE_IGNORE_THRESHOLD 3
+#define VL53L0X_CHECKENABLE_SIGNAL_RATE_MSRC 4
+#define VL53L0X_CHECKENABLE_SIGNAL_RATE_PRE_RANGE 5
+#define VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS 6
+/** @} end of VL53L0X_CheckEnable_group */
+
+
+
+/** @defgroup VL53L0X_DefineRegisters_group Define Registers
+ * @brief List of all the defined registers
+ * @{ */
+#define VL53L0X_REG_SYSRANGE_START 0x000
+/** mask existing bit in #VL53L0X_REG_SYSRANGE_START*/
+#define VL53L0X_REG_SYSRANGE_MODE_MASK 0x0F
+/** bit 0 in #VL53L0X_REG_SYSRANGE_START write 1 toggle state in
+ * continuous mode and arm next shot in single shot mode */
+#define VL53L0X_REG_SYSRANGE_MODE_START_STOP 0x01
+/** bit 1 write 0 in #VL53L0X_REG_SYSRANGE_START set single shot mode */
+#define VL53L0X_REG_SYSRANGE_MODE_SINGLESHOT 0x00
+/** bit 1 write 1 in #VL53L0X_REG_SYSRANGE_START set back-to-back operation mode */
+#define VL53L0X_REG_SYSRANGE_MODE_BACKTOBACK 0x02
+/** bit 2 write 1 in #VL53L0X_REG_SYSRANGE_START set timed operation mode */
+#define VL53L0X_REG_SYSRANGE_MODE_TIMED 0x04
+/** bit 3 write 1 in #VL53L0X_REG_SYSRANGE_START set histogram operation mode */
+#define VL53L0X_REG_SYSRANGE_MODE_HISTOGRAM 0x08
+#define VL53L0X_REG_SYSTEM_THRESH_HIGH 0x000C
+#define VL53L0X_REG_SYSTEM_THRESH_LOW 0x000E
+#define VL53L0X_REG_SYSTEM_SEQUENCE_CONFIG 0x0001
+#define VL53L0X_REG_SYSTEM_RANGE_CONFIG 0x0009
+#define VL53L0X_REG_SYSTEM_INTERMEASUREMENT_PERIOD 0x0004
+#define VL53L0X_REG_SYSTEM_INTERRUPT_CONFIG_GPIO 0x000A
+#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_DISABLED 0x00
+#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_LOW 0x01
+#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_LEVEL_HIGH 0x02
+#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_OUT_OF_WINDOW 0x03
+#define VL53L0X_REG_SYSTEM_INTERRUPT_GPIO_NEW_SAMPLE_READY 0x04
+#define VL53L0X_REG_GPIO_HV_MUX_ACTIVE_HIGH 0x0084
+#define VL53L0X_REG_SYSTEM_INTERRUPT_CLEAR 0x000B
+
+/* Result registers */
+#define VL53L0X_REG_RESULT_INTERRUPT_STATUS 0x0013
+#define VL53L0X_REG_RESULT_RANGE_STATUS 0x0014
+#define VL53L0X_REG_RESULT_CORE_PAGE 1
+#define VL53L0X_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_RTN 0x00BC
+#define VL53L0X_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_RTN 0x00C0
+#define VL53L0X_REG_RESULT_CORE_AMBIENT_WINDOW_EVENTS_REF 0x00D0
+#define VL53L0X_REG_RESULT_CORE_RANGING_TOTAL_EVENTS_REF 0x00D4
+#define VL53L0X_REG_RESULT_PEAK_SIGNAL_RATE_REF 0x00B6
+/* Algo register */
+#define VL53L0X_REG_ALGO_PART_TO_PART_RANGE_OFFSET_MM 0x0028
+#define VL53L0X_REG_I2C_SLAVE_DEVICE_ADDRESS 0x008a
+/* Check Limit registers */
+#define VL53L0X_REG_MSRC_CONFIG_CONTROL 0x0060
+#define VL53L0X_REG_PRE_RANGE_CONFIG_MIN_SNR 0X0027
+#define VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_LOW 0x0056
+#define VL53L0X_REG_PRE_RANGE_CONFIG_VALID_PHASE_HIGH 0x0057
+#define VL53L0X_REG_PRE_RANGE_MIN_COUNT_RATE_RTN_LIMIT 0x0064
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_SNR 0X0067
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_LOW 0x0047
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_VALID_PHASE_HIGH 0x0048
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_MIN_COUNT_RATE_RTN_LIMIT 0x0044
+#define VL53L0X_REG_PRE_RANGE_CONFIG_SIGMA_THRESH_HI 0X0061
+#define VL53L0X_REG_PRE_RANGE_CONFIG_SIGMA_THRESH_LO 0X0062
+
+/* PRE RANGE registers */
+#define VL53L0X_REG_PRE_RANGE_CONFIG_VCSEL_PERIOD 0x0050
+#define VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_HI 0x0051
+#define VL53L0X_REG_PRE_RANGE_CONFIG_TIMEOUT_MACROP_LO 0x0052
+#define VL53L0X_REG_SYSTEM_HISTOGRAM_BIN 0x0081
+#define VL53L0X_REG_HISTOGRAM_CONFIG_INITIAL_PHASE_SELECT 0x0033
+#define VL53L0X_REG_HISTOGRAM_CONFIG_READOUT_CTRL 0x0055
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_VCSEL_PERIOD 0x0070
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_HI 0x0071
+#define VL53L0X_REG_FINAL_RANGE_CONFIG_TIMEOUT_MACROP_LO 0x0072
+#define VL53L0X_REG_CROSSTALK_COMPENSATION_PEAK_RATE_MHz 0x0020
+#define VL53L0X_REG_MSRC_CONFIG_TIMEOUT_MACROP 0x0046
+#define VL53L0X_REG_SOFT_RESET_GO2_SOFT_RESET_N 0x00bf
+#define VL53L0X_REG_IDENTIFICATION_MODEL_ID 0x00c0
+#define VL53L0X_REG_IDENTIFICATION_REVISION_ID 0x00c2
+#define VL53L0X_REG_OSC_CALIBRATE_VAL 0x00f8
+#define VL53L0X_REG_GLOBAL_CONFIG_VCSEL_WIDTH 0x0032
+#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_0 0x00B0
+#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_1 0x00B1
+#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_2 0x00B2
+#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_3 0x00B3
+#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_4 0x00B4
+#define VL53L0X_REG_GLOBAL_CONFIG_SPAD_ENABLES_REF_5 0x00B5
+#define VL53L0X_REG_GLOBAL_CONFIG_REF_EN_START_SELECT 0x00B6
+#define VL53L0X_REG_DYNAMIC_SPAD_NUM_REQUESTED_REF_SPAD 0x004E /* 0x14E */
+#define VL53L0X_REG_DYNAMIC_SPAD_REF_EN_START_OFFSET 0x004F /* 0x14F */
+#define VL53L0X_REG_POWER_MANAGEMENT_GO1_POWER_FORCE 0x0080
+#define VL53L0X_REG_VHV_CONFIG_PAD_SCL_SDA__EXTSUP_HV 0x0089
+#define VL53L0X_REG_ALGO_PHASECAL_LIM 0x0030 /* 0x130 */
+#define VL53L0X_REG_ALGO_PHASECAL_CONFIG_TIMEOUT 0x0030
+/** @} VL53L0X_DefineRegisters_group */
+
+
+static uint8_t DefaultTuningSettings[] = {
+
+ /* update 02/11/2015_v36 */
+ 0x01, 0xFF, 0x01, 0x01, 0x00, 0x00, 0x01, 0xFF, 0x00, 0x01, 0x09, 0x00,
+ 0x01, 0x10, 0x00, 0x01, 0x11, 0x00, 0x01, 0x24, 0x01, 0x01, 0x25, 0xff,
+ 0x01, 0x75, 0x00, 0x01, 0xFF, 0x01, 0x01, 0x4e, 0x2c, 0x01, 0x48, 0x00,
+ 0x01, 0x30, 0x20, 0x01, 0xFF, 0x00, 0x01, 0x30, 0x09, /* mja changed from 0x64. */
+ 0x01, 0x54, 0x00, 0x01, 0x31, 0x04, 0x01, 0x32, 0x03, 0x01, 0x40, 0x83,
+ 0x01, 0x46, 0x25, 0x01, 0x60, 0x00, 0x01, 0x27, 0x00, 0x01, 0x50, 0x06,
+ 0x01, 0x51, 0x00, 0x01, 0x52, 0x96, 0x01, 0x56, 0x08, 0x01, 0x57, 0x30,
+ 0x01, 0x61, 0x00, 0x01, 0x62, 0x00, 0x01, 0x64, 0x00, 0x01, 0x65, 0x00,
+ 0x01, 0x66, 0xa0, 0x01, 0xFF, 0x01, 0x01, 0x22, 0x32, 0x01, 0x47, 0x14,
+ 0x01, 0x49, 0xff, 0x01, 0x4a, 0x00, 0x01, 0xFF, 0x00, 0x01, 0x7a, 0x0a,
+ 0x01, 0x7b, 0x00, 0x01, 0x78, 0x21, 0x01, 0xFF, 0x01, 0x01, 0x23, 0x34,
+ 0x01, 0x42, 0x00, 0x01, 0x44, 0xff, 0x01, 0x45, 0x26, 0x01, 0x46, 0x05,
+ 0x01, 0x40, 0x40, 0x01, 0x0E, 0x06, 0x01, 0x20, 0x1a, 0x01, 0x43, 0x40,
+ 0x01, 0xFF, 0x00, 0x01, 0x34, 0x03, 0x01, 0x35, 0x44, 0x01, 0xFF, 0x01,
+ 0x01, 0x31, 0x04, 0x01, 0x4b, 0x09, 0x01, 0x4c, 0x05, 0x01, 0x4d, 0x04,
+ 0x01, 0xFF, 0x00, 0x01, 0x44, 0x00, 0x01, 0x45, 0x20, 0x01, 0x47, 0x08,
+ 0x01, 0x48, 0x28, 0x01, 0x67, 0x00, 0x01, 0x70, 0x04, 0x01, 0x71, 0x01,
+ 0x01, 0x72, 0xfe, 0x01, 0x76, 0x00, 0x01, 0x77, 0x00, 0x01, 0xFF, 0x01,
+ 0x01, 0x0d, 0x01, 0x01, 0xFF, 0x00, 0x01, 0x80, 0x01, 0x01, 0x01, 0xF8,
+ 0x01, 0xFF, 0x01, 0x01, 0x8e, 0x01, 0x01, 0x00, 0x01, 0x01, 0xFF, 0x00,
+ 0x01, 0x80, 0x00, 0x00, 0x00, 0x00
+};
+
+static uint8_t InterruptThresholdSettings[] = {
+ /* Start of Interrupt Threshold Settings */
+ 0x1, 0xff, 0x00, 0x1, 0x80, 0x01, 0x1, 0xff, 0x01, 0x1, 0x00, 0x00,
+ 0x1, 0xff, 0x01, 0x1, 0x4f, 0x02, 0x1, 0xFF, 0x0E, 0x1, 0x00, 0x03,
+ 0x1, 0x01, 0x84, 0x1, 0x02, 0x0A, 0x1, 0x03, 0x03, 0x1, 0x04, 0x08,
+ 0x1, 0x05, 0xC8, 0x1, 0x06, 0x03, 0x1, 0x07, 0x8D, 0x1, 0x08, 0x08,
+ 0x1, 0x09, 0xC6, 0x1, 0x0A, 0x01, 0x1, 0x0B, 0x02, 0x1, 0x0C, 0x00,
+ 0x1, 0x0D, 0xD5, 0x1, 0x0E, 0x18, 0x1, 0x0F, 0x12, 0x1, 0x10, 0x01,
+ 0x1, 0x11, 0x82, 0x1, 0x12, 0x00, 0x1, 0x13, 0xD5, 0x1, 0x14, 0x18,
+ 0x1, 0x15, 0x13, 0x1, 0x16, 0x03, 0x1, 0x17, 0x86, 0x1, 0x18, 0x0A,
+ 0x1, 0x19, 0x09, 0x1, 0x1A, 0x08, 0x1, 0x1B, 0xC2, 0x1, 0x1C, 0x03,
+ 0x1, 0x1D, 0x8F, 0x1, 0x1E, 0x0A, 0x1, 0x1F, 0x06, 0x1, 0x20, 0x01,
+ 0x1, 0x21, 0x02, 0x1, 0x22, 0x00, 0x1, 0x23, 0xD5, 0x1, 0x24, 0x18,
+ 0x1, 0x25, 0x22, 0x1, 0x26, 0x01, 0x1, 0x27, 0x82, 0x1, 0x28, 0x00,
+ 0x1, 0x29, 0xD5, 0x1, 0x2A, 0x18, 0x1, 0x2B, 0x0B, 0x1, 0x2C, 0x28,
+ 0x1, 0x2D, 0x78, 0x1, 0x2E, 0x28, 0x1, 0x2F, 0x91, 0x1, 0x30, 0x00,
+ 0x1, 0x31, 0x0B, 0x1, 0x32, 0x00, 0x1, 0x33, 0x0B, 0x1, 0x34, 0x00,
+ 0x1, 0x35, 0xA1, 0x1, 0x36, 0x00, 0x1, 0x37, 0xA0, 0x1, 0x38, 0x00,
+ 0x1, 0x39, 0x04, 0x1, 0x3A, 0x28, 0x1, 0x3B, 0x30, 0x1, 0x3C, 0x0C,
+ 0x1, 0x3D, 0x04, 0x1, 0x3E, 0x0F, 0x1, 0x3F, 0x79, 0x1, 0x40, 0x28,
+ 0x1, 0x41, 0x1E, 0x1, 0x42, 0x2F, 0x1, 0x43, 0x87, 0x1, 0x44, 0x00,
+ 0x1, 0x45, 0x0B, 0x1, 0x46, 0x00, 0x1, 0x47, 0x0B, 0x1, 0x48, 0x00,
+ 0x1, 0x49, 0xA7, 0x1, 0x4A, 0x00, 0x1, 0x4B, 0xA6, 0x1, 0x4C, 0x00,
+ 0x1, 0x4D, 0x04, 0x1, 0x4E, 0x01, 0x1, 0x4F, 0x00, 0x1, 0x50, 0x00,
+ 0x1, 0x51, 0x80, 0x1, 0x52, 0x09, 0x1, 0x53, 0x08, 0x1, 0x54, 0x01,
+ 0x1, 0x55, 0x00, 0x1, 0x56, 0x0F, 0x1, 0x57, 0x79, 0x1, 0x58, 0x09,
+ 0x1, 0x59, 0x05, 0x1, 0x5A, 0x00, 0x1, 0x5B, 0x60, 0x1, 0x5C, 0x05,
+ 0x1, 0x5D, 0xD1, 0x1, 0x5E, 0x0C, 0x1, 0x5F, 0x3C, 0x1, 0x60, 0x00,
+ 0x1, 0x61, 0xD0, 0x1, 0x62, 0x0B, 0x1, 0x63, 0x03, 0x1, 0x64, 0x28,
+ 0x1, 0x65, 0x10, 0x1, 0x66, 0x2A, 0x1, 0x67, 0x39, 0x1, 0x68, 0x0B,
+ 0x1, 0x69, 0x02, 0x1, 0x6A, 0x28, 0x1, 0x6B, 0x10, 0x1, 0x6C, 0x2A,
+ 0x1, 0x6D, 0x61, 0x1, 0x6E, 0x0C, 0x1, 0x6F, 0x00, 0x1, 0x70, 0x0F,
+ 0x1, 0x71, 0x79, 0x1, 0x72, 0x00, 0x1, 0x73, 0x0B, 0x1, 0x74, 0x00,
+ 0x1, 0x75, 0x0B, 0x1, 0x76, 0x00, 0x1, 0x77, 0xA1, 0x1, 0x78, 0x00,
+ 0x1, 0x79, 0xA0, 0x1, 0x7A, 0x00, 0x1, 0x7B, 0x04, 0x1, 0xFF, 0x04,
+ 0x1, 0x79, 0x1D, 0x1, 0x7B, 0x27, 0x1, 0x96, 0x0E, 0x1, 0x97, 0xFE,
+ 0x1, 0x98, 0x03, 0x1, 0x99, 0xEF, 0x1, 0x9A, 0x02, 0x1, 0x9B, 0x44,
+ 0x1, 0x73, 0x07, 0x1, 0x70, 0x01, 0x1, 0xff, 0x01, 0x1, 0x00, 0x01,
+ 0x1, 0xff, 0x00,
+ 0x0, 0x00, 0x00};
+
+/** @defgroup VL53L0X_GpioFunctionality_group Gpio Functionality
+ * @brief Defines the different functionalities for the device GPIO(s)
+ * @{ */
+typedef uint8_t VL53L0X_GpioFunctionality;
+#define VL53L0X_GPIOFUNCTIONALITY_OFF \
+ ((VL53L0X_GpioFunctionality) 0) /*!< NO Interrupt */
+#define VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_LOW \
+ ((VL53L0X_GpioFunctionality) 1) /*!< Level Low (value < thresh_low) */
+#define VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_HIGH \
+ ((VL53L0X_GpioFunctionality) 2) /*!< Level High (value > thresh_high) */
+#define VL53L0X_GPIOFUNCTIONALITY_THRESHOLD_CROSSED_OUT \
+ ((VL53L0X_GpioFunctionality) 3)
+/*!< Out Of Window (value < thresh_low OR value > thresh_high) */
+#define VL53L0X_GPIOFUNCTIONALITY_NEW_MEASURE_READY \
+ ((VL53L0X_GpioFunctionality) 4) /*!< New Sample Ready */
+/** @} end of VL53L0X_GpioFunctionality_group */
+
+
+/** @brief Defines the parameters of the Get Version Functions */
+typedef struct {
+ uint32_t revision; /*!< revision number */
+ uint8_t major; /*!< major number */
+ uint8_t minor; /*!< minor number */
+ uint8_t build; /*!< build number */
+} VL53L0X_Version_t;
+
+/** @defgroup VL53L0X_define_Error_group Error and Warning code returned by API
+ * The following DEFINE are used to identify the PAL ERROR
+ * @{ */
+typedef int8_t VL53L0X_Error;
+#define VL53L0X_ERROR_NONE ((VL53L0X_Error) 0)
+#define VL53L0X_ERROR_CALIBRATION_WARNING ((VL53L0X_Error) -1)
+/*!< Warning invalid calibration data may be in used
+ \a VL53L0X_InitData()
+ \a VL53L0X_GetOffsetCalibrationData
+ \a VL53L0X_SetOffsetCalibrationData */
+#define VL53L0X_ERROR_MIN_CLIPPED ((VL53L0X_Error) -2)
+/*!< Warning parameter passed was clipped to min before to be applied */
+#define VL53L0X_ERROR_UNDEFINED ((VL53L0X_Error) -3)
+/*!< Unqualified error */
+#define VL53L0X_ERROR_INVALID_PARAMS ((VL53L0X_Error) -4)
+/*!< Parameter passed is invalid or out of range */
+#define VL53L0X_ERROR_NOT_SUPPORTED ((VL53L0X_Error) -5)
+/*!< Function is not supported in current mode or configuration */
+#define VL53L0X_ERROR_RANGE_ERROR ((VL53L0X_Error) -6)
+/*!< Device report a ranging error interrupt status */
+#define VL53L0X_ERROR_TIME_OUT ((VL53L0X_Error) -7)
+/*!< Aborted due to time out */
+#define VL53L0X_ERROR_MODE_NOT_SUPPORTED ((VL53L0X_Error) -8)
+/*!< Asked mode is not supported by the device */
+#define VL53L0X_ERROR_BUFFER_TOO_SMALL ((VL53L0X_Error) -9)
+/*!< ... */
+#define VL53L0X_ERROR_GPIO_NOT_EXISTING ((VL53L0X_Error) -10)
+/*!< User tried to setup a non-existing GPIO pin */
+#define VL53L0X_ERROR_GPIO_FUNCTIONALITY_NOT_SUPPORTED ((VL53L0X_Error) -11)
+/*!< unsupported GPIO functionality */
+#define VL53L0X_ERROR_INTERRUPT_NOT_CLEARED ((VL53L0X_Error) -12)
+/*!< Error during interrupt clear */
+#define VL53L0X_ERROR_CONTROL_INTERFACE ((VL53L0X_Error) -20)
+/*!< error reported from IO functions */
+#define VL53L0X_ERROR_INVALID_COMMAND ((VL53L0X_Error) -30)
+/*!< The command is not allowed in the current device state (power down) */
+#define VL53L0X_ERROR_DIVISION_BY_ZERO ((VL53L0X_Error) -40)
+/*!< In the function a division by zero occurs */
+#define VL53L0X_ERROR_REF_SPAD_INIT ((VL53L0X_Error) -50)
+/*!< Error during reference SPAD initialization */
+/** @} VL53L0X_define_Error_group */
+
+
+/** @defgroup VL53L0X_define_DeviceModes_group Defines Device modes
+ * Defines all possible modes for the device
+ * @{ */
+typedef uint8_t VL53L0X_DeviceModes;
+#define VL53L0X_DEVICEMODE_SINGLE_RANGING ((VL53L0X_DeviceModes) 0)
+#define VL53L0X_DEVICEMODE_CONTINUOUS_RANGING ((VL53L0X_DeviceModes) 1)
+#define VL53L0X_DEVICEMODE_CONTINUOUS_TIMED_RANGING ((VL53L0X_DeviceModes) 3)
+#define VL53L0X_DEVICEMODE_SINGLE_ALS ((VL53L0X_DeviceModes) 10)
+#define VL53L0X_DEVICEMODE_GPIO_DRIVE ((VL53L0X_DeviceModes) 20)
+#define VL53L0X_DEVICEMODE_GPIO_OSC ((VL53L0X_DeviceModes) 21)
+/* ... Modes to be added depending on device */
+/** @} VL53L0X_define_DeviceModes_group */
+
+
+/** @defgroup VL53L0X_define_PowerModes_group List of available Power Modes
+ * List of available Power Modes
+ * @{ */
+typedef uint8_t VL53L0X_PowerModes;
+#define VL53L0X_POWERMODE_STANDBY_LEVEL1 ((VL53L0X_PowerModes) 0)
+/*!< Standby level 1 */
+#define VL53L0X_POWERMODE_STANDBY_LEVEL2 ((VL53L0X_PowerModes) 1)
+/*!< Standby level 2 */
+#define VL53L0X_POWERMODE_IDLE_LEVEL1 ((VL53L0X_PowerModes) 2)
+/*!< Idle level 1 */
+#define VL53L0X_POWERMODE_IDLE_LEVEL2 ((VL53L0X_PowerModes) 3)
+/*!< Idle level 2 */
+/** @} VL53L0X_define_PowerModes_group */
+
+/** @defgroup VL53L0X_define_State_group Defines the current status of the device
+ * Defines the current status of the device
+ * @{ */
+typedef uint8_t VL53L0X_State;
+#define VL53L0X_STATE_POWERDOWN ((VL53L0X_State) 0)
+/*!< Device is in HW reset */
+#define VL53L0X_STATE_WAIT_STATICINIT ((VL53L0X_State) 1)
+/*!< Device is initialized and wait for static initialization */
+#define VL53L0X_STATE_STANDBY ((VL53L0X_State) 2)
+/*!< Device is in Low power Standby mode */
+#define VL53L0X_STATE_IDLE ((VL53L0X_State) 3)
+/*!< Device has been initialized and ready to do measurements */
+#define VL53L0X_STATE_RUNNING ((VL53L0X_State) 4)
+/*!< Device is performing measurement */
+#define VL53L0X_STATE_UNKNOWN ((VL53L0X_State) 98)
+/*!< Device is in unknown state and need to be rebooted */
+#define VL53L0X_STATE_ERROR ((VL53L0X_State) 99)
+/*!< Device is in error state and need to be rebooted */
+/** @} VL53L0X_define_State_group */
+
+
+/** @brief Defines the parameters of the Get Device Info Functions */
+typedef struct {
+ char Name[VL53L0X_MAX_STRING_LENGTH];
+ /*!< Name of the Device e.g. Left_Distance */
+ char Type[VL53L0X_MAX_STRING_LENGTH];
+ /*!< Type of the Device e.g VL53L0X */
+ char ProductId[VL53L0X_MAX_STRING_LENGTH];
+ /*!< Product Identifier String */
+ uint8_t ProductType;
+ /*!< Product Type, VL53L0X = 1, VL53L1 = 2 */
+ uint8_t ProductRevisionMajor;
+ /*!< Product revision major */
+ uint8_t ProductRevisionMinor;
+ /*!< Product revision minor */
+} VL53L0X_DeviceInfo_t;
+
+/** @brief Defines all parameters for the device */
+typedef struct {
+ VL53L0X_DeviceModes DeviceMode;
+ /*!< Defines type of measurement to be done for the next measurement */
+ uint32_t MeasurementTimingBudget_us;
+ /*!< Defines the allowed total time for a single measurement */
+ uint32_t InterMeasurementPeriod_ms;
+ /*!< Defines time between two consecutive measurements (between two
+ * measurement starts). If set to 0 means back-to-back mode */
+ uint8_t XTalkCompensationEnable;
+ /*!< Tells if Crosstalk compensation shall be enable or not */
+ uint16_t XTalkCompensationRange_mm;
+ /*!< CrossTalk compensation range in _mm */
+ FixPoint1616_t XTalkCompensationRate_MHz;
+ /*!< CrossTalk compensation rate in Mega counts per seconds.
+ * Expressed in 16.16 fixed point format. */
+ int32_t RangeOffset_um;
+ /*!< Range offset adjustment (mm) last programmed. */
+ uint8_t LimitChecksEnable[VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array store all the 6 Limit Check enables for this device. */
+ uint8_t LimitChecksStatus[VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array store all the 6 Status of the check linked to last measurement. */
+ FixPoint1616_t LimitChecksValue[VL53L0X_CHECKENABLE_NUMBER_OF_CHECKS];
+ /*!< This Array store all the Limit Check value for this device */
+ uint8_t WrapAroundCheckEnable;
+ /*!< Tells if Wrap Around Check shall be enable or not */
+} VL53L0X_DeviceParameters_t;
+
+/**
+ * @struct VL53L0X_RangeData_t
+ * @brief Range measurement data. */
+typedef struct {
+ uint16_t Range_mm; /*!< range distance in _mm. */
+ uint16_t RangeDMax_mm; /*!< Tells what is the maximum detection distance of the device
+ * in current setup and environment conditions (Filled when applicable) */
+ FixPoint1616_t SignalRateRtn_MHz; /*!< Return signal rate (MHz), as 16.16 fix point, effectively a measure of target reflectance.*/
+ FixPoint1616_t AmbientRateRtn_MHz; /*!< Return ambient rate (MHz), as 16.16 fix point, effectively a measure of the ambient light.*/
+ uint16_t EffectiveSpadRtnCount; /*!< Return the effective SPAD count for the return signal, as a 8.8 fix point value. */
+ uint8_t RangeFractionalPart; /*!< Fractional part of range distance. Final value is a FixPoint168 value.; only noise :( */
+ uint8_t RangeStatus; /*!< Range Status for the current measurement. Value = 0 means value is valid. See \ref RangeStatusPage */
+ FixPoint1616_t SigmaEstimate; /*!< Estimated Sigma - based on ambient & VCSEL rates and signal_total_events */
+} VL53L0X_RangingMeasurementData_t;
+
+
+#define VL53L0X_REF_SPAD_BUFFER_SIZE 6
+typedef struct {
+ // merged in here all parts of "VL53L0X_DeviceSpecificParameters_t DeviceSpecificParameters;"
+ FixPoint1616_t OscFrequency_MHz; /* Frequency used */
+ uint16_t LastEncodedTimeout; /* last encoded Time out used for timing budget*/
+ VL53L0X_GpioFunctionality Pin0GpioFunctionality; /* store the functionality of the GPIO: pin0 */
+ uint32_t FinalRangeTimeout_us;/*!< Execution time of the final range*/
+ uint8_t FinalRangeVcselPulsePeriod; /*!< Vcsel pulse period (pll clocks) for the final range measurement*/
+ uint32_t PreRangeTimeout_us; /*!< Execution time of the final range*/
+ uint8_t PreRangeVcselPulsePeriod; /*!< Vcsel pulse period (pll clocks) for the pre-range measurement*/
+ uint8_t ReadDataFromDeviceDone; /* Indicate if read from device has been done (==1) or not (==0) */
+ uint8_t ModuleId; /* Module ID */
+ uint8_t Revision; /* test Revision */
+ char ProductId[VL53L0X_MAX_STRING_LENGTH]; /* Product Identifier String */
+ uint8_t ReferenceSpadCount; /* used for ref spad management */
+ uint8_t ReferenceSpadType; /* used for ref spad management */
+ uint8_t RefSpadsInitialised; /* reports if ref spads are initialised. */
+ uint32_t PartUIDUpper; /*!< Unique Part ID Upper */
+ uint32_t PartUIDLower; /*!< Unique Part ID Lower */
+ FixPoint1616_t SignalRateMeasFixed400mm; /*!< Peek Signal rate at 400 mm*/
+
+ // Merged in here the VL53L0X_SpadData_t SpadData; /*!< Spad Data; Enables and Good-Map */
+ uint8_t RefSpadEnables[VL53L0X_REF_SPAD_BUFFER_SIZE]; /*!< Reference Spad Enables */
+ uint8_t RefGoodSpadMap[VL53L0X_REF_SPAD_BUFFER_SIZE]; /*!< Reference Spad Good Spad Map */
+
+ // Merged in here all parts of DeviceParams_t
+ int32_t Part2PartOffsetNVM_um; /*!< backed up NVM value */
+ int32_t Part2PartOffsetAdjustNVM_um; /*!< backed up NVM value representing additional offset adjustment */
+ uint8_t SequenceConfig; /*!< Internal value for the sequence config */
+ uint8_t RangeFractionalEnable; /*!< Enable/Disable fractional part of ranging data */
+ VL53L0X_State PalState; /*!< Current state of the PAL for this device */
+ VL53L0X_PowerModes PowerMode; /*!< Current Power Mode; Stdby1/2, Idle1/2 */
+ uint16_t SigmaEstRefArray; /*!< Reference array sigma value in 1/100th of [mm] e.g. 100 = 1mm; loaded from tuning settings */
+ uint16_t SigmaEstEffPulseWidth; /*!< Effective Pulse width for sigma estimate in 1/100th of ns e.g. 900 = 9.0ns */
+ uint16_t SigmaEstEffAmbWidth; /*!< Effective Ambient width for sigma estimate in 1/100th of ns e.g. 500 = 5.0ns */
+ uint8_t StopVariable; /*!< StopVariable used during the stop sequence */
+ uint16_t targetRefRate; /*!< Target Ambient Rate for Ref spad management */
+ FixPoint1616_t LastSignalRef_MHz; /*!< Latest Signal ref in MHz */
+ uint8_t *pTuningSettingsPointer; /*!< Pointer for alternative Tuning Settings table */
+ uint8_t UseInternalTuningSettings; /*!< Indicate if we use Tuning Settings table, default = True */
+ uint16_t LinearityCorrectiveGain; /*!< Linearity Corrective Gain value in x1000 */
+ uint16_t DmaxCalRange_mm; /*!< Dmax Calibration Range _mm */
+ FixPoint1616_t DmaxCalSignalRateRtn_MHz;/*!< Dmax Calibration Signal Rate Return _MHz */
+
+} VL53L0X_DevData_t;
+
+ /* All these macros were replaced with following regulator expressions:
+a) Search for: \QVL53L0X_SETARRAYPARAMETERFIELD(\E(\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_\*]+)\Q);\E
+ Replace by: Data.CurrentParameters.\2[\4] = \6;
+ to replace this: VL53L0X_SETARRAYPARAMETERFIELD(field, index, value);
+ by this: Data.CurrentParameters.field[index] = value;
+
+b) Search for: \QVL53L0X_GETARRAYPARAMETERFIELD(\E(\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_\*]+)\Q);\E
+ Replace by: \6 = Data.CurrentParameters.\2[\4];
+ to replace this: VL53L0X_GETARRAYPARAMETERFIELD( LimitChecksValue, limit_check_id, temp_fix1616);
+ by this: temp_fix1616 = Data.CurrentParameters.LimitChecksValue[limit_check_id];
+
+c) Search for: \QVL53L0X_SETPARAMETERFIELD(\E(\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_\*]+)\Q);\E
+ Replace by: Data.CurrentParameters.\2 = \4;
+ to replace this: VL53L0X_SETPARAMETERFIELD(field, value);
+ by this: Data.CurrentParameters.field = value
+
+d) Search for: \QVL53L0X_GETPARAMETERFIELD(\E(\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_\*]+)\Q);\E
+ Replace by: \4 = Data.CurrentParameters.\2 ;
+ to replace this: VL53L0X_GETPARAMET ERFIELD(field, variable);
+ by this: variable = Data.CurrentParameters.field;
+
+d) Search for: \QPALDevDataSet(\E(\s*)([A-Z\d_]+)[[:punct:]](\s*)([A-Z\d_\*]+)\Q);\E
+ Replace by: Data.\2 = \4;
+ to replace this: PALDevDataSet(field, value);
+ by this: Data.field = value;
+
+d) Search for: \QPALDevDataGet(\E(\s*)([A-Z\d]+)\Q)\E
+ Replace by: Data.\2
+ to replace this: PALDevDataGet(field)
+ by this: Data.field
+
+#define PALDevDataSet(field, value) (Data.field)=(value)
+#define PALDevDataGet(field) (Data.field)
+#define VL53L0X_SETPARAMETERFIELD(field, value) Data.CurrentParameters.field = value
+#define VL53L0X_GETPARAMETERFIELD(field, variable) variable = Data.CurrentParameters.field
+#define VL53L0X_SETARRAYPARAMETERFIELD(field, index, value) Data.CurrentParameters.field[index] = value
+#define VL53L0X_GETARRAYPARAMETERFIELD(field, index, variable) variable = Data.CurrentParameters.field[index]
+#define VL53L0X_SETDEVICESPECIFICPARAMETER(field, value) Data.field = value
+#define VL53L0X_GETDEVICESPECIFICPARAMETER(field) Data.field
+ */
+
+
+/** @defgroup VL53L0X_define_InterruptPolarity_group Defines the Polarity of the Interrupt
+ * Defines the Polarity of the Interrupt
+ * @{
+ */
+typedef uint8_t VL53L0X_InterruptPolarity;
+#define VL53L0X_INTERRUPTPOLARITY_LOW ((VL53L0X_InterruptPolarity) 0)
+/*!< Set active low polarity best setup for falling edge. */
+#define VL53L0X_INTERRUPTPOLARITY_HIGH ((VL53L0X_InterruptPolarity) 1)
+/*!< Set active high polarity best setup for rising edge. */
+
+/** @} VL53L0X_define_InterruptPolarity_group */
+
+
+/** @defgroup VL53L0X_define_VcselPeriod_group Vcsel Period Defines
+ * Defines the range measurement for which to access the vcsel period.
+ * @{ */
+typedef uint8_t VL53L0X_VcselPeriod;
+#define VL53L0X_VCSEL_PERIOD_PRE_RANGE ((VL53L0X_VcselPeriod) 0)
+/*!<Identifies the pre-range vcsel period. */
+#define VL53L0X_VCSEL_PERIOD_FINAL_RANGE ((VL53L0X_VcselPeriod) 1)
+/*!<Identifies the final range vcsel period. */
+
+/** @} VL53L0X_define_VcselPeriod_group */
+/** @defgroup VL53L0X_define_SchedulerSequence_group Defines the steps
+ * carried out by the scheduler during a range measurement.
+ * @{
+ * Defines the states of all the steps in the scheduler i.e. enabled/disabled. */
+typedef struct {
+ uint8_t TccOn; /*!<Reports if Target Centre Check On */
+ uint8_t MsrcOn; /*!<Reports if MSRC On */
+ uint8_t DssOn; /*!<Reports if DSS On */
+ uint8_t PreRangeOn; /*!<Reports if Pre-Range On */
+ uint8_t FinalRangeOn; /*!<Reports if Final-Range On */
+} VL53L0X_SchedulerSequenceSteps_t;
+/** @} VL53L0X_define_SchedulerSequence_group */
+
+/** @defgroup VL53L0X_define_SequenceStepId_group
+ * Defines the the sequence steps performed during ranging..
+ * @{ */
+typedef uint8_t VL53L0X_SequenceStepId;
+#define VL53L0X_SEQUENCESTEP_TCC ((VL53L0X_VcselPeriod) 0) /*!<Target CentreCheck identifier. */
+#define VL53L0X_SEQUENCESTEP_DSS ((VL53L0X_VcselPeriod) 1) /*!<Dynamic Spad Selection function Identifier. */
+#define VL53L0X_SEQUENCESTEP_MSRC ((VL53L0X_VcselPeriod) 2) /*!<Minimum Signal Rate Check function Identifier. */
+#define VL53L0X_SEQUENCESTEP_PRE_RANGE ((VL53L0X_VcselPeriod) 3) /*!<Pre-Range check Identifier. */
+#define VL53L0X_SEQUENCESTEP_FINAL_RANGE ((VL53L0X_VcselPeriod) 4) /*!<Final Range Check Identifier. */
+#define VL53L0X_SEQUENCESTEP_NUMBER_OF_CHECKS 5 /*!<Number of Sequence Step Managed by the API. */
+/** @} VL53L0X_define_SequenceStepId_group */
+
+
+typedef enum {
+ Range_Config_DEFAULT,
+ Range_Config_LONG_RANGE,
+ Range_Config_HIGH_ACCURACY,
+ Range_Config_HIGH_SPEED
+} VL53L0X_RangingConfig;
+/** @} VL53L0X_define_SequenceStepId_group */
+
+/** @} VL53L0X_globaldefine_group */
+
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* _VL53L0X_DEF_H_ */
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,380 @@
+/*
+ * Crealab : version Scratch
+ */
+
+#undef printf
+#include "Crealab.h"
+#include "LED_WS2812.h"
+#include "VL53L0X.h"
+
+//#include "AsyncToF.h"
+
+Serial pc_uart(USBTX, USBRX); // USBTX = PA2
+Serial bt_uart(D1, D0); // PA9 = Tx, PA10 = Rx
+//Serial bt_uart(D5, D4); // PA9 = Tx, PA10 = Rx
+uint32_t go;
+bool ShowDataLog=false;
+uint16_t TOF_UseRange_mm = 450;
+// ---------------- PIN DEFINITIONS ---------------------
+
+InterruptIn buttonBox(PA_12);
+
+// --- Define the Four PINs & Time of movement used for Motor drive
+
+Motor motorRG(D13,D11,D10,D9);
+Motor motorRD(A0,A1,A2,A3);
+
+
+Creabot mybot(&motorRG, &motorRD, 8.10f,8.3f); // insert the motors and indicate wheel diameter and distance between wheels
+LED_WS2812 ledBand(A4,2);
+
+DigitalIn isCmd(A5); // relier le pin A5 a la masse (GND) pour faire fonctionner le robot en mode demo autonome
+
+//static I2C busI2C(D4,D5);
+//static I2C busI2C(D0,D1);
+static I2C busI2C(D12,A6);
+
+static DigitalOut shutDownPin(D6);
+static VL53L0X TOF1 (&busI2C, &shutDownPin, D7);
+
+bool receivedCOMMAND;
+char commandRECEIVED;
+int parameterRECEIVED;
+int state;
+char commandLine[256];
+int commandPosition;
+VL53L0X_Error TOFError;
+
+void init_TOF( void )
+{
+ pc_uart.printf("\n\r--- Initializing the TOF sensor ---\n\r");
+
+ /* Init the TOF sensor with default params */
+ TOFError = TOF1.init_sensor();
+ /* This configuration "Range_Config_HIGH_SPEED" sets following parameters:
+ signalLimit = (FixPoint1616_t)(0.15*65536); ==> VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE
+ sigmaLimit = (FixPoint1616_t)(32*65536); ==> VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE
+ timingBudget = 10000; Must be > c_min_timing_budget_us = 20000;
+ preRangeVcselPeriod = 14;
+ finalRangeVcselPeriod = 10; */
+
+ if (TOFError == VL53L0X_ERROR_NONE) { TOFError = TOF1.start_measurement(range_continuous_polling, NULL, Range_Config_DEFAULT); }
+ pc_uart.printf("TOFError = %d. ( 0 = OK ) \n\r", TOFError);
+ pc_uart.printf(" TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE] = %4.2f \n\r",
+ TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE] /65536.1);
+ pc_uart.printf(" TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] = %4.2f \n\r",
+ TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] /65536.1);
+
+ if (TOFError == VL53L0X_ERROR_NONE) { TOFError = TOF1.VL53L0X_set_measurement_timing_budget_us(100000); }
+ TOF1.CurrentParameters.RangeOffset_um = 14; // seems it is wrongly configured by default to 54mm offset!
+ pc_uart.printf("TOFError = %d. ( 0 = OK ) \n\r", TOFError);
+
+ // Report_Deep_Infos(TOF1);
+
+ if (TOFError != VL53L0X_ERROR_NONE)
+ { pc_uart.printf("\n\r--- Error Initializing the TOF sensor ---\n\r");
+ //while(1) { }; // consider to hang up the device here
+ // alternatively just clear the Error State:
+ // TOF1.ErrState = VL53L0X_ERROR_NONE;
+ }
+ else
+ { pc_uart.printf("\n\r--- Success Initializing the TOF sensor ---\n\r"); }
+}
+
+bool TOF_OK;
+VL53L0X_RangingMeasurementData_t RangeResults;
+uint16_t TOF_Dist_mm;
+double TOF_RelDist; // measured distance relative to the Used Range. Should be clamped to 0 ... 1, but can actually also be negative or >1
+const uint32_t out_of_range = 0xffff;
+uint16_t TOF_MinDist_mm=5;
+
+bool GetNewTOF()
+{ uint32_t NewDist_mm;
+ TOFError = TOF1.get_measurement(range_continuous_polling, &RangeResults);
+ if ( (TOFError == VL53L0X_ERROR_NONE) && (RangeResults.RangeStatus == 0) )
+ { // we have a valid range.
+ // Report_Range_Infos( RangeResults );
+ if (ShowDataLog) pc_uart.printf("Dist=%3d, SigRate=%4.2fM/s, AmbRate=%4.2fM/s, SpadRtnCnt=%3.1f, SigmEst=%3.3f\n\r",
+ RangeResults.Range_mm, RangeResults.SignalRateRtn_MHz/65536.1, RangeResults.AmbientRateRtn_MHz/65536.1,
+ RangeResults.EffectiveSpadRtnCount/256.1, RangeResults.SigmaEstimate/65536.1);
+ //Report_Deep_Infos(TOF1);
+ NewDist_mm = RangeResults.Range_mm;
+ // pc_uart.printf("%6ld\r", NewDist_mm); // Distance is ~1700 when looking at the ceiling, so approximately 1 per mm. A really usable distance range is only up to 1270.
+
+ if (TOF_Dist_mm == out_of_range) // previous value was useless
+ { TOF_Dist_mm = NewDist_mm; } // only take the new value
+ else // average old with new value!!
+ { TOF_Dist_mm = ( NewDist_mm * 2 + TOF_Dist_mm * 3 ) / 5 ;
+ if (TOF_Dist_mm < TOF_MinDist_mm) { TOF_MinDist_mm = TOF_Dist_mm; pc_uart.printf("DMin = %3d. \r\n", TOF_MinDist_mm);} // adapt the min dist parameter
+
+ // The device theoretical working distance range is from 0 up to 1270mm, distance is always expressed in mm!
+ // However here we transform to a relative number, of which only the range 0 ... 1 should be used.
+ TOF_RelDist = ( (double) TOF_Dist_mm - TOF_MinDist_mm) / TOF_UseRange_mm;
+ if (TOF_RelDist <0) {TOF_RelDist = 0;} // clamping values <0 (that should actually never occur with above adaption of Min dist!, values >1 can still happen!
+ }
+ return true; // new measurement is available
+ }
+ else
+ { // pc_uart.printf(" --\r");
+ TOF_Dist_mm = out_of_range;
+ TOF_RelDist = out_of_range;
+ return false; // no new measurement is available
+ }
+}
+
+
+
+void help() // Display list of Commands
+{
+ DEBUG("List of commands:\n\r");
+ DEBUG(" h --> Help, display list of commands\n\r");
+}
+
+void callback()
+{
+ switch(state) {
+ case 0:
+ break;
+ case 1:
+ break;
+ case 2:
+ break;
+ case 3:
+ break;
+ default:
+ }
+ state=state+1;
+}
+
+/* Stop all processes */
+void stop_all()
+{
+ mybot.stopMove();
+}
+
+void clicked()
+{
+ DEBUG("Labyrinthe\n\r");
+ commandRECEIVED = 'l';
+ receivedCOMMAND = true;
+}
+
+void labyrinthe()
+{
+ wait(1);
+ mybot.move(FORWARD,15);
+ mybot.waitEndMove();
+ mybot.move(ROTATE, 90);
+ mybot.waitEndMove();
+ mybot.move(FORWARD,15);
+ mybot.waitEndMove();
+ mybot.move(ROTATE, 90);
+ mybot.waitEndMove();
+}
+
+void executeCommand(char c, int parameter)
+{
+ bool flaghelp = false;
+ switch (c) {
+ case 'h':
+ help();
+ state=0;
+ flaghelp=true;
+ CASE('a', "Avance <cm> (a <cm>) => Avance du nombre de cm indiques", mybot.move(FORWARD,parameter); )
+ CASE('r', "Recule <cm> (r <cm>) => Recule du nombre de cm indiques", mybot.move(BACKWARD,parameter); )
+ CASE('d', "Droite <deg> (d <deg>) => Tourne a droite du nombre de degres indiques", mybot.move(RIGHT,parameter,0); )
+ CASE('g', "Gauche <deg> (g <deg>) => Tourne a gauche du nombre de degres indiques", mybot.move(LEFT,parameter,0); )
+ CASE('p', "Pivote_d <deh> (p <deg>) => pivote a droite du nombre de degres indiques", mybot.move(ROTATE,parameter); )
+ CASE('q', "Pivote_g <deg> (q <deg>) => pivote a gauche du nombre de degres indiques", mybot.move(ROTATE,-parameter); )
+ CASE('s', "Stop => Arrete les moteurs", mybot.stopMove(); state=0; )
+ CASE('l', "Labyrinthe => Lance le parcours Labyrinthe", labyrinthe(); )
+ default :
+ DEBUG("invalid command; use: 'h' for help()\n\r");
+ state=0;
+ }
+}
+
+void analyseCommand(char *command, int parameter)
+{
+ parameterRECEIVED = parameter;
+ switch(command[0]) {
+ case 'A':
+ case 'a':
+ commandRECEIVED = 'a';
+ break;
+ case 'R':
+ case 'r':
+ commandRECEIVED = 'r';
+ break;
+ case 'D':
+ case 'd':
+ commandRECEIVED = 'd';
+ break;
+ case 'G':
+ case 'g':
+ commandRECEIVED = 'g';
+ break;
+ case 'L':
+ case 'l':
+ commandRECEIVED = 'l';
+ break;
+ case 'P':
+ if(command[7]=='d') {
+ commandRECEIVED = 'p';
+ } else if (command[7]=='g') {
+ commandRECEIVED = 'q';
+ } else {
+ commandRECEIVED = 'h';
+ }
+ break;
+ case 'p':
+ commandRECEIVED = 'p';
+ break;
+ case 'q':
+ commandRECEIVED = 'q';
+ break;
+ case 'S':
+ case 's':
+ commandRECEIVED = 's';
+ mybot.stopMove();
+ state=0;
+ break;
+ default:
+ commandRECEIVED = 'h';
+ }
+}
+
+void checkCommand(int result, char *command, int parameter)
+{
+ if(result==2 || command[0]=='h' || command[0]=='s') {
+ if(command[0]=='c') {
+ DEBUG("CREABOT PRESENT\n\r");
+ } else {
+ analyseCommand(command, parameter);
+ receivedCOMMAND = true;
+ }
+ }
+}
+
+void split(char *line, int length)
+{
+ char command[256];
+ int parameter=0;
+ int result = 1;
+ int i=0;
+ int j=0;
+ while(i<length && line[i]==' ') {
+ i++;
+ }
+ while(i<length && line[i]!=' ') {
+ command[j]=line[i];
+ i++;
+ j++;
+ }
+ command[j]=0;
+ i++;
+ j=0;
+ while(i<length && line[i]!=' ' && line[i]>='0' && line[i]<='9') {
+ i++;
+ j++;
+ }
+ if(j>0) {
+ result++;
+ i--;
+ int k=1;
+ while(j>0) {
+ parameter += (line[i]-'0')*k;
+ j--;
+ i--;
+ k=k*10;
+ }
+ }
+ checkCommand(result, command, parameter);
+}
+
+void storeC(char c)
+{
+ if(c==10 || c==13|| commandPosition >= 254) {
+ split(commandLine, commandPosition);
+ commandPosition=0;
+ } else {
+ commandLine[commandPosition++]=c;
+ commandLine[commandPosition]=0;
+ }
+}
+
+void getBT()
+{
+ char c = bt_uart.getc();
+ storeC(c);
+}
+
+void getPC()
+{
+ char c = pc_uart.getc();
+ storeC(c);
+}
+
+void endOfMove(int status)
+{
+ DEBUG("ENDOFMOVE\n\r");
+ state=0;
+}
+void demoMode(void)
+{
+ init_TOF();
+ TOF_Dist_mm=200;
+ while(1){
+ if(GetNewTOF()){
+ pc_uart.printf("\n\rDistance : %d mm\n\r",TOF_Dist_mm);
+// DEBUG("\n\rDistance : %d mm\n\r",TOF_Dist_mm)
+ }
+
+ if (TOF_Dist_mm < 60 & TOF_Dist_mm > 0){
+ mybot.move(BACKWARD,5);
+ mybot.waitEndMove(5000000); // 5 seconds
+ mybot.move(ROTATE,-90);
+ mybot.waitEndMove(5000000); // 5 seconds
+ }
+ else{
+ mybot.move(FORWARD,5);
+// mybot.waitEndMove(5000000); // 5 seconds
+ }
+ }
+}
+/* Routine */
+int main()
+{
+ /* Rename HC-C6 BT*/
+
+ commandPosition=0;
+ bt_uart.attach(getBT);
+ pc_uart.attach(getPC);
+ mybot.setCallBack(endOfMove);
+ mybot.setSpeed(4.5); // max 6.9 cm.s, average 5 cm.s
+ state=0;
+ receivedCOMMAND = false;
+ DEBUG("CREABOT alpha version\n\r");
+ __disable_irq();
+ pc_uart.printf("Init Done ...\n\r");
+ __enable_irq();
+ pc_uart.printf("start passed ok\n");
+
+
+ ledBand.SetColor(BLUE,0);
+ ledBand.SetColor(BLUE,1);
+
+ isCmd.mode(PullUp);
+ pc_uart.printf("switchState=%d\n\r", isCmd.read());
+ if (isCmd.read()==0){
+ demoMode();
+ }
+ while(1) {
+ if(state==0 && receivedCOMMAND) {
+ receivedCOMMAND = false;
+ state=1;
+ executeCommand(commandRECEIVED, parameterRECEIVED);
+ }
+ wait(0.1);
+ }
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000
+++ b/mainCopy.txt Sat Feb 08 09:48:46 2020 +0000
@@ -0,0 +1,379 @@
+/*
+ * Crealab : version Scratch
+ */
+
+#undef printf
+#include "Crealab.h"
+#include "LED_WS2812.h"
+#include "VL53L0X.h"
+
+//#include "AsyncToF.h"
+
+Serial pc_uart(USBTX, USBRX); // USBTX = PA2
+Serial bt_uart(D5, D4); // PA9 = Tx, PA10 = Rx
+uint32_t go;
+bool ShowDataLog=false;
+uint16_t TOF_UseRange_mm = 450;
+// ---------------- PIN DEFINITIONS ---------------------
+
+InterruptIn buttonBox(PA_12);
+
+// --- Define the Four PINs & Time of movement used for Motor drive
+//Motor motorRD(PA_4, PA_3, PA_1, PA_0);
+//Motor motorRG(PA_8, PA_11, PB_5, PB_4);
+Motor motorRG(D12,D11,D10,D9);
+Motor motorRD(A3,A2,A1,A0);
+Creabot mybot(&motorRG, &motorRD, 8.10f,8.3f); // insert the motors and indicate wheel diameter and distance between wheels
+LED_WS2812 ledBand(A4,2);
+/*AsyncToF myToF(D4,D5,D13,A2,0x52);*/
+//AsyncToF myToF(D4,D5,D13,NC,0x52);
+DigitalIn isCmd(A5); // relier le pin A5 a la masse (GND) pour faire fonctionner le robot en mode demo autonome
+
+static I2C busI2C(D0,D1);
+static DigitalOut shutDownPin(D6);
+static VL53L0X TOF1 (&busI2C, &shutDownPin, D7);
+
+bool receivedCOMMAND;
+char commandRECEIVED;
+int parameterRECEIVED;
+int state;
+char commandLine[256];
+int commandPosition;
+VL53L0X_Error TOFError;
+
+void init_TOF( void )
+{
+ pc_uart.printf("\n\r--- Initializing the TOF sensor ---\n\r");
+
+ /* Init the TOF sensor with default params */
+ TOFError = TOF1.init_sensor();
+ /* This configuration "Range_Config_HIGH_SPEED" sets following parameters:
+ signalLimit = (FixPoint1616_t)(0.15*65536); ==> VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE
+ sigmaLimit = (FixPoint1616_t)(32*65536); ==> VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE
+ timingBudget = 10000; Must be > c_min_timing_budget_us = 20000;
+ preRangeVcselPeriod = 14;
+ finalRangeVcselPeriod = 10; */
+
+ if (TOFError == VL53L0X_ERROR_NONE) { TOFError = TOF1.start_measurement(range_continuous_polling, NULL, Range_Config_DEFAULT); }
+ pc_uart.printf("TOFError = %d. ( 0 = OK ) \n\r", TOFError);
+ pc_uart.printf(" TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE] = %4.2f \n\r",
+ TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGNAL_RATE_FINAL_RANGE] /65536.1);
+ pc_uart.printf(" TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] = %4.2f \n\r",
+ TOF1.CurrentParameters.LimitChecksValue[VL53L0X_CHECKENABLE_SIGMA_FINAL_RANGE] /65536.1);
+
+ if (TOFError == VL53L0X_ERROR_NONE) { TOFError = TOF1.VL53L0X_set_measurement_timing_budget_us(100000); }
+ TOF1.CurrentParameters.RangeOffset_um = 14; // seems it is wrongly configured by default to 54mm offset!
+ pc_uart.printf("TOFError = %d. ( 0 = OK ) \n\r", TOFError);
+
+ // Report_Deep_Infos(TOF1);
+
+ if (TOFError != VL53L0X_ERROR_NONE)
+ { pc_uart.printf("\n\r--- Error Initializing the TOF sensor ---\n\r");
+ //while(1) { }; // consider to hang up the device here
+ // alternatively just clear the Error State:
+ // TOF1.ErrState = VL53L0X_ERROR_NONE;
+ }
+ else
+ { pc_uart.printf("\n\r--- Success Initializing the TOF sensor ---\n\r"); }
+}
+
+bool TOF_OK;
+VL53L0X_RangingMeasurementData_t RangeResults;
+uint16_t TOF_Dist_mm;
+double TOF_RelDist; // measured distance relative to the Used Range. Should be clamped to 0 ... 1, but can actually also be negative or >1
+const uint32_t out_of_range = 0xffff;
+uint16_t TOF_MinDist_mm=5;
+
+bool GetNewTOF()
+{ uint32_t NewDist_mm;
+ TOFError = TOF1.get_measurement(range_continuous_polling, &RangeResults);
+ if ( (TOFError == VL53L0X_ERROR_NONE) && (RangeResults.RangeStatus == 0) )
+ { // we have a valid range.
+ // Report_Range_Infos( RangeResults );
+ if (ShowDataLog) pc_uart.printf("Dist=%3d, SigRate=%4.2fM/s, AmbRate=%4.2fM/s, SpadRtnCnt=%3.1f, SigmEst=%3.3f\n\r",
+ RangeResults.Range_mm, RangeResults.SignalRateRtn_MHz/65536.1, RangeResults.AmbientRateRtn_MHz/65536.1,
+ RangeResults.EffectiveSpadRtnCount/256.1, RangeResults.SigmaEstimate/65536.1);
+ //Report_Deep_Infos(TOF1);
+ NewDist_mm = RangeResults.Range_mm;
+ // pc_uart.printf("%6ld\r", NewDist_mm); // Distance is ~1700 when looking at the ceiling, so approximately 1 per mm. A really usable distance range is only up to 1270.
+
+ if (TOF_Dist_mm == out_of_range) // previous value was useless
+ { TOF_Dist_mm = NewDist_mm; } // only take the new value
+ else // average old with new value!!
+ { TOF_Dist_mm = ( NewDist_mm * 2 + TOF_Dist_mm * 3 ) / 5 ;
+ if (TOF_Dist_mm < TOF_MinDist_mm) { TOF_MinDist_mm = TOF_Dist_mm; pc_uart.printf("DMin = %3d. \r\n", TOF_MinDist_mm);} // adapt the min dist parameter
+
+ // The device theoretical working distance range is from 0 up to 1270mm, distance is always expressed in mm!
+ // However here we transform to a relative number, of which only the range 0 ... 1 should be used.
+ TOF_RelDist = ( (double) TOF_Dist_mm - TOF_MinDist_mm) / TOF_UseRange_mm;
+ if (TOF_RelDist <0) {TOF_RelDist = 0;} // clamping values <0 (that should actually never occur with above adaption of Min dist!, values >1 can still happen!
+ }
+ return true; // new measurement is available
+ }
+ else
+ { // pc_uart.printf(" --\r");
+ TOF_Dist_mm = out_of_range;
+ TOF_RelDist = out_of_range;
+ return false; // no new measurement is available
+ }
+}
+
+
+
+void help() // Display list of Commands
+{
+ DEBUG("List of commands:\n\r");
+ DEBUG(" h --> Help, display list of commands\n\r");
+}
+
+void callback()
+{
+ switch(state) {
+ case 0:
+ break;
+ case 1:
+ break;
+ case 2:
+ break;
+ case 3:
+ break;
+ default:
+ }
+ state=state+1;
+}
+
+/* Stop all processes */
+void stop_all()
+{
+ mybot.stopMove();
+}
+
+void clicked()
+{
+ DEBUG("Labyrinthe\n\r");
+ commandRECEIVED = 'l';
+ receivedCOMMAND = true;
+}
+
+void labyrinthe()
+{
+ wait(1);
+ mybot.move(FORWARD,15);
+ mybot.waitEndMove();
+ mybot.move(ROTATE, 90);
+ mybot.waitEndMove();
+ mybot.move(FORWARD,15);
+ mybot.waitEndMove();
+ mybot.move(ROTATE, 90);
+ mybot.waitEndMove();
+}
+
+void executeCommand(char c, int parameter)
+{
+ bool flaghelp = false;
+ pc_uart.printf("hffehihgiehighegieighieughei\n");
+ switch (c) {
+ case 'h':
+ help();
+ state=0;
+ flaghelp=true;
+ CASE('a', "Avance <cm> (a <cm>) => Avance du nombre de cm indiques", mybot.move(FORWARD,parameter); )
+ CASE('r', "Recule <cm> (r <cm>) => Recule du nombre de cm indiques", mybot.move(BACKWARD,parameter); )
+ CASE('d', "Droite <deg> (d <deg>) => Tourne a droite du nombre de degres indiques", mybot.move(RIGHT,parameter,0); )
+ CASE('g', "Gauche <deg> (g <deg>) => Tourne a gauche du nombre de degres indiques", mybot.move(LEFT,parameter,0); )
+ CASE('p', "Pivote_d <deh> (p <deg>) => pivote a droite du nombre de degres indiques", mybot.move(ROTATE,parameter); )
+ CASE('q', "Pivote_g <deg> (q <deg>) => pivote a gauche du nombre de degres indiques", mybot.move(ROTATE,-parameter); )
+ CASE('s', "Stop => Arrete les moteurs", mybot.stopMove(); state=0; )
+ CASE('l', "Labyrinthe => Lance le parcours Labyrinthe", labyrinthe(); )
+ default :
+ DEBUG("invalid command; use: 'h' for help()\n\r");
+ state=0;
+ }
+}
+
+void analyseCommand(char *command, int parameter)
+{
+ parameterRECEIVED = parameter;
+ switch(command[0]) {
+ case 'A':
+ case 'a':
+ commandRECEIVED = 'a';
+ break;
+ case 'R':
+ case 'r':
+ commandRECEIVED = 'r';
+ break;
+ case 'D':
+ case 'd':
+ commandRECEIVED = 'd';
+ break;
+ case 'G':
+ case 'g':
+ commandRECEIVED = 'g';
+ break;
+ case 'L':
+ case 'l':
+ commandRECEIVED = 'l';
+ break;
+ case 'P':
+ if(command[7]=='d') {
+ commandRECEIVED = 'p';
+ } else if (command[7]=='g') {
+ commandRECEIVED = 'q';
+ } else {
+ commandRECEIVED = 'h';
+ }
+ break;
+ case 'p':
+ commandRECEIVED = 'p';
+ break;
+ case 'q':
+ commandRECEIVED = 'q';
+ break;
+ case 'S':
+ case 's':
+ commandRECEIVED = 's';
+ mybot.stopMove();
+ state=0;
+ break;
+ default:
+ commandRECEIVED = 'h';
+ }
+}
+
+void checkCommand(int result, char *command, int parameter)
+{
+ if(result==2 || command[0]=='h' || command[0]=='s') {
+ if(command[0]=='c') {
+ DEBUG("CREABOT PRESENT\n\r");
+ } else {
+ analyseCommand(command, parameter);
+ receivedCOMMAND = true;
+ }
+ }
+}
+
+void split(char *line, int length)
+{
+ char command[256];
+ int parameter=0;
+ int result = 1;
+ int i=0;
+ int j=0;
+ while(i<length && line[i]==' ') {
+ i++;
+ }
+ while(i<length && line[i]!=' ') {
+ command[j]=line[i];
+ i++;
+ j++;
+ }
+ command[j]=0;
+ i++;
+ j=0;
+ while(i<length && line[i]!=' ' && line[i]>='0' && line[i]<='9') {
+ i++;
+ j++;
+ }
+ if(j>0) {
+ result++;
+ i--;
+ int k=1;
+ while(j>0) {
+ parameter += (line[i]-'0')*k;
+ j--;
+ i--;
+ k=k*10;
+ }
+ }
+ checkCommand(result, command, parameter);
+}
+
+void storeC(char c)
+{
+ if(c==10 || c==13|| commandPosition >= 254) {
+ split(commandLine, commandPosition);
+ commandPosition=0;
+ } else {
+ commandLine[commandPosition++]=c;
+ commandLine[commandPosition]=0;
+ }
+}
+
+void getBT()
+{
+ char c = bt_uart.getc();
+ storeC(c);
+}
+
+void getPC()
+{
+ char c = pc_uart.getc();
+ storeC(c);
+}
+
+void endOfMove(int status)
+{
+ DEBUG("ENDOFMOVE\n\r");
+ state=0;
+}
+void demoMode(void)
+{
+ init_TOF();
+ TOF_Dist_mm=200;
+ while(1){
+ if(GetNewTOF()){
+// pc_uart.printf("\n\rDistance : %d mm\n\r",TOF_Dist_mm);
+// DEBUG("\n\rDistance : %d mm\n\r",TOF_Dist_mm)
+ }
+
+ if (TOF_Dist_mm < 60 & TOF_Dist_mm > 0){
+ mybot.move(BACKWARD,5);
+ mybot.waitEndMove(5000000); // 5 seconds
+ mybot.move(ROTATE,-90);
+ mybot.waitEndMove(5000000); // 5 seconds
+ }
+ else{
+ mybot.move(FORWARD,5);
+// mybot.waitEndMove(5000000); // 5 seconds
+ }
+ }
+}
+/* Routine */
+int main()
+{
+ /* Rename HC-C6 BT*/
+
+ commandPosition=0;
+ pc_uart.attach(getPC);
+ bt_uart.attach(getBT);
+
+ mybot.setCallBack(endOfMove);
+ mybot.setSpeed(6.0); // max 6.9 cm.s, average 5 cm.s
+ state=0;
+ receivedCOMMAND = false;
+ DEBUG("CREABOT alpha version\n\r");
+ __disable_irq();
+ pc_uart.printf("Init Done ...\n\r");
+ __enable_irq();
+ pc_uart.printf("start passed ok\n");
+
+
+ ledBand.SetColor(BLUE,0);
+ ledBand.SetColor(BLUE,1);
+
+ isCmd.mode(PullUp);
+ pc_uart.printf("switchState=%d\n\r", isCmd.read());
+ if (isCmd.read()==0){
+ demoMode();
+ }
+ while(1) {
+ if(state==0 && receivedCOMMAND) {
+ receivedCOMMAND = false;
+ state=1;
+ pc_uart.printf("tototo\n");
+ executeCommand(commandRECEIVED, parameterRECEIVED);
+ }
+ wait(0.1);
+ }
+}
\ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Sat Feb 08 09:48:46 2020 +0000 @@ -0,0 +1,1 @@ +https://os.mbed.com/users/mbed_official/code/mbed/builds/65be27845400 \ No newline at end of file