James Kuszmaul | 29c5952 | 2022-02-12 16:44:26 -0800 | [diff] [blame] | 1 | #include "y2022/control_loops/localizer/localizer.h" |
| 2 | |
| 3 | #include "frc971/control_loops/c2d.h" |
| 4 | #include "frc971/wpilib/imu_batch_generated.h" |
| 5 | // TODO(james): Things to do: |
| 6 | // -Approach still seems fundamentally sound. |
| 7 | // -Really need to work on cost/residual function. |
| 8 | // -Particularly for handling stopping. |
| 9 | // -Extra hysteresis |
| 10 | |
| 11 | namespace frc971::controls { |
| 12 | |
| 13 | namespace { |
| 14 | constexpr double kG = 9.80665; |
| 15 | constexpr std::chrono::microseconds kNominalDt(500); |
| 16 | |
| 17 | template <int N> |
| 18 | Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) { |
| 19 | CHECK_EQ(static_cast<size_t>(N), values.size()); |
| 20 | Eigen::Matrix<double, N, 1> vector; |
| 21 | for (int ii = 0; ii < N; ++ii) { |
| 22 | vector(ii, 0) = values[ii]; |
| 23 | } |
| 24 | return vector; |
| 25 | } |
| 26 | |
| 27 | #if 0 |
| 28 | Eigen::Matrix<double, 3, 3> AxisToMatrix(const Eigen::Vector3d &vec) { |
| 29 | const double rotation_norm = vec.norm(); |
| 30 | return rotation_norm < 1e-5 |
| 31 | ? Eigen::Matrix<double, 3, 3>::Identity() |
| 32 | : Eigen::AngleAxis<double>(rotation_norm, vec / rotation_norm) |
| 33 | .toRotationMatrix(); |
| 34 | } |
| 35 | #endif |
| 36 | } // namespace |
| 37 | |
| 38 | ModelBasedLocalizer::ModelBasedLocalizer( |
| 39 | const control_loops::drivetrain::DrivetrainConfig<double> &dt_config) |
| 40 | : dt_config_(dt_config), |
| 41 | velocity_drivetrain_coefficients_( |
| 42 | dt_config.make_hybrid_drivetrain_velocity_loop() |
| 43 | .plant() |
| 44 | .coefficients()), |
| 45 | down_estimator_(dt_config) { |
| 46 | if (dt_config_.is_simulated) { |
| 47 | down_estimator_.assume_perfect_gravity(); |
| 48 | } |
| 49 | A_continuous_accel_.setZero(); |
| 50 | A_continuous_model_.setZero(); |
| 51 | B_continuous_accel_.setZero(); |
| 52 | B_continuous_model_.setZero(); |
| 53 | |
| 54 | A_continuous_accel_(kX, kVelocityX) = 1.0; |
| 55 | A_continuous_accel_(kY, kVelocityY) = 1.0; |
| 56 | |
| 57 | const double diameter = 2.0 * dt_config_.robot_radius; |
| 58 | |
| 59 | A_continuous_model_(kTheta, kLeftVelocity) = -1.0 / diameter; |
| 60 | A_continuous_model_(kTheta, kRightVelocity) = 1.0 / diameter; |
| 61 | A_continuous_model_(kLeftEncoder, kLeftVelocity) = 1.0; |
| 62 | A_continuous_model_(kRightEncoder, kRightVelocity) = 1.0; |
| 63 | const auto &vel_coefs = velocity_drivetrain_coefficients_; |
| 64 | A_continuous_model_(kLeftVelocity, kLeftVelocity) = |
| 65 | vel_coefs.A_continuous(0, 0); |
| 66 | A_continuous_model_(kLeftVelocity, kRightVelocity) = |
| 67 | vel_coefs.A_continuous(0, 1); |
| 68 | A_continuous_model_(kRightVelocity, kLeftVelocity) = |
| 69 | vel_coefs.A_continuous(1, 0); |
| 70 | A_continuous_model_(kRightVelocity, kRightVelocity) = |
| 71 | vel_coefs.A_continuous(1, 1); |
| 72 | |
| 73 | A_continuous_model_(kLeftVelocity, kLeftVoltageError) = |
| 74 | 1 * vel_coefs.B_continuous(0, 0); |
| 75 | A_continuous_model_(kLeftVelocity, kRightVoltageError) = |
| 76 | 1 * vel_coefs.B_continuous(0, 1); |
| 77 | A_continuous_model_(kRightVelocity, kLeftVoltageError) = |
| 78 | 1 * vel_coefs.B_continuous(1, 0); |
| 79 | A_continuous_model_(kRightVelocity, kRightVoltageError) = |
| 80 | 1 * vel_coefs.B_continuous(1, 1); |
| 81 | |
| 82 | B_continuous_model_.block<1, 2>(kLeftVelocity, kLeftVoltage) = |
| 83 | vel_coefs.B_continuous.row(0); |
| 84 | B_continuous_model_.block<1, 2>(kRightVelocity, kLeftVoltage) = |
| 85 | vel_coefs.B_continuous.row(1); |
| 86 | |
| 87 | B_continuous_accel_(kVelocityX, kAccelX) = 1.0; |
| 88 | B_continuous_accel_(kVelocityY, kAccelY) = 1.0; |
| 89 | B_continuous_accel_(kTheta, kThetaRate) = 1.0; |
| 90 | |
| 91 | Q_continuous_model_.setZero(); |
| 92 | Q_continuous_model_.diagonal() << 1e-4, 1e-4, 1e-4, 1e-2, 1e-0, 1e-0, 1e-2, |
| 93 | 1e-0, 1e-0; |
| 94 | |
| 95 | P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt); |
| 96 | } |
| 97 | |
| 98 | Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates, |
| 99 | ModelBasedLocalizer::kNModelStates> |
| 100 | ModelBasedLocalizer::AModel( |
| 101 | const ModelBasedLocalizer::ModelState &state) const { |
| 102 | Eigen::Matrix<double, kNModelStates, kNModelStates> A = A_continuous_model_; |
| 103 | const double theta = state(kTheta); |
| 104 | const double stheta = std::sin(theta); |
| 105 | const double ctheta = std::cos(theta); |
| 106 | const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0; |
| 107 | A(kX, kTheta) = -stheta * velocity; |
| 108 | A(kX, kLeftVelocity) = ctheta / 2.0; |
| 109 | A(kX, kRightVelocity) = ctheta / 2.0; |
| 110 | A(kY, kTheta) = ctheta * velocity; |
| 111 | A(kY, kLeftVelocity) = stheta / 2.0; |
| 112 | A(kY, kRightVelocity) = stheta / 2.0; |
| 113 | return A; |
| 114 | } |
| 115 | |
| 116 | Eigen::Matrix<double, ModelBasedLocalizer::kNAccelStates, |
| 117 | ModelBasedLocalizer::kNAccelStates> |
| 118 | ModelBasedLocalizer::AAccel() const { |
| 119 | return A_continuous_accel_; |
| 120 | } |
| 121 | |
| 122 | ModelBasedLocalizer::ModelState ModelBasedLocalizer::DiffModel( |
| 123 | const ModelBasedLocalizer::ModelState &state, |
| 124 | const ModelBasedLocalizer::ModelInput &U) const { |
| 125 | ModelState x_dot = AModel(state) * state + B_continuous_model_ * U; |
| 126 | const double theta = state(kTheta); |
| 127 | const double stheta = std::sin(theta); |
| 128 | const double ctheta = std::cos(theta); |
| 129 | const double velocity = (state(kLeftVelocity) + state(kRightVelocity)) / 2.0; |
| 130 | x_dot(kX) = ctheta * velocity; |
| 131 | x_dot(kY) = stheta * velocity; |
| 132 | return x_dot; |
| 133 | } |
| 134 | |
| 135 | ModelBasedLocalizer::AccelState ModelBasedLocalizer::DiffAccel( |
| 136 | const ModelBasedLocalizer::AccelState &state, |
| 137 | const ModelBasedLocalizer::AccelInput &U) const { |
| 138 | return AAccel() * state + B_continuous_accel_ * U; |
| 139 | } |
| 140 | |
| 141 | ModelBasedLocalizer::ModelState ModelBasedLocalizer::UpdateModel( |
| 142 | const ModelBasedLocalizer::ModelState &model, |
| 143 | const ModelBasedLocalizer::ModelInput &input, |
| 144 | const aos::monotonic_clock::duration dt) const { |
| 145 | return control_loops::RungeKutta( |
| 146 | std::bind(&ModelBasedLocalizer::DiffModel, this, std::placeholders::_1, |
| 147 | input), |
| 148 | model, aos::time::DurationInSeconds(dt)); |
| 149 | } |
| 150 | |
| 151 | ModelBasedLocalizer::AccelState ModelBasedLocalizer::UpdateAccel( |
| 152 | const ModelBasedLocalizer::AccelState &accel, |
| 153 | const ModelBasedLocalizer::AccelInput &input, |
| 154 | const aos::monotonic_clock::duration dt) const { |
| 155 | return control_loops::RungeKutta( |
| 156 | std::bind(&ModelBasedLocalizer::DiffAccel, this, std::placeholders::_1, |
| 157 | input), |
| 158 | accel, aos::time::DurationInSeconds(dt)); |
| 159 | } |
| 160 | |
| 161 | ModelBasedLocalizer::AccelState ModelBasedLocalizer::AccelStateForModelState( |
| 162 | const ModelBasedLocalizer::ModelState &state) const { |
| 163 | const double robot_speed = |
| 164 | (state(kLeftVelocity) + state(kRightVelocity)) / 2.0; |
| 165 | const double velocity_x = std::cos(state(kTheta)) * robot_speed; |
| 166 | const double velocity_y = std::sin(state(kTheta)) * robot_speed; |
| 167 | return (AccelState() << state(0), state(1), state(2), velocity_x, velocity_y) |
| 168 | .finished(); |
| 169 | } |
| 170 | |
| 171 | ModelBasedLocalizer::ModelState ModelBasedLocalizer::ModelStateForAccelState( |
| 172 | const ModelBasedLocalizer::AccelState &state, |
| 173 | const Eigen::Vector2d &encoders, const double yaw_rate) const { |
| 174 | const double robot_speed = state(kVelocityX) * std::cos(state(kTheta)) + |
| 175 | state(kVelocityY) * std::sin(state(kTheta)); |
| 176 | const double radius = dt_config_.robot_radius; |
| 177 | const double left_velocity = robot_speed - yaw_rate * radius; |
| 178 | const double right_velocity = robot_speed + yaw_rate * radius; |
| 179 | return (ModelState() << state(0), state(1), state(2), encoders(0), |
| 180 | left_velocity, 0.0, encoders(1), right_velocity, 0.0) |
| 181 | .finished(); |
| 182 | } |
| 183 | |
| 184 | double ModelBasedLocalizer::ModelDivergence( |
| 185 | const ModelBasedLocalizer::CombinedState &state, |
| 186 | const ModelBasedLocalizer::AccelInput &accel_inputs, |
| 187 | const Eigen::Vector2d &filtered_accel, |
| 188 | const ModelBasedLocalizer::ModelInput &model_inputs) { |
| 189 | // Convert the model state into the acceleration-based state-space and check |
| 190 | // the distance between the two (should really be a weighted norm, but all the |
| 191 | // numbers are on ~the same scale). |
| 192 | VLOG(2) << "divergence: " |
| 193 | << (state.accel_state - AccelStateForModelState(state.model_state)) |
| 194 | .transpose(); |
| 195 | const AccelState diff_accel = DiffAccel(state.accel_state, accel_inputs); |
| 196 | const ModelState diff_model = DiffModel(state.model_state, model_inputs); |
| 197 | const double model_lng_velocity = |
| 198 | (state.model_state(kLeftVelocity) + state.model_state(kRightVelocity)) / |
| 199 | 2.0; |
| 200 | const double model_lng_accel = |
| 201 | (diff_model(kLeftVelocity) + diff_model(kRightVelocity)) / 2.0; |
| 202 | const Eigen::Vector2d robot_frame_accel( |
| 203 | model_lng_accel, diff_model(kTheta) * model_lng_velocity); |
| 204 | const Eigen::Vector2d model_accel = |
| 205 | Eigen::AngleAxisd(state.model_state(kTheta), Eigen::Vector3d::UnitZ()) |
| 206 | .toRotationMatrix() |
| 207 | .block<2, 2>(0, 0) * |
| 208 | robot_frame_accel; |
| 209 | const double accel_diff = (model_accel - filtered_accel).norm(); |
| 210 | const double theta_rate_diff = |
| 211 | std::abs(diff_accel(kTheta) - diff_model(kTheta)); |
| 212 | |
| 213 | const Eigen::Vector2d accel_vel = state.accel_state.bottomRows<2>(); |
| 214 | const Eigen::Vector2d model_vel = |
| 215 | AccelStateForModelState(state.model_state).bottomRows<2>(); |
| 216 | velocity_residual_ = (accel_vel - model_vel).norm() / |
| 217 | (1.0 + accel_vel.norm() + model_vel.norm()); |
| 218 | theta_rate_residual_ = theta_rate_diff; |
| 219 | accel_residual_ = accel_diff / 4.0; |
| 220 | return velocity_residual_ + theta_rate_residual_ + accel_residual_; |
| 221 | } |
| 222 | |
| 223 | void ModelBasedLocalizer::HandleImu(aos::monotonic_clock::time_point t, |
| 224 | const Eigen::Vector3d &gyro, |
| 225 | const Eigen::Vector3d &accel, |
| 226 | const Eigen::Vector2d encoders, |
| 227 | const Eigen::Vector2d voltage) { |
| 228 | VLOG(2) << t; |
| 229 | if (t_ == aos::monotonic_clock::min_time) { |
| 230 | t_ = t; |
| 231 | } |
| 232 | if (t_ + 2 * kNominalDt < t) { |
| 233 | t_ = t; |
| 234 | ++clock_resets_; |
| 235 | } |
| 236 | const aos::monotonic_clock::duration dt = t - t_; |
| 237 | t_ = t; |
| 238 | down_estimator_.Predict(gyro, accel, dt); |
| 239 | // TODO(james): Should we prefer this or use the down-estimator corrected |
| 240 | // version? |
| 241 | const double yaw_rate = (dt_config_.imu_transform * gyro)(2); |
| 242 | const double diameter = 2.0 * dt_config_.robot_radius; |
| 243 | |
| 244 | const Eigen::AngleAxis<double> orientation( |
| 245 | Eigen::AngleAxis<double>(xytheta()(kTheta), Eigen::Vector3d::UnitZ()) * |
| 246 | down_estimator_.X_hat()); |
| 247 | |
| 248 | const Eigen::Vector3d absolute_accel = |
| 249 | orientation * dt_config_.imu_transform * kG * accel; |
| 250 | abs_accel_ = absolute_accel; |
| 251 | const Eigen::Vector3d absolute_gyro = |
| 252 | orientation * dt_config_.imu_transform * gyro; |
| 253 | (void)absolute_gyro; |
| 254 | |
| 255 | VLOG(2) << "abs accel " << absolute_accel.transpose(); |
| 256 | VLOG(2) << "abs gyro " << absolute_gyro.transpose(); |
| 257 | VLOG(2) << "dt " << aos::time::DurationInSeconds(dt); |
| 258 | |
| 259 | // Update all the branched states. |
| 260 | const AccelInput accel_input(absolute_accel.x(), absolute_accel.y(), |
| 261 | yaw_rate); |
| 262 | const ModelInput model_input(voltage); |
| 263 | |
| 264 | const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous = |
| 265 | AModel(current_state_.model_state); |
| 266 | |
| 267 | Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete; |
| 268 | Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete; |
| 269 | |
| 270 | DiscretizeQAFast(Q_continuous_model_, A_continuous, dt, &Q_discrete, |
| 271 | &A_discrete); |
| 272 | |
| 273 | P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete; |
| 274 | |
| 275 | Eigen::Matrix<double, kNModelOutputs, kNModelStates> H; |
| 276 | Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R; |
| 277 | { |
| 278 | H.setZero(); |
| 279 | R.setZero(); |
| 280 | H(0, kLeftEncoder) = 1.0; |
| 281 | H(1, kRightEncoder) = 1.0; |
| 282 | H(2, kRightVelocity) = 1.0 / diameter; |
| 283 | H(2, kLeftVelocity) = -1.0 / diameter; |
| 284 | |
| 285 | R.diagonal() << 1e-9, 1e-9, 1e-13; |
| 286 | } |
| 287 | |
| 288 | const Eigen::Matrix<double, kNModelOutputs, 1> Z(encoders(0), encoders(1), |
| 289 | yaw_rate); |
| 290 | |
| 291 | if (branches_.empty()) { |
| 292 | VLOG(2) << "Initializing"; |
| 293 | current_state_.model_state.setZero(); |
| 294 | current_state_.accel_state.setZero(); |
| 295 | current_state_.model_state(kLeftEncoder) = encoders(0); |
| 296 | current_state_.model_state(kRightEncoder) = encoders(1); |
| 297 | current_state_.branch_time = t; |
| 298 | branches_.Push(current_state_); |
| 299 | } |
| 300 | |
| 301 | const Eigen::Matrix<double, kNModelStates, kNModelOutputs> K = |
| 302 | P_model_ * H.transpose() * (H * P_model_ * H.transpose() + R).inverse(); |
| 303 | P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() - |
| 304 | K * H) * |
| 305 | P_model_; |
| 306 | VLOG(2) << "K\n" << K; |
| 307 | VLOG(2) << "Z\n" << Z.transpose(); |
| 308 | |
| 309 | for (CombinedState &state : branches_) { |
| 310 | state.accel_state = UpdateAccel(state.accel_state, accel_input, dt); |
| 311 | if (down_estimator_.consecutive_still() > 100.0) { |
| 312 | state.accel_state(kVelocityX) *= 0.9; |
| 313 | state.accel_state(kVelocityY) *= 0.9; |
| 314 | } |
| 315 | state.model_state = UpdateModel(state.model_state, model_input, dt); |
| 316 | state.model_state += K * (Z - H * state.model_state); |
| 317 | } |
| 318 | |
| 319 | VLOG(2) << "oildest accel " << branches_[0].accel_state.transpose(); |
| 320 | VLOG(2) << "oildest accel diff " |
| 321 | << DiffAccel(branches_[0].accel_state, accel_input).transpose(); |
| 322 | VLOG(2) << "oildest model " << branches_[0].model_state.transpose(); |
| 323 | |
| 324 | // Determine whether to switch modes--if we are currently in model-based mode, |
| 325 | // swap to accel-based if the two states have divergeed meaningfully in the |
| 326 | // oldest branch. If we are currently in accel-based, then swap back to model |
| 327 | // if the oldest model branch matches has matched the |
| 328 | filtered_residual_accel_ += |
| 329 | 0.01 * (accel_input.topRows<2>() - filtered_residual_accel_); |
| 330 | const double model_divergence = |
| 331 | branches_.full() ? ModelDivergence(branches_[0], accel_input, |
| 332 | filtered_residual_accel_, model_input) |
| 333 | : 0.0; |
| 334 | filtered_residual_ += |
| 335 | (1.0 - std::exp(-aos::time::DurationInSeconds(kNominalDt) / 0.0095)) * |
| 336 | (model_divergence - filtered_residual_); |
| 337 | constexpr double kUseAccelThreshold = 0.4; |
| 338 | constexpr double kUseModelThreshold = 0.2; |
| 339 | constexpr size_t kShareStates = kNModelStates; |
| 340 | static_assert(kUseModelThreshold < kUseAccelThreshold); |
| 341 | if (using_model_) { |
| 342 | if (filtered_residual_ > kUseAccelThreshold) { |
| 343 | hysteresis_count_++; |
| 344 | } else { |
| 345 | hysteresis_count_ = 0; |
| 346 | } |
| 347 | if (hysteresis_count_ > 0) { |
| 348 | using_model_ = false; |
| 349 | // Grab the accel-based state from back when we started diverging. |
| 350 | // TODO(james): This creates a problematic selection bias, because |
| 351 | // we will tend to bias towards deliberately out-of-tune measurements. |
| 352 | current_state_.accel_state = branches_[0].accel_state; |
| 353 | current_state_.model_state = branches_[0].model_state; |
| 354 | current_state_.model_state = ModelStateForAccelState( |
| 355 | current_state_.accel_state, encoders, yaw_rate); |
| 356 | } else { |
| 357 | VLOG(2) << "Normal branching"; |
| 358 | current_state_.model_state = branches_[branches_.size() - 1].model_state; |
| 359 | current_state_.accel_state = |
| 360 | AccelStateForModelState(current_state_.model_state); |
| 361 | current_state_.branch_time = t; |
| 362 | } |
| 363 | hysteresis_count_ = 0; |
| 364 | } else { |
| 365 | if (filtered_residual_ < kUseModelThreshold) { |
| 366 | hysteresis_count_++; |
| 367 | } else { |
| 368 | hysteresis_count_ = 0; |
| 369 | } |
| 370 | if (hysteresis_count_ > 100) { |
| 371 | using_model_ = true; |
| 372 | // Grab the model-based state from back when we stopped diverging. |
| 373 | current_state_.model_state.topRows<kShareStates>() = |
| 374 | ModelStateForAccelState(branches_[0].accel_state, encoders, yaw_rate) |
| 375 | .topRows<kShareStates>(); |
| 376 | current_state_.accel_state = |
| 377 | AccelStateForModelState(current_state_.model_state); |
| 378 | } else { |
| 379 | current_state_.accel_state = branches_[branches_.size() - 1].accel_state; |
| 380 | // TODO(james): Why was I leaving the encoders/wheel velocities in place? |
| 381 | current_state_.model_state = branches_[branches_.size() - 1].model_state; |
| 382 | current_state_.model_state = ModelStateForAccelState( |
| 383 | current_state_.accel_state, encoders, yaw_rate); |
| 384 | current_state_.branch_time = t; |
| 385 | } |
| 386 | } |
| 387 | |
| 388 | // Generate a new branch, with the accel state reset based on the model-based |
| 389 | // state (really, just getting rid of the lateral velocity). |
| 390 | CombinedState new_branch = current_state_; |
| 391 | //if (!keep_accel_state) { |
| 392 | if (using_model_) { |
| 393 | new_branch.accel_state = AccelStateForModelState(new_branch.model_state); |
| 394 | } |
| 395 | new_branch.accumulated_divergence = 0.0; |
| 396 | |
| 397 | branches_.Push(new_branch); |
| 398 | |
| 399 | last_residual_ = model_divergence; |
| 400 | |
| 401 | VLOG(2) << "Using " << (using_model_ ? "model" : "accel"); |
| 402 | VLOG(2) << "Residual " << last_residual_; |
| 403 | VLOG(2) << "Filtered Residual " << filtered_residual_; |
| 404 | VLOG(2) << "buffer size " << branches_.size(); |
| 405 | VLOG(2) << "Model state " << current_state_.model_state.transpose(); |
| 406 | VLOG(2) << "Accel state " << current_state_.accel_state.transpose(); |
| 407 | VLOG(2) << "Accel state for model " |
| 408 | << AccelStateForModelState(current_state_.model_state).transpose(); |
| 409 | VLOG(2) << "Input acce " << accel.transpose(); |
| 410 | VLOG(2) << "Input gyro " << gyro.transpose(); |
| 411 | VLOG(2) << "Input voltage " << voltage.transpose(); |
| 412 | VLOG(2) << "Input encoder " << encoders.transpose(); |
| 413 | VLOG(2) << "yaw rate " << yaw_rate; |
| 414 | |
| 415 | CHECK(std::isfinite(last_residual_)); |
| 416 | } |
| 417 | |
| 418 | void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now, |
| 419 | const Eigen::Vector3d &xytheta) { |
| 420 | branches_.Reset(); |
| 421 | t_ = now; |
| 422 | using_model_ = true; |
| 423 | current_state_.model_state << xytheta(0), xytheta(1), xytheta(2), |
| 424 | current_state_.model_state(kLeftEncoder), 0.0, 0.0, |
| 425 | current_state_.model_state(kRightEncoder), 0.0, 0.0; |
| 426 | current_state_.accel_state = |
| 427 | AccelStateForModelState(current_state_.model_state); |
| 428 | last_residual_ = 0.0; |
| 429 | filtered_residual_ = 0.0; |
| 430 | filtered_residual_accel_.setZero(); |
| 431 | abs_accel_.setZero(); |
| 432 | } |
| 433 | |
| 434 | flatbuffers::Offset<AccelBasedState> ModelBasedLocalizer::BuildAccelState( |
| 435 | flatbuffers::FlatBufferBuilder *fbb, const AccelState &state) { |
| 436 | AccelBasedState::Builder accel_state_builder(*fbb); |
| 437 | accel_state_builder.add_x(state(kX)); |
| 438 | accel_state_builder.add_y(state(kY)); |
| 439 | accel_state_builder.add_theta(state(kTheta)); |
| 440 | accel_state_builder.add_velocity_x(state(kVelocityX)); |
| 441 | accel_state_builder.add_velocity_y(state(kVelocityY)); |
| 442 | return accel_state_builder.Finish(); |
| 443 | } |
| 444 | |
| 445 | flatbuffers::Offset<ModelBasedState> ModelBasedLocalizer::BuildModelState( |
| 446 | flatbuffers::FlatBufferBuilder *fbb, const ModelState &state) { |
| 447 | ModelBasedState::Builder model_state_builder(*fbb); |
| 448 | model_state_builder.add_x(state(kX)); |
| 449 | model_state_builder.add_y(state(kY)); |
| 450 | model_state_builder.add_theta(state(kTheta)); |
| 451 | model_state_builder.add_left_encoder(state(kLeftEncoder)); |
| 452 | model_state_builder.add_left_velocity(state(kLeftVelocity)); |
| 453 | model_state_builder.add_left_voltage_error(state(kLeftVoltageError)); |
| 454 | model_state_builder.add_right_encoder(state(kRightEncoder)); |
| 455 | model_state_builder.add_right_velocity(state(kRightVelocity)); |
| 456 | model_state_builder.add_right_voltage_error(state(kRightVoltageError)); |
| 457 | return model_state_builder.Finish(); |
| 458 | } |
| 459 | |
| 460 | flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus( |
| 461 | flatbuffers::FlatBufferBuilder *fbb) { |
| 462 | const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState> |
| 463 | down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_); |
| 464 | |
| 465 | const CombinedState &state = current_state_; |
| 466 | |
| 467 | const flatbuffers::Offset<ModelBasedState> model_state_offset = |
| 468 | BuildModelState(fbb, state.model_state); |
| 469 | |
| 470 | const flatbuffers::Offset<AccelBasedState> accel_state_offset = |
| 471 | BuildAccelState(fbb, state.accel_state); |
| 472 | |
| 473 | const flatbuffers::Offset<AccelBasedState> oldest_accel_state_offset = |
| 474 | branches_.empty() ? flatbuffers::Offset<AccelBasedState>() |
| 475 | : BuildAccelState(fbb, branches_[0].accel_state); |
| 476 | |
| 477 | const flatbuffers::Offset<ModelBasedState> oldest_model_state_offset = |
| 478 | branches_.empty() ? flatbuffers::Offset<ModelBasedState>() |
| 479 | : BuildModelState(fbb, branches_[0].model_state); |
| 480 | |
| 481 | ModelBasedStatus::Builder builder(*fbb); |
| 482 | builder.add_accel_state(accel_state_offset); |
| 483 | builder.add_oldest_accel_state(oldest_accel_state_offset); |
| 484 | builder.add_oldest_model_state(oldest_model_state_offset); |
| 485 | builder.add_model_state(model_state_offset); |
| 486 | builder.add_using_model(using_model_); |
| 487 | builder.add_residual(last_residual_); |
| 488 | builder.add_filtered_residual(filtered_residual_); |
| 489 | builder.add_velocity_residual(velocity_residual_); |
| 490 | builder.add_accel_residual(accel_residual_); |
| 491 | builder.add_theta_rate_residual(theta_rate_residual_); |
| 492 | builder.add_down_estimator(down_estimator_offset); |
| 493 | builder.add_x(xytheta()(0)); |
| 494 | builder.add_y(xytheta()(1)); |
| 495 | builder.add_theta(xytheta()(2)); |
| 496 | builder.add_implied_accel_x(abs_accel_(0)); |
| 497 | builder.add_implied_accel_y(abs_accel_(1)); |
| 498 | builder.add_implied_accel_z(abs_accel_(2)); |
| 499 | builder.add_clock_resets(clock_resets_); |
| 500 | return builder.Finish(); |
| 501 | } |
| 502 | |
| 503 | EventLoopLocalizer::EventLoopLocalizer( |
| 504 | aos::EventLoop *event_loop, |
| 505 | const control_loops::drivetrain::DrivetrainConfig<double> &dt_config) |
| 506 | : event_loop_(event_loop), |
| 507 | model_based_(dt_config), |
| 508 | status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")), |
| 509 | output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")), |
James Kuszmaul | 29c5952 | 2022-02-12 16:44:26 -0800 | [diff] [blame] | 510 | output_fetcher_( |
| 511 | event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>( |
| 512 | "/drivetrain")) { |
| 513 | event_loop_->MakeWatcher( |
| 514 | "/drivetrain", |
| 515 | [this]( |
| 516 | const frc971::control_loops::drivetrain::LocalizerControl &control) { |
| 517 | const double theta = control.keep_current_theta() |
| 518 | ? model_based_.xytheta()(2) |
| 519 | : control.theta(); |
| 520 | model_based_.HandleReset(event_loop_->monotonic_now(), |
| 521 | {control.x(), control.y(), theta}); |
| 522 | }); |
| 523 | event_loop_->MakeWatcher( |
| 524 | "/localizer", [this](const frc971::IMUValuesBatch &values) { |
| 525 | CHECK(values.has_readings()); |
James Kuszmaul | 29c5952 | 2022-02-12 16:44:26 -0800 | [diff] [blame] | 526 | output_fetcher_.Fetch(); |
| 527 | for (const IMUValues *value : *values.readings()) { |
| 528 | zeroer_.InsertAndProcessMeasurement(*value); |
| 529 | if (zeroer_.Zeroed()) { |
James Kuszmaul | e5f67dd | 2022-02-12 20:08:29 -0800 | [diff] [blame] | 530 | if (output_fetcher_.get() != nullptr) { |
| 531 | const bool disabled = |
| 532 | output_fetcher_.context().monotonic_event_time + |
| 533 | std::chrono::milliseconds(10) < |
| 534 | event_loop_->context().monotonic_event_time; |
| 535 | model_based_.HandleImu( |
| 536 | aos::monotonic_clock::time_point(std::chrono::nanoseconds( |
| 537 | value->monotonic_timestamp_ns())), |
| 538 | zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(), |
| 539 | {value->left_encoder(), value->right_encoder()}, |
| 540 | disabled ? Eigen::Vector2d::Zero() |
| 541 | : Eigen::Vector2d{output_fetcher_->left_voltage(), |
| 542 | output_fetcher_->right_voltage()}); |
| 543 | } |
James Kuszmaul | 29c5952 | 2022-02-12 16:44:26 -0800 | [diff] [blame] | 544 | } |
| 545 | { |
| 546 | auto builder = status_sender_.MakeBuilder(); |
| 547 | const flatbuffers::Offset<ModelBasedStatus> model_based_status = |
| 548 | model_based_.PopulateStatus(builder.fbb()); |
| 549 | LocalizerStatus::Builder status_builder = |
| 550 | builder.MakeBuilder<LocalizerStatus>(); |
| 551 | status_builder.add_model_based(model_based_status); |
| 552 | status_builder.add_zeroed(zeroer_.Zeroed()); |
| 553 | status_builder.add_faulted_zero(zeroer_.Faulted()); |
| 554 | builder.CheckOk(builder.Send(status_builder.Finish())); |
| 555 | } |
| 556 | if (last_output_send_ + std::chrono::milliseconds(5) < |
| 557 | event_loop_->context().monotonic_event_time) { |
| 558 | auto builder = output_sender_.MakeBuilder(); |
| 559 | LocalizerOutput::Builder output_builder = |
| 560 | builder.MakeBuilder<LocalizerOutput>(); |
James Kuszmaul | 1798c07 | 2022-02-13 15:32:11 -0800 | [diff] [blame^] | 561 | // TODO(james): Should we bother to try to estimate time offsets for |
| 562 | // the pico? |
| 563 | output_builder.add_monotonic_timestamp_ns( |
| 564 | value->monotonic_timestamp_ns()); |
James Kuszmaul | 29c5952 | 2022-02-12 16:44:26 -0800 | [diff] [blame] | 565 | output_builder.add_x(model_based_.xytheta()(0)); |
| 566 | output_builder.add_y(model_based_.xytheta()(1)); |
| 567 | output_builder.add_theta(model_based_.xytheta()(2)); |
| 568 | builder.CheckOk(builder.Send(output_builder.Finish())); |
| 569 | last_output_send_ = event_loop_->monotonic_now(); |
| 570 | } |
| 571 | } |
| 572 | }); |
| 573 | } |
| 574 | |
| 575 | } // namespace frc971::controls |