mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
ekf_att_pos_estimator: fixed files names and perf counters names
This commit is contained in:
parent
a72015c260
commit
f52edc4cde
@ -32,7 +32,7 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file fw_att_pos_estimator_main.cpp
|
||||
* @file ekf_att_pos_estimator_main.cpp
|
||||
* Implementation of the attitude and position estimator.
|
||||
*
|
||||
* @author Paul Riseborough <p_riseborough@live.com.au>
|
||||
@ -336,13 +336,13 @@ FixedwingEstimator::FixedwingEstimator() :
|
||||
_baro_gps_offset(0.0f),
|
||||
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_COUNT, "fw_att_pos_estimator")),
|
||||
_perf_gyro(perf_alloc(PC_COUNT, "fw_ekf_gyro_upd")),
|
||||
_perf_accel(perf_alloc(PC_COUNT, "fw_ekf_accel_upd")),
|
||||
_perf_mag(perf_alloc(PC_COUNT, "fw_ekf_mag_upd")),
|
||||
_perf_gps(perf_alloc(PC_COUNT, "fw_ekf_gps_upd")),
|
||||
_perf_baro(perf_alloc(PC_COUNT, "fw_ekf_baro_upd")),
|
||||
_perf_airspeed(perf_alloc(PC_COUNT, "fw_ekf_aspd_upd")),
|
||||
_loop_perf(perf_alloc(PC_COUNT, "ekf_att_pos_estimator")),
|
||||
_perf_gyro(perf_alloc(PC_COUNT, "ekf_att_pos_gyro_upd")),
|
||||
_perf_accel(perf_alloc(PC_COUNT, "ekf_att_pos_accel_upd")),
|
||||
_perf_mag(perf_alloc(PC_COUNT, "ekf_att_pos_mag_upd")),
|
||||
_perf_gps(perf_alloc(PC_COUNT, "ekf_att_pos_gps_upd")),
|
||||
_perf_baro(perf_alloc(PC_COUNT, "ekf_att_pos_baro_upd")),
|
||||
_perf_airspeed(perf_alloc(PC_COUNT, "ekf_att_pos_aspd_upd")),
|
||||
|
||||
/* states */
|
||||
_initialized(false),
|
||||
@ -32,7 +32,7 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file fw_att_pos_estimator_params.c
|
||||
* @file ekf_att_pos_estimator_params.c
|
||||
*
|
||||
* Parameters defined by the attitude and position estimator task
|
||||
*
|
||||
Loading…
x
Reference in New Issue
Block a user