OpticalFlow - fixed minor compiler warnings and moved chip select to A3 for APM2

This commit is contained in:
Randy Mackay 2012-01-26 23:35:49 +09:00
parent 8dee001657
commit a8b3d2f063
1 changed files with 13 additions and 19 deletions

View File

@ -21,7 +21,7 @@
FastSerialPort0(Serial); // FTDI/console FastSerialPort0(Serial); // FTDI/console
AP_OpticalFlow_ADNS3080 flowSensor; AP_OpticalFlow_ADNS3080 flowSensor;
//AP_OpticalFlow_ADNS3080 flowSensor(A6); // override chip select pin to use A6 if using APM2 //AP_OpticalFlow_ADNS3080 flowSensor(A3); // override chip select pin to use A3 if using APM2
void setup() void setup()
{ {
@ -110,7 +110,6 @@ void display_config()
void set_frame_rate() void set_frame_rate()
{ {
int value; int value;
byte extConfig;
// frame rate // frame rate
Serial.print("frame rate: "); Serial.print("frame rate: ");
@ -196,7 +195,6 @@ void display_image_continuously()
void set_resolution() void set_resolution()
{ {
int value; int value;
byte reg;
int resolution = flowSensor.get_resolution(); int resolution = flowSensor.get_resolution();
Serial.print("resolution: "); Serial.print("resolution: ");
Serial.println(resolution); Serial.println(resolution);
@ -231,7 +229,6 @@ void set_resolution()
void set_shutter_speed() void set_shutter_speed()
{ {
int value; int value;
byte extConfig;
// shutter speed // shutter speed
Serial.print("shutter speed: "); Serial.print("shutter speed: ");
@ -300,7 +297,6 @@ void set_shutter_speed()
// //
void display_motion() void display_motion()
{ {
int value;
boolean first_time = true; boolean first_time = true;
Serial.flush(); Serial.flush();
@ -317,20 +313,18 @@ void display_motion()
Serial.println("overflow!!"); Serial.println("overflow!!");
// x,y,squal // x,y,squal
//if( flowSensor.motion() || first_time ) { Serial.print("x/dx: ");
Serial.print("x/dx: "); Serial.print(flowSensor.x,DEC);
Serial.print(flowSensor.x,DEC); Serial.print("/");
Serial.print("/"); Serial.print(flowSensor.dx,DEC);
Serial.print(flowSensor.dx,DEC); Serial.print("\ty/dy: ");
Serial.print("\ty/dy: "); Serial.print(flowSensor.y,DEC);
Serial.print(flowSensor.y,DEC); Serial.print("/");
Serial.print("/"); Serial.print(flowSensor.dy,DEC);
Serial.print(flowSensor.dy,DEC); Serial.print("\tsqual:");
Serial.print("\tsqual:"); Serial.print(flowSensor.surface_quality,DEC);
Serial.print(flowSensor.surface_quality,DEC); Serial.println();
Serial.println(); first_time = false;
first_time = false;
//}
// short delay // short delay
delay(100); delay(100);