Browse Source

Rover: remove ability to use DCM as AHRS

gps-1.3.1
Peter Barker 4 years ago committed by Peter Barker
parent
commit
3b15ff0d42
  1. 3
      Rover/Log.cpp
  2. 2
      Rover/Parameters.cpp
  3. 2
      Rover/Rover.h

3
Rover/Log.cpp

@ -12,10 +12,9 @@ void Rover::Log_Write_Attitude() @@ -12,10 +12,9 @@ void Rover::Log_Write_Attitude()
ahrs.Write_Attitude(targets);
#if AP_AHRS_NAVEKF_AVAILABLE
AP::ahrs_navekf().Log_Write();
ahrs.Write_AHRS2();
#endif
ahrs.Write_POS();
// log steering rate controller

2
Rover/Parameters.cpp

@ -343,7 +343,6 @@ const AP_Param::Info Rover::var_info[] = { @@ -343,7 +343,6 @@ const AP_Param::Info Rover::var_info[] = {
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
GOBJECT(gps, "GPS", AP_GPS),
#if AP_AHRS_NAVEKF_AVAILABLE
#if HAL_NAVEKF2_AVAILABLE
// @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
@ -354,7 +353,6 @@ const AP_Param::Info Rover::var_info[] = { @@ -354,7 +353,6 @@ const AP_Param::Info Rover::var_info[] = {
// @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
#endif
#endif
// @Group: RPM

2
Rover/Rover.h

@ -162,9 +162,7 @@ private: @@ -162,9 +162,7 @@ private:
AP_L1_Control L1_controller{ahrs, nullptr};
#if AP_AHRS_NAVEKF_AVAILABLE
OpticalFlow optflow;
#endif
#if OSD_ENABLED || OSD_PARAM_ENABLED
AP_OSD osd;

Loading…
Cancel
Save