Skip to content
tkazik edited this page Nov 8, 2021 · 8 revisions

Parameter files

This page provides a sample parameter file for MSF and a detailed description of the parameters. In addition, it gives heuristics on how to choose them where possible. The sample parameter file can be found here. For an introduction on how to run MSF, refer to the Setup for GPS and ROVIO page.

MSF Core Parameters

These parameters belong to the main MSF program and not to a specific sensor and are necessary independent of the sensors in use.

  • scale_init: Here, a scaling factor can be defined. I found this to be (almost) always 1, i.e. no scaling.
  • core/data_playback: This boolean variable should be set True if you are running the system from a ROSbag and False otherwise. Note that when using a ROSbag you need to set the ROS parameter to use simulation time to true: rosparam set use_sim_time true. In addition, you should play your ROSbag using the --clock option.
  • core/fixed_bias: This is a boolean variable as well. When set to True, the IMU bias can not be adapted online by MSF. In general, setting this to False is a good idea unless you are very confident in your biases and certain they won't change during runtime.
  • core IMU parameters: These parameters are specific to the IMU used as MSF's IMU. Note that there might be multiple IMU's but only one should be mapped to MSF's IMU input. The 4 parameters to be set are: core/core_noise_acc, core/core_noise_accbias, core/core_noise_gyr, core/core_noise_gyrbias

MSF single sensor Parameters

These parameters belong to a single sensor of MSF. They only need to be set for sensors in use and might vary slightly depending on the sensor in use. For simplicity, I will only list the parameters once, where sensortype should be replaced by the appropriate name e.g. sensortype/init/q_ic should be replaced by pose_sensor/init/q_ic for a pose sensor. For pose and position sensors, all necessary parameters are listed in the sample parameter file.

  • Transformation parameters: This values define the transformation between the measurement point of the respective sensor and the drone IMU and have to be computed/estimated a priori. For pose measurement this is a 6 DOF transform and for position a 3 DOF transform. The corresponding parameters are: sensortype/init/q_ic/x, sensortype/init/q_ic/y, sensortype/init/q_ic/z, sensortype/init/q_ic/w, sensortype/init/p_ic/x, sensortype/init/p_ic/y, sensortype/init/p_ic/z
  • sensortype/type_absolute_measurements: This boolean parameter defines whether the measurements of the sensor are given as absolute measurements or relative to its last measurement.
  • sensortype/type_use_fixed_covariance: This boolean parameter defines whether MSF should use a fixed covariance (True) or the covariance provided by the filter (False). This has to be set to True if the sensor does not provide a covariance measurement. (I did not test this feature so I can't argue about its performance)
  • sensortype/type_measurement_world_sensor: This parameter is boolean as well. It selects if the sensor measures its position w.r.t. the world (True, e.g. Vicon, Rovio) or the position of the world coordinate system w.r.t. the sensor (False, e.g. ethzasl_ptam)

Stability features

These features serve as a tradeoff between stability on precision. By default, they are all set to False, but should be taken into consideration unless you are very certain about the behavior of your system.

  • Outlier rejection: There are two parameters used for outlier rejection. The first sensortype/enable_mah_outlier_rejection is boolean and simply enables the feature when set to True. The second is sensortype/mah_threshold. It is of type double and defines the limit of accepting measurements. Generally, it is a good idea to use outlier rejection unless you are really confident your sensors won't produce outliers and events, then it does not significantly decrease precision. As a threshold choosing around 5 proved to work well. Recall that the Mahalanobis distance depends on the covariance of the sensor and therefore does not have to be adjusted for noisier sensors as long as the noise parameter is chosen accordingly.
  • Noise Estimation: Note that this feature is only relevant if you are NOT using covariance from sensor. Noise estimation is defined using 3 parameters. The first sensortype/enable_noise_estimation is a boolean to enable or disable the noise estimation feature. If disabled the noise parameter is kept constant at the initial value. The second parameter is sensortype/noise_estimation_discount_factor and is used to define the discount factor of the average computation: averagei+1 = (1-alpha)*d + alpha * averagei, where alpha is in [0,1]. The final parameter is sensortype/max_noise_threshold. It is optional and can be used to define an upper limit for noise. If the "true" noise exceeds this limit MSF will no longer increase its estimate and therefore most likely reject all measurements from this sensor. Generally, noise estimation proved to be useful if you are either uncertain about your noise estimate or if you expect the noise to change during operation. Given an exact initial noise, noise estimation might lose some precision. When choosing the discount factor one should think about the frequency of the sensor. The higher the frequency the closer it should be chosen to 1, since otherwise noise might be adjusted too frequently [?]. A value of 0.999 turned out to be reasonable for a frequency of 100Hz. The maximal noise threshold might help in case of diverging sensors, where otherwise the noise estimate might become extremely large and thus take a long time to recover. However, for stability reasons, it should be chosen rather large.
  • Sensor Recovery: There are three main parameters for sensor recovery. In addition, there are some more parameters related to recovery discussed under transform recovery below. The first parameter again is a boolean called sensortype/enable_divergence_recovery that enables or disables sensor recovery. The second parameter sensortype/divergence_rejection_limit defines how many measurements have to be rejected back-to-back until the sensor is regarded as diverging. The last parameter called sensortype/use_reset_to_pose defines whether the sensor should be reset to the last pose estimate (True) or completely restarted (False). This should always be chosen True if the sensor provides a method to reset to pose, since it increases accuracy. This feature should only be enabled for sensors that are not expected to recover on their own, such as ROVIO. Sensors like GPS that will eventually recover on their own do not benefit from this feature. Using it anyways would decrease precision. The rejection limit gives a tradeoff between time to reaction and precision, since in general, the system will lose some accuracy when resetting one does not want to choose this parameter too small since otherwise the sensor might be reset even when it is not actually diverging. On the other hand, choosing it too large will cause the system to take longer to take action resulting in a loss of information. Choosing a threshold of around 30 proved to work well, however again one might think about the frequency of the sensor when choosing this parameter.

Sensor handler parameters

These parameters correspond to an MSF sensorhandler and not to a specific sensor. For a description of the difference please refer to its ROS wiki. Generally, they should rather be chosen too large than too small. If there is no good a priori estimate the noise estimation feature should be enabled.

  • Noise parameters: handlertype/sensortype_noise_meas_p and handlertype/sensortype_noise_meas_q give the initial values for noise of corresponding sensortype for translation (p) and rotation (q) as in a EKF setting.
  • Transform noise: These parameters give the noise (or uncertainty) in the transformations. Each noise parameter is accompanied by a boolean that makes the transform fixed (True) or part of the state (False). For example position_pose_sensor/pose_fixed_p_ic is the boolean corresponding to position_pose_sensor/pose_noise_p_ic. For a complete list please refer to the sample parameter file. Generally, one should keep internal transforms (i.e. between IMU's) fixed since they can not change during flight and can be estimated precisely a priori. On the other hand, it usually makes sense to add some noise to transforms between different external frames (i.e. GPS and ROVIO) since this can change and usually is not precisely known a priori. This noise however should never be chosen larger than the noise of the sensor.
  • handlertype/use_stable_initialization: This parameter defines whether the simple initialization based on a single measurement (False) or the dynamic initialization based on multiple measurements (True) should be used. When set to False, the drone has to be aligned with the GPS frame [i.e. facing east?]. Otherwise, this should be True. If True, it is important that after initialization the system follows some movement to be able to estimate a stable transform.