diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 693a385009..cdd35b294d 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -411,6 +411,11 @@ private: // last visual odometry update time uint32_t visual_odom_last_update_ms; + // last wheel encoder update times + float wheel_encoder_last_angle_rad[WHEELENCODER_MAX_INSTANCES]; // distance in radians at time of last update to EKF + uint32_t wheel_encoder_last_update_ms[WHEELENCODER_MAX_INSTANCES]; // system time of last ping from each encoder + uint32_t wheel_encoder_last_ekf_update_ms; // system time of last encoder data push to EKF + // True when we are doing motor test bool motor_test; diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index c485b08160..e720d9d400 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -95,7 +95,63 @@ void Rover::update_visual_odom() // update wheel encoders void Rover::update_wheel_encoder() { + // exit immediately if not enabled + if (g2.wheel_encoder.num_sensors() == 0) { + return; + } + + // update encoders g2.wheel_encoder.update(); + + // initialise on first iteration + uint32_t now = AP_HAL::millis(); + if (wheel_encoder_last_ekf_update_ms == 0) { + wheel_encoder_last_ekf_update_ms = now; + for (uint8_t i = 0; i 100) { + delta_time = system_dt; + wheel_encoder_last_update_ms[i] = wheel_encoder_last_ekf_update_ms; + } else { + delta_time = sensor_diff_ms / 1000.0f; + wheel_encoder_last_update_ms[i] = latest_sensor_update_ms; + } + + /* 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) + * delTime is the time interval for the measurement of delAng (sec) + * 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, delta_time, wheel_encoder_last_update_ms[i], g2.wheel_encoder.get_position(i), g2.wheel_encoder.get_wheel_radius(i)); + } + + // record system time update for next iteration + wheel_encoder_last_ekf_update_ms = now; } // read_battery - reads battery voltage and current and invokes failsafe