mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Renamed FW filter to EKF to express its generic properties, switched multicopters over to this filter for first tests.
This commit is contained in:
parent
edd16afead
commit
7b61c927f0
@ -6,7 +6,7 @@
|
||||
#
|
||||
# Start the attitude and position estimator
|
||||
#
|
||||
fw_att_pos_estimator start
|
||||
ekf_att_pos_estimator start
|
||||
|
||||
#
|
||||
# Start attitude controller
|
||||
|
||||
@ -5,7 +5,8 @@
|
||||
#
|
||||
|
||||
attitude_estimator_ekf start
|
||||
position_estimator_inav start
|
||||
ekf_att_pos_estimator start
|
||||
#position_estimator_inav start
|
||||
|
||||
mc_att_control start
|
||||
mc_pos_control start
|
||||
|
||||
@ -70,7 +70,7 @@ MODULES += modules/gpio_led
|
||||
# Estimation modules (EKF/ SO3 / other filters)
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/fw_att_pos_estimator
|
||||
MODULES += modules/ekf_att_pos_estimator
|
||||
MODULES += modules/position_estimator_inav
|
||||
#MODULES += examples/flow_position_estimator
|
||||
|
||||
|
||||
@ -79,7 +79,7 @@ MODULES += modules/gpio_led
|
||||
#
|
||||
MODULES += modules/attitude_estimator_ekf
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += modules/fw_att_pos_estimator
|
||||
MODULES += modules/ekf_att_pos_estimator
|
||||
MODULES += modules/position_estimator_inav
|
||||
MODULES += examples/flow_position_estimator
|
||||
|
||||
|
||||
@ -90,7 +90,7 @@
|
||||
*
|
||||
* @ingroup apps
|
||||
*/
|
||||
extern "C" __EXPORT int fw_att_pos_estimator_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int ekf_att_pos_estimator_main(int argc, char *argv[]);
|
||||
|
||||
__EXPORT uint32_t millis();
|
||||
|
||||
@ -1255,10 +1255,10 @@ int FixedwingEstimator::trip_nan() {
|
||||
return ret;
|
||||
}
|
||||
|
||||
int fw_att_pos_estimator_main(int argc, char *argv[])
|
||||
int ekf_att_pos_estimator_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
errx(1, "usage: fw_att_pos_estimator {start|stop|status}");
|
||||
errx(1, "usage: ekf_att_pos_estimator {start|stop|status}");
|
||||
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
|
||||
@ -35,7 +35,7 @@
|
||||
# Main Attitude and Position Estimator for Fixed Wing Aircraft
|
||||
#
|
||||
|
||||
MODULE_COMMAND = fw_att_pos_estimator
|
||||
MODULE_COMMAND = ekf_att_pos_estimator
|
||||
|
||||
SRCS = fw_att_pos_estimator_main.cpp \
|
||||
fw_att_pos_estimator_params.c \
|
||||
Loading…
x
Reference in New Issue
Block a user