mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
removed DCM reference from OPT FLOW
This commit is contained in:
parent
1f52ad27d9
commit
41dada23ea
@ -168,7 +168,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||
AP_Compass_HIL compass; // never used
|
||||
AP_IMU_Shim imu; // never used
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
AP_OpticalFlow_ADNS3080 optflow(&dcm);
|
||||
AP_OpticalFlow_ADNS3080 optflow;
|
||||
#endif
|
||||
static int32_t gps_base_alt;
|
||||
#else
|
||||
@ -200,16 +200,10 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
|
||||
AP_DCM dcm(&imu, g_gps);
|
||||
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
AP_OpticalFlow_ADNS3080 optflow(&dcm);
|
||||
AP_OpticalFlow_ADNS3080 optflow();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HIL_MODE == HIL_MODE_ATTITUDE
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
AP_OpticalFlow_ADNS3080 optflow(&dcm);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// GCS selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -621,7 +615,7 @@ static void medium_loop()
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
if(g.optflow_enabled){
|
||||
optflow.read();
|
||||
optflow.update_position(cos_yaw_x, sin_yaw_y, current_loc.alt); // updates internal lon and lat with estimation based on optical flow
|
||||
optflow.update_position(dcm.roll, dcm.pitch, cos_yaw_x, sin_yaw_y, current_loc.alt); // updates internal lon and lat with estimation based on optical flow
|
||||
|
||||
// write to log
|
||||
if (g.log_bitmask & MASK_LOG_OPTFLOW){
|
||||
|
@ -207,7 +207,7 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// OPTICAL_FLOW
|
||||
#if defined( __AVR_ATmega2560__ ) // determines if optical flow code is included
|
||||
#define OPTFLOW_ENABLED
|
||||
//#define OPTFLOW_ENABLED
|
||||
#endif
|
||||
|
||||
//#define OPTFLOW_ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user