diff --git a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde
index 5e8324651b0f3debdd087c41b2e8429f4ea8b6b5..b959dc7d104d9fbc2584034a052b0c49097d3545 100644
--- a/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde
+++ b/libraries/AP_OpticalFlow/examples/AP_OpticalFlow_test/AP_OpticalFlow_test.pde
@@ -19,19 +19,21 @@
 //
 FastSerialPort0(Serial);        // FTDI/console
 
-AP_OpticalFlow_ADNS3080 flowSensor;
-//AP_OpticalFlow_ADNS3080 flowSensor(A3);  // override chip select pin to use A3 if using APM2
+AP_OpticalFlow_ADNS3080 flowSensor;		// for APM1
+//AP_OpticalFlow_ADNS3080_APM2 flowSensor(A3);  // override chip select pin to use A3 if using APM2
 
 void setup()
-{  
+{
 	Serial.begin(115200);
 	Serial.println("ArduPilot Mega OpticalFlow library test ver 1.5");
 
 	delay(1000);
-	
+
 	// flowSensor initialization
-	if( flowSensor.init() == false )
-	    Serial.println("Failed to initialise ADNS3080");
+	if( flowSensor.init(true) == false ) {
+	    Serial.print("Failed to initialise ADNS3080 ");
+	}
+
 	flowSensor.set_orientation(AP_OPTICALFLOW_ADNS3080_PINS_FORWARD);
 	flowSensor.set_field_of_view(AP_OPTICALFLOW_ADNS3080_08_FOV);
 	
@@ -336,7 +338,7 @@ void display_motion()
 void loop()
 {
 	int value;
-	
+
 	// display menu to user
 	display_menu();
 	
diff --git a/libraries/AP_OpticalFlow/keywords.txt b/libraries/AP_OpticalFlow/keywords.txt
index 1bcb812592c29d79efab19e9929dcf59af16a77b..8393f31eceb9c8d59ea627aedc7c2c4a7555a06f 100644
--- a/libraries/AP_OpticalFlow/keywords.txt
+++ b/libraries/AP_OpticalFlow/keywords.txt
@@ -1,5 +1,6 @@
 AP_OpticalFlow	KEYWORD1
 AP_OpticalFlow_ADNS3080	KEYWORD1
+AP_OpticalFlow_ADNS3080_APM2	KEYWORD1
 init	KEYWORD2
 read	KEYWORD2
 update	KEYWORD2