Sensors and motors work / Mbed 2 deprecated nucleo_ros_good

Dependencies:   mbed ros_lib_kinetic

Files at this revision

API Documentation at this revision

Comitter:
florine_van
Date:
Thu Oct 17 12:22:14 2019 +0000
Parent:
8:a936ec892d87
Commit message:
clean code;

Changed in this revision

main.cpp Show annotated file Show diff for this revision Revisions of this file
diff -r a936ec892d87 -r 2b469b23c42d main.cpp
--- a/main.cpp	Thu Oct 17 12:12:03 2019 +0000
+++ b/main.cpp	Thu Oct 17 12:22:14 2019 +0000
@@ -1,4 +1,3 @@
-
 
 #include"mbed.h"
 #include <ros.h>
@@ -12,12 +11,11 @@
 DigitalOut SHDN_3(PD_2);
 DigitalOut SHDN_4(PG_3);
 
-
 // set-up serial to pc 
 I2C i2c(I2C_SDA, I2C_SCL); 
 // Set up I²C on the STM32 NUCLEO-401RE 
-#define addr1    (0x29) 
-#define addr2    (0x2A)  
+#define addr1   (0x29) 
+#define addr2   (0x2A)  
 #define addr3   (0x2B)
 #define addr4   (0x2C)
 
@@ -26,8 +24,6 @@
 #define ADDR2   (addr2<<1)
 #define ADDR3   (addr3<<1)
 #define ADDR4   (addr4<<1)
-
-
 // I²C address of VL6180 shifted by 1 bit                        
 //(0x29 << 1) so the R/W command can be added
 
@@ -67,13 +63,12 @@
 int VL6180_Init(char addr) {    
     char reset;    
     
+    // check to see has it be Initialised already
     reset = ReadByte(0x016, addr);    
     if (reset==1)
-    {      
-        // check to see has it be Initialised already
-    
+    {       
         /////////////////////////////////////////////////////////////////// 
-        // SENSOR 1
+        // DEFAULT SETTINGS
         ///////////////////////////////////////////////////////////////////
         // Mandatory : private registers 
         WriteByte(0x0207, 0x01, addr); 
@@ -108,7 +103,10 @@
         WriteByte(0x0030, 0x00, addr);
         
         WriteByte(0x016, 0x00, addr); //change fresh out of set status to 0    
-    }    
+    }  
+    else {
+        return -1;   
+    }  
     return 0; 
 }
 
@@ -123,7 +121,6 @@
 /////////////////////////////////////////////////////////////////// 
 // poll for new sample ready ready 
 /////////////////////////////////////////////////////////////////// 
-
 int VL6180_Poll_Range(char addr) {    
     char status;    
     char range_status;  
@@ -158,7 +155,6 @@
 /////////////////////////////////////////////////////////////////// 
 int VL6180_Clear_Interrupts(char addr) {    
     WriteByte(0x015,0x07, addr);    
-  //  WriteByte(0x015,0x07, addr2);  
     return 0; 
 }
 
@@ -190,34 +186,32 @@
     int range1; 
     int range2;
     int range3;
-    int range4;
-    
-    
+    int range4;  
     
-    //change default address of sensor 4
+    // load settings onto VL6180X sensors    
     VL6180_Init(ADDR1);
+    // change default address of sensor 2
     WriteByte(0x212, addr2, ADDR1);
+    
     SHDN_3 = 1;
     VL6180_Init(ADDR1);
+    // change default address of sensor 3
     WriteByte(0x212, addr3, ADDR1);
+    
     SHDN_4 = 1;
     VL6180_Init(ADDR1);
+    // change default address of sensor 4
     WriteByte(0x212, addr4, ADDR1);
+    
     SHDN_1 = 1;
-    VL6180_Init(ADDR1);
-    // load settings onto VL6180X    
-    //VL6180_Init(addr1<<1);
-    //SHDN_1 = 0; 
-    //VL6180_Init(addr2<<1);
-    
+    VL6180_Init(ADDR1);    
   
     while (1)
     {            
-        // start range measurement        
-        
-        // poll the VL6180 till new sample ready    
-        VL6180_Start_Range(ADDR1);    
-        //VL6180_Poll_Range(ADDR1);   
+        // start range measurement          
+        VL6180_Start_Range(ADDR1);
+        // poll the VL6180 till new sample ready      
+        VL6180_Poll_Range(ADDR1);   
         range1 = VL6180_Read_Range(ADDR1);
         VL6180_Clear_Interrupts(ADDR1);  
         wait_ms(10);
@@ -233,7 +227,7 @@
         VL6180_Clear_Interrupts(ADDR3);  
         wait_ms(10);
         VL6180_Start_Range(ADDR4);         
-        //VL6180_Poll_Range(ADDR4); 
+        VL6180_Poll_Range(ADDR4); 
         range4 = VL6180_Read_Range(ADDR4);
         VL6180_Clear_Interrupts(ADDR4);                 
         // clear the interrupt on VL6180                 
@@ -244,9 +238,8 @@
 //        range1_pub.publish(&int_sensor1_msg);     
 //        range2_pub.publish(&int_sensor2_msg);  
 //        nh.spinOnce();
-       pc.printf("Range one = %d | range two = %d | range three = %d | range four = %d\r\n",range1, range2, range3, range4);  
-       //pc.printf("lfajfl\r\n");
-       //pc.printf("Range one = %d\r\n ",range1);      
+
+        pc.printf("Range one = %d | range two = %d | range three = %d | range four = %d\r\n",range1, range2, range3, range4);       
         wait_ms(100); 
         
     }