Rover: allow NavEKFs to be compiled out

This commit is contained in:
Peter Barker 2020-01-15 23:05:49 +11:00 committed by Andrew Tridgell
parent e358677f85
commit 797aa51025
2 changed files with 8 additions and 0 deletions

View File

@ -332,13 +332,17 @@ const AP_Param::Info Rover::var_info[] = {
GOBJECT(gps, "GPS_", AP_GPS), GOBJECT(gps, "GPS_", AP_GPS),
#if AP_AHRS_NAVEKF_AVAILABLE #if AP_AHRS_NAVEKF_AVAILABLE
#if HAL_NAVEKF2_AVAILABLE
// @Group: EK2_ // @Group: EK2_
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp // @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2), GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
#endif
#if HAL_NAVEKF3_AVAILABLE
// @Group: EK3_ // @Group: EK3_
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp // @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3), GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
#endif
#endif #endif
// @Group: RPM // @Group: RPM

View File

@ -60,7 +60,9 @@ void Rover::update_wheel_encoder()
const uint32_t now_ms = AP_HAL::millis(); const uint32_t now_ms = AP_HAL::millis();
// calculate angular change (in radians) // calculate angular change (in radians)
#if HAL_NAVEKF3_AVAILABLE
const float delta_angle = curr_angle_rad - wheel_encoder_last_angle_rad[wheel_encoder_last_index_sent]; const float delta_angle = curr_angle_rad - wheel_encoder_last_angle_rad[wheel_encoder_last_index_sent];
#endif
wheel_encoder_last_angle_rad[wheel_encoder_last_index_sent] = curr_angle_rad; wheel_encoder_last_angle_rad[wheel_encoder_last_index_sent] = curr_angle_rad;
// calculate delta time using time between sensor readings or time since last send to ekf (whichever is shorter) // calculate delta time using time between sensor readings or time since last send to ekf (whichever is shorter)
@ -72,6 +74,7 @@ void Rover::update_wheel_encoder()
} else { } else {
wheel_encoder_last_reading_ms[wheel_encoder_last_index_sent] = sensor_reading_ms; wheel_encoder_last_reading_ms[wheel_encoder_last_index_sent] = sensor_reading_ms;
} }
#if HAL_NAVEKF3_AVAILABLE
const float delta_time = sensor_diff_ms * 0.001f; const float delta_time = sensor_diff_ms * 0.001f;
/* delAng is the measured change in angular position from the previous measurement where a positive rotation is produced by forward motion of the vehicle (rad) /* delAng is the measured change in angular position from the previous measurement where a positive rotation is produced by forward motion of the vehicle (rad)
@ -84,6 +87,7 @@ void Rover::update_wheel_encoder()
wheel_encoder_last_reading_ms[wheel_encoder_last_index_sent], wheel_encoder_last_reading_ms[wheel_encoder_last_index_sent],
g2.wheel_encoder.get_pos_offset(wheel_encoder_last_index_sent), g2.wheel_encoder.get_pos_offset(wheel_encoder_last_index_sent),
g2.wheel_encoder.get_wheel_radius(wheel_encoder_last_index_sent)); g2.wheel_encoder.get_wheel_radius(wheel_encoder_last_index_sent));
#endif
} }
// Accel calibration // Accel calibration