@@ -51,6 +51,8 @@ Arduino_AlvikCarrier::Arduino_AlvikCarrier(){
5151
5252 // color sensor
5353 apds9960 = new APDS9960 (*wire, APDS_INT);
54+ apds9999 = new Arduino_APDS9999 (*wire);
55+ color_sensor_used = -1 ;
5456
5557 // servo
5658 servo_A = new Servo ();
@@ -170,21 +172,41 @@ int Arduino_AlvikCarrier::beginAPDS(){
170172 pinMode (APDS_LED, OUTPUT);
171173 // enableIlluminator();
172174 disableIlluminator ();
173- if (!apds9960->begin ()){
174- return ERROR_APDS;
175+
176+ if (!apds9999->begin ()){
177+ if (!apds9960->begin ()){
178+ return ERROR_APDS;
179+ }
180+ color_sensor_used = APDS9960_VERSION;
181+ }
182+ else {
183+ apds9999->enableColorSensor ();
184+ apds9999->enableProximitySensor ();
185+ apds9999->setGain (APDS9999_GAIN_3X);
186+ apds9999->setLSResolution (APDS9999_LS_RES_16B);
187+ apds9999->setLSRate (APDS9999_LS_RATE_25MS);
188+ color_sensor_used = APDS9999_VERSION;
175189 }
190+
176191 return 0 ;
177192}
178193
179194void Arduino_AlvikCarrier::updateAPDS (){
180- if (apds9960->proximityAvailable ()){
181- bottom_proximity=apds9960->readProximity ();
195+ if (color_sensor_used == APDS9960_VERSION){
196+ if (apds9960->proximityAvailable ()){
197+ bottom_proximity=apds9960->readProximity ();
198+ }
199+ if (apds9960->colorAvailable ()){
200+ apds9960->readColor (bottom_red, bottom_green, bottom_blue, bottom_clear);
201+ }
182202 }
183- // digitalWrite(APDS_LED,HIGH);
184- if (apds9960->colorAvailable ()){
185- apds9960->readColor (bottom_red, bottom_green, bottom_blue, bottom_clear);
203+ if (color_sensor_used == APDS9999_VERSION){
204+ bottom_proximity = 255 - apds9999->getProximity ();
205+ bottom_red = apds9999->getRed ();
206+ bottom_green = apds9999->getGreen ();
207+ bottom_blue = apds9999->getBlue ();
208+ bottom_clear = apds9999->getIR ();
186209 }
187- // digitalWrite(APDS_LED,LOW);
188210}
189211
190212void Arduino_AlvikCarrier::setIlluminator (uint8_t value){
@@ -228,7 +250,9 @@ int Arduino_AlvikCarrier::getProximity(){
228250
229251int Arduino_AlvikCarrier::beginServo (){
230252 servo_A->attach (SERVO_A);
253+ delay (200 );
231254 servo_B->attach (SERVO_B);
255+ delay (200 );
232256 return 0 ;
233257}
234258
@@ -1052,12 +1076,23 @@ void Arduino_AlvikCarrier::setBehaviour(const uint8_t behaviour, const bool enab
10521076}
10531077
10541078bool Arduino_AlvikCarrier::isLifted (){
1055- if (getProximity ()>LIFT_THRESHOLD){
1056- return true ;
1079+ if (color_sensor_used == APDS9960_VERSION){
1080+ if (getProximity ()>LIFT_THRESHOLD){
1081+ return true ;
1082+ }
1083+ else {
1084+ return false ;
1085+ }
10571086 }
1058- else {
1059- return false ;
1087+ if (color_sensor_used == APDS9999_VERSION){
1088+ if (getProximity ()>=254 ){ // different scale
1089+ return true ;
1090+ }
1091+ else {
1092+ return false ;
1093+ }
10601094 }
1095+ return false ;
10611096}
10621097
10631098
0 commit comments