mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 09:38:29 -04:00
AP_OpticalFlow - updated test sketch to allow testing of APM2 version
This commit is contained in:
parent
3075a0c5bd
commit
f18ee75b5c
@ -19,8 +19,8 @@
|
|||||||
//
|
//
|
||||||
FastSerialPort0(Serial); // FTDI/console
|
FastSerialPort0(Serial); // FTDI/console
|
||||||
|
|
||||||
AP_OpticalFlow_ADNS3080 flowSensor;
|
AP_OpticalFlow_ADNS3080 flowSensor; // for APM1
|
||||||
//AP_OpticalFlow_ADNS3080 flowSensor(A3); // override chip select pin to use A3 if using APM2
|
//AP_OpticalFlow_ADNS3080_APM2 flowSensor(A3); // override chip select pin to use A3 if using APM2
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
{
|
{
|
||||||
@ -30,8 +30,10 @@ void setup()
|
|||||||
delay(1000);
|
delay(1000);
|
||||||
|
|
||||||
// flowSensor initialization
|
// flowSensor initialization
|
||||||
if( flowSensor.init() == false )
|
if( flowSensor.init(true) == false ) {
|
||||||
Serial.println("Failed to initialise ADNS3080");
|
Serial.print("Failed to initialise ADNS3080 ");
|
||||||
|
}
|
||||||
|
|
||||||
flowSensor.set_orientation(AP_OPTICALFLOW_ADNS3080_PINS_FORWARD);
|
flowSensor.set_orientation(AP_OPTICALFLOW_ADNS3080_PINS_FORWARD);
|
||||||
flowSensor.set_field_of_view(AP_OPTICALFLOW_ADNS3080_08_FOV);
|
flowSensor.set_field_of_view(AP_OPTICALFLOW_ADNS3080_08_FOV);
|
||||||
|
|
||||||
|
@ -1,5 +1,6 @@
|
|||||||
AP_OpticalFlow KEYWORD1
|
AP_OpticalFlow KEYWORD1
|
||||||
AP_OpticalFlow_ADNS3080 KEYWORD1
|
AP_OpticalFlow_ADNS3080 KEYWORD1
|
||||||
|
AP_OpticalFlow_ADNS3080_APM2 KEYWORD1
|
||||||
init KEYWORD2
|
init KEYWORD2
|
||||||
read KEYWORD2
|
read KEYWORD2
|
||||||
update KEYWORD2
|
update KEYWORD2
|
||||||
|
Loading…
Reference in New Issue
Block a user