@@ -51,6 +51,8 @@ Arduino_AlvikCarrier::Arduino_AlvikCarrier(){
51
51
52
52
// color sensor
53
53
apds9960 = new APDS9960 (*wire, APDS_INT);
54
+ apds9999 = new Arduino_APDS9999 (*wire);
55
+ color_sensor_used = -1 ;
54
56
55
57
// servo
56
58
servo_A = new Servo ();
@@ -170,21 +172,41 @@ int Arduino_AlvikCarrier::beginAPDS(){
170
172
pinMode (APDS_LED, OUTPUT);
171
173
// enableIlluminator();
172
174
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;
175
189
}
190
+
176
191
return 0 ;
177
192
}
178
193
179
194
void 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
+ }
182
202
}
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 ();
186
209
}
187
- // digitalWrite(APDS_LED,LOW);
188
210
}
189
211
190
212
void Arduino_AlvikCarrier::setIlluminator (uint8_t value){
@@ -228,7 +250,9 @@ int Arduino_AlvikCarrier::getProximity(){
228
250
229
251
int Arduino_AlvikCarrier::beginServo (){
230
252
servo_A->attach (SERVO_A);
253
+ delay (200 );
231
254
servo_B->attach (SERVO_B);
255
+ delay (200 );
232
256
return 0 ;
233
257
}
234
258
@@ -1052,12 +1076,23 @@ void Arduino_AlvikCarrier::setBehaviour(const uint8_t behaviour, const bool enab
1052
1076
}
1053
1077
1054
1078
bool 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
+ }
1057
1086
}
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
+ }
1060
1094
}
1095
+ return false ;
1061
1096
}
1062
1097
1063
1098
0 commit comments