From 8e5ee61b02542e0f50e87fbb4acce15d33d41cbf Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 11 Aug 2024 14:51:46 -0500 Subject: [PATCH] AP_NavEKF3: derivation: don't generate unused equations The code is left in for the future when they might be used. --- libraries/AP_NavEKF3/derivation/generate_1.py | 34 +++++++++---------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/libraries/AP_NavEKF3/derivation/generate_1.py b/libraries/AP_NavEKF3/derivation/generate_1.py index fcdd3db2365e1..8f738925c8e0e 100755 --- a/libraries/AP_NavEKF3/derivation/generate_1.py +++ b/libraries/AP_NavEKF3/derivation/generate_1.py @@ -682,25 +682,25 @@ def generate_code(): # quaternion_error_propagation() # print('Generating heading observation code ...') # yaw_observation(P,state,R_to_earth) - print('Generating gps heading observation code ...') - gps_yaw_observation(P,state,R_to_body) - print('Generating mag observation code ...') - mag_observation_variance(P,state,R_to_body,i,ib) - mag_observation(P,state,R_to_body,i,ib) - print('Generating declination observation code ...') - declination_observation(P,state,ix,iy) - print('Generating airspeed observation code ...') - tas_observation(P,state,vx,vy,vz,wx,wy) - print('Generating sideslip observation code ...') - beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy) - print('Generating optical flow observation code ...') - optical_flow_observation(P,state,R_to_body,vx,vy,vz) - print('Generating body frame velocity observation code ...') - body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz) + # print('Generating gps heading observation code ...') + # gps_yaw_observation(P,state,R_to_body) + # print('Generating mag observation code ...') + # mag_observation_variance(P,state,R_to_body,i,ib) + # mag_observation(P,state,R_to_body,i,ib) + # print('Generating declination observation code ...') + # declination_observation(P,state,ix,iy) + # print('Generating airspeed observation code ...') + # tas_observation(P,state,vx,vy,vz,wx,wy) + # print('Generating sideslip observation code ...') + # beta_observation(P,state,R_to_body,vx,vy,vz,wx,wy) + # print('Generating optical flow observation code ...') + # optical_flow_observation(P,state,R_to_body,vx,vy,vz) + # print('Generating body frame velocity observation code ...') + # body_frame_velocity_observation(P,state,R_to_body,vx,vy,vz) # print('Generating body frame acceleration observation code ...') # body_frame_accel_observation(P,state,R_to_body,vx,vy,vz,wx,wy) - print('Generating yaw estimator code ...') - yaw_estimator() + # print('Generating yaw estimator code ...') + # yaw_estimator() print('Code generation finished!')