mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_Optflow - small fix to lat/lon calculation and made example sketch work again
This commit is contained in:
parent
30f4ced9df
commit
1ff58aaa81
@ -97,9 +97,9 @@ AP_OpticalFlow::update_position(float roll, float pitch, float cos_yaw_x, float
|
|||||||
x_cm = -change_x * avg_altitude * conv_factor; // perhaps this altitude should actually be the distance to the ground? i.e. if we are very rolled over it should be longer?
|
x_cm = -change_x * avg_altitude * conv_factor; // perhaps this altitude should actually be the distance to the ground? i.e. if we are very rolled over it should be longer?
|
||||||
y_cm = -change_y * avg_altitude * conv_factor; // for example if you are leaned over at 45 deg the ground will appear farther away and motion from opt flow sensor will be less
|
y_cm = -change_y * avg_altitude * conv_factor; // for example if you are leaned over at 45 deg the ground will appear farther away and motion from opt flow sensor will be less
|
||||||
|
|
||||||
|
// convert x/y movements into lon/lat movement
|
||||||
vlon = x_cm * sin_yaw_y - y_cm * cos_yaw_x;
|
vlon = x_cm * sin_yaw_y + y_cm * cos_yaw_x;
|
||||||
vlat = y_cm * sin_yaw_y - x_cm * cos_yaw_x;
|
vlat = y_cm * sin_yaw_y - x_cm * cos_yaw_x;
|
||||||
}
|
}
|
||||||
|
|
||||||
_last_altitude = altitude;
|
_last_altitude = altitude;
|
||||||
|
@ -3,10 +3,23 @@
|
|||||||
Code by Randy Mackay. DIYDrones.com
|
Code by Randy Mackay. DIYDrones.com
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include <FastSerial.h>
|
||||||
|
#include <AP_Common.h>
|
||||||
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
|
||||||
#include <SPI.h> // Arduino SPI library
|
#include <SPI.h> // Arduino SPI library
|
||||||
|
#include <AP_DCM.h> // ArduCopter DCM Library
|
||||||
#include "AP_OpticalFlow.h" // ArduCopter OpticalFlow Library
|
#include "AP_OpticalFlow.h" // ArduCopter OpticalFlow Library
|
||||||
|
|
||||||
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
// Serial ports
|
||||||
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
|
//
|
||||||
|
// Note that FastSerial port buffers are allocated at ::begin time,
|
||||||
|
// so there is not much of a penalty to defining ports that we don't
|
||||||
|
// use.
|
||||||
|
//
|
||||||
|
FastSerialPort0(Serial); // FTDI/console
|
||||||
|
|
||||||
AP_OpticalFlow_ADNS3080 flowSensor;
|
AP_OpticalFlow_ADNS3080 flowSensor;
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
@ -297,7 +310,7 @@ void display_motion()
|
|||||||
|
|
||||||
while( !Serial.available() ) {
|
while( !Serial.available() ) {
|
||||||
flowSensor.read();
|
flowSensor.read();
|
||||||
flowSensor.get_position(0,0,0,100);
|
flowSensor.update_position(0,0,0,1,100);
|
||||||
|
|
||||||
// x,y,squal
|
// x,y,squal
|
||||||
//if( flowSensor.motion() || first_time ) {
|
//if( flowSensor.motion() || first_time ) {
|
||||||
|
Loading…
Reference in New Issue
Block a user