matlab: Update readme file for the replay and improve optical flow tuning

This commit is contained in:
Paul Riseborough 2017-06-26 15:23:30 +10:00
parent c1829d8e9a
commit 3e99898d47
2 changed files with 12 additions and 2 deletions

View File

@ -36,7 +36,7 @@ param.fusion.magDeclDeg = 10.5; % Magnetic declination in deg
%% Optical flow measurement fusion
param.fusion.rangeTimeDelay = 0.05; % range fidner sensor delay relative to IMU (sec)
param.fusion.flowTimeDelay = 0.05; % Optical flow sensor time delay relative to IMU (sec)
param.fusion.flowRateError = 0.5; % Observation noise 1SD for the flow sensor (rad/sec)
param.fusion.flowRateError = 0.1; % Observation noise 1SD for the flow sensor (rad/sec)
param.fusion.flowGate = 5.0; % Size of the optical flow rate innovation consistency check gate in SD
param.fusion.rngValidMin = 0.05; % range measurements wil be constrained to be no less than this (m)
param.fusion.rngValidMax = 5.0; % ignore range measurements larger than this (m)

View File

@ -30,6 +30,7 @@ Copy the generated .mat files into the /EKF_replay/TestData/APM directory.
Collect data with EK2_REC_RPL = 1
Convert the .ulg log file to .csv files using the PX4/pyulog python script https://github.com/PX4/pyulog/blob/master/pyulog/ulog2csv.py
Import the .csv file containing the sensor_combined_0 data into the matlab workspace and process it using …/EKF_replay/Common/convert_px4_sensor_combined_csv_data.m. This will generate the following data files:
imu_data.mat
@ -38,13 +39,22 @@ mag_data.mat
Import the .csv file containing the vehicle_gps_position_0 data into the matlab workspace and process it using …/EKF_replay/Common/convert_px4_vehicle_gps_position_csv. This will generate the gps_data.mat file.
If you have an optical flow and range finder sensor fitted:
Import the .csv file containing the optical_flow_0 data into the matlab workspace and process it using …/EKF_replay/Common/convert_px4_optical_flow_csv_data.m.
Import the .csv file containing the distance_sensor_0 data into the matlab workspace and process it using …/EKF_replay/Common/convert_px4_distance_sensor_csv_data.m.
This will generate the following data files:
flow_data.mat
rng_data.mat
Copy the generated .mat files into the /EKF_replay/TestData/PX4 directory.
4) Make ‘…/EKF_replay/Filter the working directory.
5) Execute SetParameterDefaults at the command prompt to load the default filter tuning parameter struct param into the workspace. The defaults have been set to provide robust estimation across the entire data set, not optimised for accuracy.
6) Replay the data by running either the replay_apm_data.m or replay_px4_data.m script files.
6) Replay the data by running either the replay_apm_data.m, replay_px4_data.m or if you have px4 optical flow data, the replay_px4_optflow_data.m script file.
Output plots are saved as .png files in the ‘…/EKF_replay/OutputPlots/ directory.