@@ -199,76 +199,84 @@ var FlightLogParser = function(logData) {
199199 // standard logger.
200200
201201 defaultSysConfigExtension = {
202- thrMid :null , // Throttle Mid Position
203- thrExpo :null , // Throttle Expo
204- tpa_breakpoint :null , // TPA Breakpoint
205- airmode_activate_throttle :null , // airmode activation level
206- serialrx_provider :null , // name of the serial rx provider
207- superExpoFactor :null , // Super Expo Factor
208- rates :[ null , null , null ] , // Rates [ROLL, PITCH, YAW]
209- rc_rates :[ null , null , null ] , // RC Rates [ROLL, PITCH, YAW]
210- rc_expo :[ null , null , null ] , // RC Expo [ROLL, PITCH, YAW]
211- looptime :null , // Looptime
212- gyro_sync_denom :null , // Gyro Sync Denom
213- pid_process_denom :null , // PID Process Denom
214- pidController :null , // Active PID Controller
215- rollPID :[ null , null , null ] , // Roll [P, I, D]
216- pitchPID :[ null , null , null ] , // Pitch[P, I, D]
217- yawPID :[ null , null , null ] , // Yaw [P, I, D]
218- feedforward_transition :null , // Feedforward transition
219- altPID :[ null , null , null ] , // Altitude Hold [P, I, D]
220- posPID :[ null , null , null ] , // Position Hold [P, I, D]
221- posrPID :[ null , null , null ] , // Position Rate [P, I, D]
222- navrPID :[ null , null , null ] , // Nav Rate [P, I, D]
223- levelPID :[ null , null , null ] , // Level Mode [P, I, D]
224- magPID :null , // Magnetometer P
225- velPID :[ null , null , null ] , // Velocity [P, I, D]
226- yaw_p_limit :null , // Yaw P Limit
227- yaw_lpf_hz :null , // Yaw LowPass Filter Hz
228- dterm_average_count :null , // DTerm Average Count
229- rollPitchItermResetRate :null , // ITerm Reset rate for Roll and Pitch
230- yawItermResetRate :null , // ITerm Reset Rate for Yaw
231- dterm_lpf_hz :null , // DTerm Lowpass Filter Hz
232- dterm_lpf2_hz :null , // DTerm Lowpass Filter Hz 2
233- dterm_differentiator :null , // DTerm Differentiator
234- H_sensitivity :null , // Horizon Sensitivity
235- iterm_reset_offset :null , // I-Term reset offset
236- deadband :null , // Roll, Pitch Deadband
237- yaw_deadband :null , // Yaw Deadband
238- gyro_lpf :null , // Gyro lpf setting.
239- gyro_32khz_hardware_lpf :null , // Gyro 32khz hardware lpf setting. (post BF3.4)
240- gyro_lowpass_hz :null , // Gyro Soft Lowpass Filter Hz
241- gyro_lowpass2_hz :null , // Gyro Soft Lowpass Filter Hz 2
242- gyro_notch_hz :null , // Gyro Notch Frequency
243- gyro_notch_cutoff :null , // Gyro Notch Cutoff
244- dterm_notch_hz :null , // Dterm Notch Frequency
245- dterm_notch_cutoff :null , // Dterm Notch Cutoff
246- acc_lpf_hz :null , // Accelerometer Lowpass filter Hz
247- acc_hardware :null , // Accelerometer Hardware type
248- baro_hardware :null , // Barometer Hardware type
249- mag_hardware :null , // Magnetometer Hardware type
250- gyro_cal_on_first_arm :null , // Gyro Calibrate on first arm
251- vbat_pid_compensation :null , // VBAT PID compensation
252- rc_smoothing :null , // RC Control Smoothing
253- rc_interpolation :null , // RC Control Interpolation type
254- rc_interpolation_interval :null , // RC Control Interpolation Interval
255- dterm_filter_type :null , // D term filtering type (PT1, BIQUAD)
256- pidAtMinThrottle :null , // Stabilisation at zero throttle
257- itermThrottleGain :null , // Betaflight PID
258- ptermSetpointWeight :null , // Betaflight PID
259- dtermSetpointWeight :null , // Betaflight PID
260- yawRateAccelLimit :null , // Betaflight PID
261- rateAccelLimit :null , // Betaflight PID
262- gyro_soft_type :null , // Gyro soft filter type (PT1, BIQUAD)
263- gyro_soft2_type :null , // Gyro soft filter 2 type (PT1, BIQUAD)
264- debug_mode :null , // Selected Debug Mode
265- features :null , // Activated features (e.g. MOTORSTOP etc)
266- Craft_name :null , // Craft Name
267- motorOutput :[ null , null ] , // Minimum and maximum outputs to motor's
268- digitalIdleOffset :null , // min throttle for d-shot (as a percentage)
269- pidSumLimit :null , // PID sum limit
270- pidSumLimitYaw :null , // PID sum limit yaw
271- unknownHeaders : [ ] // Unknown Extra Headers
202+ anti_gravity_gain :null , // Anti gravity gain
203+ anti_gravity_mode :null , // Anti gravity mode
204+ anti_gravity_threshold :null , // Anti gravity threshold for step mode
205+ thrMid :null , // Throttle Mid Position
206+ thrExpo :null , // Throttle Expo
207+ tpa_breakpoint :null , // TPA Breakpoint
208+ airmode_activate_throttle :null , // airmode activation level
209+ serialrx_provider :null , // name of the serial rx provider
210+ superExpoFactor :null , // Super Expo Factor
211+ rates :[ null , null , null ] , // Rates [ROLL, PITCH, YAW]
212+ rc_rates :[ null , null , null ] , // RC Rates [ROLL, PITCH, YAW]
213+ rc_expo :[ null , null , null ] , // RC Expo [ROLL, PITCH, YAW]
214+ looptime :null , // Looptime
215+ gyro_sync_denom :null , // Gyro Sync Denom
216+ pid_process_denom :null , // PID Process Denom
217+ pidController :null , // Active PID Controller
218+ rollPID :[ null , null , null ] , // Roll [P, I, D]
219+ pitchPID :[ null , null , null ] , // Pitch[P, I, D]
220+ yawPID :[ null , null , null ] , // Yaw [P, I, D]
221+ feedforward_transition :null , // Feedforward transition
222+ altPID :[ null , null , null ] , // Altitude Hold [P, I, D]
223+ posPID :[ null , null , null ] , // Position Hold [P, I, D]
224+ posrPID :[ null , null , null ] , // Position Rate [P, I, D]
225+ navrPID :[ null , null , null ] , // Nav Rate [P, I, D]
226+ levelPID :[ null , null , null ] , // Level Mode [P, I, D]
227+ magPID :null , // Magnetometer P
228+ velPID :[ null , null , null ] , // Velocity [P, I, D]
229+ yaw_p_limit :null , // Yaw P Limit
230+ yaw_lpf_hz :null , // Yaw LowPass Filter Hz
231+ dterm_average_count :null , // DTerm Average Count
232+ rollPitchItermResetRate :null , // ITerm Reset rate for Roll and Pitch
233+ yawItermResetRate :null , // ITerm Reset Rate for Yaw
234+ dterm_lpf_hz :null , // DTerm Lowpass Filter Hz
235+ dterm_lpf2_hz :null , // DTerm Lowpass Filter Hz 2
236+ dterm_differentiator :null , // DTerm Differentiator
237+ H_sensitivity :null , // Horizon Sensitivity
238+ iterm_reset_offset :null , // I-Term reset offset
239+ deadband :null , // Roll, Pitch Deadband
240+ yaw_deadband :null , // Yaw Deadband
241+ gyro_lpf :null , // Gyro lpf setting.
242+ gyro_32khz_hardware_lpf :null , // Gyro 32khz hardware lpf setting. (post BF3.4)
243+ gyro_lowpass_hz :null , // Gyro Soft Lowpass Filter Hz
244+ gyro_lowpass2_hz :null , // Gyro Soft Lowpass Filter Hz 2
245+ gyro_notch_hz :null , // Gyro Notch Frequency
246+ gyro_notch_cutoff :null , // Gyro Notch Cutoff
247+ dterm_notch_hz :null , // Dterm Notch Frequency
248+ dterm_notch_cutoff :null , // Dterm Notch Cutoff
249+ acc_lpf_hz :null , // Accelerometer Lowpass filter Hz
250+ acc_hardware :null , // Accelerometer Hardware type
251+ baro_hardware :null , // Barometer Hardware type
252+ mag_hardware :null , // Magnetometer Hardware type
253+ gyro_cal_on_first_arm :null , // Gyro Calibrate on first arm
254+ vbat_pid_compensation :null , // VBAT PID compensation
255+ rc_smoothing :null , // RC Control Smoothing
256+ rc_smoothing_type :null , // Type of the RC Smoothing
257+ rc_interpolation :null , // RC Control Interpolation type
258+ rc_interpolation_interval :null , // RC Control Interpolation Interval
259+ rc_smoothing_cutoffs :[ null , null ] , // RC Smoothing input and derivative cutoff
260+ rc_smoothing_filter_type :[ null , null ] , // RC Smoothing input and derivative type
261+ rc_smoothing_rx_average :null , // RC Smoothing rx average readed in ms
262+ rc_smoothing_debug_axis :null , // Axis recorded in the debug mode of rc_smoothing
263+ dterm_filter_type :null , // D term filtering type (PT1, BIQUAD)
264+ pidAtMinThrottle :null , // Stabilisation at zero throttle
265+ itermThrottleGain :null , // Betaflight PID
266+ ptermSetpointWeight :null , // Betaflight PID
267+ dtermSetpointWeight :null , // Betaflight PID
268+ yawRateAccelLimit :null , // Betaflight PID
269+ rateAccelLimit :null , // Betaflight PID
270+ gyro_soft_type :null , // Gyro soft filter type (PT1, BIQUAD)
271+ gyro_soft2_type :null , // Gyro soft filter 2 type (PT1, BIQUAD)
272+ debug_mode :null , // Selected Debug Mode
273+ features :null , // Activated features (e.g. MOTORSTOP etc)
274+ Craft_name :null , // Craft Name
275+ motorOutput :[ null , null ] , // Minimum and maximum outputs to motor's
276+ digitalIdleOffset :null , // min throttle for d-shot (as a percentage)
277+ pidSumLimit :null , // PID sum limit
278+ pidSumLimitYaw :null , // PID sum limit yaw
279+ unknownHeaders : [ ] // Unknown Extra Headers
272280 } ,
273281
274282 // Translation of the field values name to the sysConfig var where it must be stored
@@ -527,6 +535,9 @@ var FlightLogParser = function(logData) {
527535 case "gyro_cal_on_first_arm" :
528536 case "vbat_pid_compensation" :
529537 case "rc_smoothing" :
538+ case "rc_smoothing_type" :
539+ case "rc_smoothing_debug_axis" :
540+ case "rc_smoothing_rx_average" :
530541 case "superExpoYawMode" :
531542 case "features" :
532543 case "dynamic_pid" :
@@ -551,6 +562,7 @@ var FlightLogParser = function(logData) {
551562 case "gyro_soft_type" :
552563 case "gyro_soft2_type" :
553564 case "debug_mode" :
565+ case "anti_gravity_mode" :
554566 case "anti_gravity_gain" :
555567 that . sysConfig [ fieldName ] = parseInt ( fieldValue , 10 ) ;
556568 break ;
@@ -640,6 +652,8 @@ var FlightLogParser = function(logData) {
640652 case "levelPID" :
641653 case "velPID" :
642654 case "motorOutput" :
655+ case "rc_smoothing_cutoffs" :
656+ case "rc_smoothing_filter_type" :
643657 that . sysConfig [ fieldName ] = parseCommaSeparatedString ( fieldValue ) ;
644658 break ;
645659 case "magPID" :
0 commit comments