mirror of https://github.com/ArduPilot/ardupilot
Rover: EKF objects have moved into AP_AHRS_NavEKF
This commit is contained in:
parent
373b8be7ef
commit
50484c3321
|
@ -334,11 +334,11 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
// @Group: EK2_
|
||||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||
GOBJECTN(EKF2, NavEKF2, "EK2_", NavEKF2),
|
||||
GOBJECTN(ahrs.EKF2, NavEKF2, "EK2_", NavEKF2),
|
||||
|
||||
// @Group: EK3_
|
||||
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
|
||||
GOBJECTN(EKF3, NavEKF3, "EK3_", NavEKF3),
|
||||
GOBJECTN(ahrs.EKF3, NavEKF3, "EK3_", NavEKF3),
|
||||
#endif
|
||||
|
||||
// @Group: RPM
|
||||
|
|
|
@ -79,7 +79,7 @@ void Rover::update_wheel_encoder()
|
|||
* timeStamp_ms is the time when the rotation was last measured (msec)
|
||||
* posOffset is the XYZ body frame position of the wheel hub (m)
|
||||
*/
|
||||
EKF3.writeWheelOdom(delta_angle,
|
||||
ahrs.EKF3.writeWheelOdom(delta_angle,
|
||||
delta_time,
|
||||
wheel_encoder_last_reading_ms[wheel_encoder_last_index_sent],
|
||||
g2.wheel_encoder.get_pos_offset(wheel_encoder_last_index_sent),
|
||||
|
|
Loading…
Reference in New Issue