aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.c16
-rw-r--r--src/modules/multirotor_att_control/multirotor_att_control_main.c83
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c243
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c29
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.h18
-rw-r--r--src/modules/position_estimator_inav/kalman_filter_inertial.c27
-rw-r--r--src/modules/position_estimator_inav/kalman_filter_inertial.h12
-rw-r--r--src/modules/position_estimator_inav/module.mk41
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c441
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c97
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h77
11 files changed, 954 insertions, 130 deletions
diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c
index aab8f3e04..bb8580328 100644
--- a/src/modules/commander/commander.c
+++ b/src/modules/commander/commander.c
@@ -1389,6 +1389,7 @@ int commander_thread_main(int argc, char *argv[])
uint64_t start_time = hrt_absolute_time();
uint64_t failsave_ll_start_time = 0;
+ enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode;
bool state_changed = true;
bool param_init_forced = true;
@@ -1828,8 +1829,9 @@ int commander_thread_main(int argc, char *argv[])
} else if (sp_man.manual_sas_switch < -STICK_ON_OFF_LIMIT) {
- /* bottom stick position, set altitude hold */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
+ /* bottom stick position, set default */
+ /* this MUST be mapped to extremal position to switch easy in case of emergency */
+ current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
} else if (sp_man.manual_sas_switch > STICK_ON_OFF_LIMIT) {
@@ -1837,8 +1839,14 @@ int commander_thread_main(int argc, char *argv[])
current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_SIMPLE;
} else {
- /* center stick position, set default */
- current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS;
+ /* center stick position, set altitude hold */
+ current_status.manual_sas_mode = VEHICLE_MANUAL_SAS_MODE_ALTITUDE;
+ }
+
+ if (current_status.manual_sas_mode != manual_sas_mode) {
+ /* publish SAS mode changes immediately */
+ manual_sas_mode = current_status.manual_sas_mode;
+ state_changed = true;
}
/*
diff --git a/src/modules/multirotor_att_control/multirotor_att_control_main.c b/src/modules/multirotor_att_control/multirotor_att_control_main.c
index d94c0a69c..258299828 100644
--- a/src/modules/multirotor_att_control/multirotor_att_control_main.c
+++ b/src/modules/multirotor_att_control/multirotor_att_control_main.c
@@ -241,13 +241,18 @@ mc_thread_main(int argc, char *argv[])
} else if (state.flag_control_manual_enabled) {
-
+ /* direct manual input */
if (state.flag_control_attitude_enabled) {
+ /* Control attitude, update attitude setpoint depending on SAS mode:
+ * VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS: roll, pitch, yaw, thrust
+ * VEHICLE_MANUAL_SAS_MODE_ALTITUDE: roll, pitch, yaw
+ * VEHICLE_MANUAL_SAS_MODE_SIMPLE: yaw
+ * */
/* initialize to current yaw if switching to manual or att control */
if (state.flag_control_attitude_enabled != flag_control_attitude_enabled ||
- state.flag_control_manual_enabled != flag_control_manual_enabled ||
- state.flag_system_armed != flag_system_armed) {
+ state.flag_control_manual_enabled != flag_control_manual_enabled ||
+ state.flag_system_armed != flag_system_armed) {
att_sp.yaw_body = att.yaw;
}
@@ -255,24 +260,30 @@ mc_thread_main(int argc, char *argv[])
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
if (state.rc_signal_lost) {
- /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
- param_get(failsafe_throttle_handle, &failsafe_throttle);
- att_sp.roll_body = 0.0f;
- att_sp.pitch_body = 0.0f;
+ if (state.manual_sas_mode != VEHICLE_MANUAL_SAS_MODE_SIMPLE) {
+ /* Don't reset attitude setpoint in SIMPLE SAS mode, it's handled by position controller. */
+ att_sp.roll_body = 0.0f;
+ att_sp.pitch_body = 0.0f;
- /*
- * Only go to failsafe throttle if last known throttle was
- * high enough to create some lift to make hovering state likely.
- *
- * This is to prevent that someone landing, but not disarming his
- * multicopter (throttle = 0) does not make it jump up in the air
- * if shutting down his remote.
- */
- if (isfinite(manual.throttle) && manual.throttle > 0.2f) {
- att_sp.thrust = failsafe_throttle;
+ if (state.manual_sas_mode != VEHICLE_MANUAL_SAS_MODE_ALTITUDE) {
+ /* Don't touch throttle in modes with altitude hold, it's handled by position controller.
+ *
+ * Only go to failsafe throttle if last known throttle was
+ * high enough to create some lift to make hovering state likely.
+ *
+ * This is to prevent that someone landing, but not disarming his
+ * multicopter (throttle = 0) does not make it jump up in the air
+ * if shutting down his remote.
+ */
+ if (isfinite(manual.throttle) && manual.throttle > 0.2f) {
+ /* the failsafe throttle is stored as a parameter, as it depends on the copter and the payload */
+ param_get(failsafe_throttle_handle, &failsafe_throttle);
+ att_sp.thrust = failsafe_throttle;
- } else {
- att_sp.thrust = 0.0f;
+ } else {
+ att_sp.thrust = 0.0f;
+ }
+ }
}
/* keep current yaw, do not attempt to go to north orientation,
@@ -287,17 +298,15 @@ mc_thread_main(int argc, char *argv[])
} else {
rc_loss_first_time = true;
- att_sp.roll_body = manual.roll;
- att_sp.pitch_body = manual.pitch;
-
- /* set attitude if arming */
+ /* control yaw in all SAS modes */
+ /* set yaw if arming */
if (!flag_control_attitude_enabled && state.flag_system_armed) {
att_sp.yaw_body = att.yaw;
}
/* act if stabilization is active or if the (nonsense) direct pass through mode is set */
if (state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS ||
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
+ state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
if (state.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE) {
rates_sp.yaw = manual.yaw;
@@ -313,7 +322,9 @@ mc_thread_main(int argc, char *argv[])
*/
/* only move setpoint if manual input is != 0 */
- if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && manual.throttle > 0.3f) {
+ if ((manual.yaw < -0.01f || 0.01f < manual.yaw) && (
+ state.manual_sas_mode != VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS ||
+ manual.throttle > 0.3f)) {
rates_sp.yaw = manual.yaw;
control_yaw_position = false;
first_time_after_yaw_speed_control = true;
@@ -329,13 +340,19 @@ mc_thread_main(int argc, char *argv[])
}
}
- att_sp.thrust = manual.throttle;
+ if (state.manual_sas_mode != VEHICLE_MANUAL_SAS_MODE_SIMPLE) {
+ /* don't update attitude setpoint in SIMPLE SAS mode */
+ att_sp.roll_body = manual.roll;
+ att_sp.pitch_body = manual.pitch;
+ if (state.manual_sas_mode != VEHICLE_MANUAL_SAS_MODE_ALTITUDE) {
+ /* don't set throttle in alt hold modes */
+ att_sp.thrust = manual.throttle;
+ }
+ }
+
att_sp.timestamp = hrt_absolute_time();
}
- /* STEP 2: publish the controller output */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
-
if (motor_test_mode) {
printf("testmode");
att_sp.roll_body = 0.0f;
@@ -343,14 +360,15 @@ mc_thread_main(int argc, char *argv[])
att_sp.yaw_body = 0.0f;
att_sp.thrust = 0.1f;
att_sp.timestamp = hrt_absolute_time();
- /* STEP 2: publish the result to the vehicle actuators */
- orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
}
+ /* STEP 2: publish the controller output */
+ orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
+
} else {
/* manual rate inputs, from RC control or joystick */
if (state.flag_control_rates_enabled &&
- state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
+ state.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_RATES) {
rates_sp.roll = manual.roll;
rates_sp.pitch = manual.pitch;
@@ -359,7 +377,6 @@ mc_thread_main(int argc, char *argv[])
rates_sp.timestamp = hrt_absolute_time();
}
}
-
}
/** STEP 3: Identify the controller setup to run and set up the inputs correctly */
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 7b8d83aa8..6fe129d84 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -1,7 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,7 +35,7 @@
/**
* @file multirotor_pos_control.c
*
- * Skeleton for multirotor position controller
+ * Multirotor position controller
*/
#include <nuttx/config.h>
@@ -52,13 +52,16 @@
#include <sys/prctl.h>
#include <drivers/drv_hrt.h>
#include <uORB/uORB.h>
+#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_status.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_attitude_setpoint.h>
+#include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_local_position_setpoint.h>
#include <uORB/topics/vehicle_vicon_position.h>
#include <systemlib/systemlib.h>
+#include <mavlink/mavlink_log.h>
#include "multirotor_pos_control_params.h"
@@ -79,9 +82,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]);
*/
static void usage(const char *reason);
-static void
-usage(const char *reason)
-{
+static void usage(const char *reason) {
if (reason)
fprintf(stderr, "%s\n", reason);
fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
@@ -96,21 +97,20 @@ usage(const char *reason)
* The actual stack size should be set in the call
* to task_spawn().
*/
-int multirotor_pos_control_main(int argc, char *argv[])
-{
+int multirotor_pos_control_main(int argc, char *argv[]) {
if (argc < 1)
usage("missing command");
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("multirotor pos control already running\n");
+ printf("multirotor_pos_control already running\n");
/* this is not an error */
exit(0);
}
thread_should_exit = false;
- deamon_task = task_spawn("multirotor pos control",
+ deamon_task = task_spawn("multirotor_pos_control",
SCHED_DEFAULT,
SCHED_PRIORITY_MAX - 60,
4096,
@@ -126,9 +126,9 @@ int multirotor_pos_control_main(int argc, char *argv[])
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tmultirotor pos control app is running\n");
+ printf("\tmultirotor_pos_control app is running\n");
} else {
- printf("\tmultirotor pos control app not started\n");
+ printf("\tmultirotor_pos_control app not started\n");
}
exit(0);
}
@@ -137,98 +137,185 @@ int multirotor_pos_control_main(int argc, char *argv[])
exit(1);
}
-static int
-multirotor_pos_control_thread_main(int argc, char *argv[])
-{
+static int multirotor_pos_control_thread_main(int argc, char *argv[]) {
/* welcome user */
- printf("[multirotor pos control] Control started, taking over position control\n");
+ printf("[multirotor_pos_control] started\n");
+ static int mavlink_fd;
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(mavlink_fd, "[multirotor_pos_control] started");
/* structures */
- struct vehicle_status_s state;
+ struct vehicle_status_s status;
+ memset(&status, 0, sizeof(status));
struct vehicle_attitude_s att;
- //struct vehicle_global_position_setpoint_s global_pos_sp;
- struct vehicle_local_position_setpoint_s local_pos_sp;
- struct vehicle_vicon_position_s local_pos;
- struct manual_control_setpoint_s manual;
+ memset(&att, 0, sizeof(att));
struct vehicle_attitude_setpoint_s att_sp;
+ memset(&att_sp, 0, sizeof(att_sp));
+ struct manual_control_setpoint_s manual;
+ memset(&manual, 0, sizeof(manual));
+ struct vehicle_local_position_s local_pos;
+ memset(&local_pos, 0, sizeof(local_pos));
+ struct vehicle_local_position_setpoint_s local_pos_sp;
+ memset(&local_pos_sp, 0, sizeof(local_pos_sp));
/* subscribe to attitude, motor setpoints and system state */
- int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int param_sub = orb_subscribe(ORB_ID(parameter_update));
int state_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
int manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
- int local_pos_sub = orb_subscribe(ORB_ID(vehicle_vicon_position));
- //int global_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
int local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint));
+ int local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
- /* publish attitude setpoint */
+ /* publish setpoint */
+ orb_advert_t local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &local_pos_sp);
orb_advert_t att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
+ bool reset_sp_alt = true;
+ bool reset_sp_pos = true;
+ hrt_abstime t_prev = 0;
+ float alt_integral = 0.0f;
+ float alt_ctl_dz = 0.2f;
+
thread_running = true;
- int loopcounter = 0;
-
- struct multirotor_position_control_params p;
- struct multirotor_position_control_param_handles h;
- parameters_init(&h);
- parameters_update(&h, &p);
-
-
- while (1) {
- /* get a local copy of the vehicle state */
- orb_copy(ORB_ID(vehicle_status), state_sub, &state);
- /* get a local copy of manual setpoint */
- orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
- /* get a local copy of attitude */
- orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
- /* get a local copy of local position */
- orb_copy(ORB_ID(vehicle_vicon_position), local_pos_sub, &local_pos);
- /* get a local copy of local position setpoint */
- orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp);
-
- if (loopcounter == 500) {
- parameters_update(&h, &p);
- loopcounter = 0;
+ struct multirotor_position_control_params params;
+ struct multirotor_position_control_param_handles params_h;
+ parameters_init(&params_h);
+ parameters_update(&params_h, &params);
+
+ int paramcheck_counter = 0;
+
+ while (!thread_should_exit) {
+ orb_copy(ORB_ID(vehicle_status), state_sub, &status);
+
+ /* check parameters at 1 Hz*/
+ paramcheck_counter++;
+ if (paramcheck_counter == 50) {
+ bool param_updated;
+ orb_check(param_sub, &param_updated);
+ if (param_updated) {
+ parameters_update(&params_h, &params);
+ }
+ paramcheck_counter = 0;
}
- // if (state.state_machine == SYSTEM_STATE_AUTO) {
-
- // XXX IMPLEMENT POSITION CONTROL HERE
-
- float dT = 1.0f / 50.0f;
-
- float x_setpoint = 0.0f;
-
- // XXX enable switching between Vicon and local position estimate
- /* local pos is the Vicon position */
-
- // XXX just an example, lacks rotation around world-body transformation
- att_sp.pitch_body = (local_pos.x - x_setpoint) * p.p;
- att_sp.roll_body = 0.0f;
- att_sp.yaw_body = 0.0f;
- att_sp.thrust = 0.3f;
+ /* Check if controller should act */
+ bool act = status.flag_system_armed && (
+ /* SAS modes */
+ (
+ status.flag_control_manual_enabled &&
+ status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS && (
+ status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_ALTITUDE ||
+ status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_SIMPLE
+ )
+ ) ||
+ /* AUTO mode */
+ status.state_machine == SYSTEM_STATE_AUTO
+ );
+
+ hrt_abstime t = hrt_absolute_time();
+ float dt;
+ if (t_prev != 0) {
+ dt = (t - t_prev) * 0.000001f;
+ } else {
+ dt = 0.0f;
+ }
+ t_prev = t;
+ if (act) {
+ orb_copy(ORB_ID(manual_control_setpoint), manual_sub, &manual);
+ orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
+ orb_copy(ORB_ID(vehicle_attitude_setpoint), att_sp_sub, &att_sp);
+ orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
+ if (status.state_machine == SYSTEM_STATE_AUTO) {
+ orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp);
+ }
+
+ if (reset_sp_alt) {
+ reset_sp_alt = false;
+ local_pos_sp.z = local_pos.z;
+ alt_integral = manual.throttle;
+ char str[80];
+ sprintf(str, "reset alt setpoint: z = %.2f, throttle = %.2f", local_pos_sp.z, manual.throttle);
+ mavlink_log_info(mavlink_fd, str);
+ }
+
+ if (status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_SIMPLE && reset_sp_pos) {
+ reset_sp_pos = false;
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ char str[80];
+ sprintf(str, "reset pos setpoint: x = %.2f, y = %.2f", local_pos_sp.x, local_pos_sp.y);
+ mavlink_log_info(mavlink_fd, str);
+ }
+
+ float err_linear_limit = params.alt_d / params.alt_p * params.alt_rate_max;
+
+ if (status.flag_control_manual_enabled) {
+ /* move altitude setpoint with manual controls */
+ float alt_ctl = manual.throttle - 0.5f;
+ if (fabs(alt_ctl) < alt_ctl_dz) {
+ alt_ctl = 0.0f;
+ } else {
+ if (alt_ctl > 0.0f)
+ alt_ctl = (alt_ctl - alt_ctl_dz) / (0.5f - alt_ctl_dz);
+ else
+ alt_ctl = (alt_ctl + alt_ctl_dz) / (0.5f - alt_ctl_dz);
+ local_pos_sp.z -= alt_ctl * params.alt_rate_max * dt;
+ if (local_pos_sp.z > local_pos.z + err_linear_limit)
+ local_pos_sp.z = local_pos.z + err_linear_limit;
+ else if (local_pos_sp.z < local_pos.z - err_linear_limit)
+ local_pos_sp.z = local_pos.z - err_linear_limit;
+ }
+
+ if (status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_SIMPLE) {
+ // TODO move position setpoint with manual controls
+ }
+ }
+
+ /* PID for altitude */
+ float alt_err = local_pos.z - local_pos_sp.z;
+ /* don't accelerate more than ALT_RATE_MAX, limit error to corresponding value */
+ if (alt_err > err_linear_limit) {
+ alt_err = err_linear_limit;
+ } else if (alt_err < -err_linear_limit) {
+ alt_err = -err_linear_limit;
+ }
+ /* P and D components */
+ float thrust_ctl_pd = alt_err * params.alt_p + local_pos.vz * params.alt_d;
+ /* add I component */
+ float thrust_ctl = thrust_ctl_pd + alt_integral;
+ alt_integral += thrust_ctl_pd / params.alt_p * params.alt_i * dt;
+ if (thrust_ctl < params.thr_min) {
+ thrust_ctl = params.thr_min;
+ } else if (thrust_ctl > params.thr_max) {
+ thrust_ctl = params.thr_max;
+ }
+ if (status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_SIMPLE || status.state_machine == SYSTEM_STATE_AUTO) {
+ // TODO add position controller
+ } else {
+ reset_sp_pos = true;
+ }
+ att_sp.thrust = thrust_ctl;
att_sp.timestamp = hrt_absolute_time();
-
+ if (status.flag_control_manual_enabled) {
+ /* publish local position setpoint in manual mode */
+ orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
+ }
/* publish new attitude setpoint */
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
- // } else if (state.state_machine == SYSTEM_STATE_STABILIZED) {
- /* set setpoint to current position */
- // XXX select pos reset channel on remote
- /* reset setpoint to current position (position hold) */
- // if (1 == 2) {
- // local_pos_sp.x = local_pos.x;
- // local_pos_sp.y = local_pos.y;
- // local_pos_sp.z = local_pos.z;
- // local_pos_sp.yaw = att.yaw;
- // }
- // }
+ } else {
+ reset_sp_alt = true;
+ reset_sp_pos = true;
+ }
/* run at approximately 50 Hz */
usleep(20000);
- loopcounter++;
}
- printf("[multirotor pos control] ending now...\n");
+ printf("[multirotor_pos_control] exiting\n");
+ mavlink_log_info(mavlink_fd, "[multirotor_pos_control] exiting");
thread_running = false;
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
index 6b73dc405..90dd820f4 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
@@ -34,29 +34,40 @@
****************************************************************************/
/*
- * @file multirotor_position_control_params.c
+ * @file multirotor_pos_control_params.c
*
- * Parameters for EKF filter
+ * Parameters for multirotor_pos_control
*/
#include "multirotor_pos_control_params.h"
-/* Extended Kalman Filter covariances */
-
/* controller parameters */
-PARAM_DEFINE_FLOAT(MC_POS_P, 0.2f);
+PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.3f);
+PARAM_DEFINE_FLOAT(MPC_THR_MAX, 0.7f);
+PARAM_DEFINE_FLOAT(MPC_ALT_P, 0.1f);
+PARAM_DEFINE_FLOAT(MPC_ALT_I, 0.01f);
+PARAM_DEFINE_FLOAT(MPC_ALT_D, 0.2f);
+PARAM_DEFINE_FLOAT(MPC_ALT_RATE_MAX, 3.0f);
int parameters_init(struct multirotor_position_control_param_handles *h)
{
+ h->thr_min = param_find("MPC_THR_MIN");
+ h->thr_max = param_find("MPC_THR_MAX");
/* PID parameters */
- h->p = param_find("MC_POS_P");
-
+ h->alt_p = param_find("MPC_ALT_P");
+ h->alt_i = param_find("MPC_ALT_I");
+ h->alt_d = param_find("MPC_ALT_D");
+ h->alt_rate_max = param_find("MPC_ALT_RATE_MAX");
return OK;
}
int parameters_update(const struct multirotor_position_control_param_handles *h, struct multirotor_position_control_params *p)
{
- param_get(h->p, &(p->p));
-
+ param_get(h->thr_min, &(p->thr_min));
+ param_get(h->thr_max, &(p->thr_max));
+ param_get(h->alt_p, &(p->alt_p));
+ param_get(h->alt_i, &(p->alt_i));
+ param_get(h->alt_d, &(p->alt_d));
+ param_get(h->alt_rate_max, &(p->alt_rate_max));
return OK;
}
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control_params.h b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
index 274f6c22a..849055cd1 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
@@ -42,15 +42,21 @@
#include <systemlib/param/param.h>
struct multirotor_position_control_params {
- float p;
- float i;
- float d;
+ float thr_min;
+ float thr_max;
+ float alt_p;
+ float alt_i;
+ float alt_d;
+ float alt_rate_max;
};
struct multirotor_position_control_param_handles {
- param_t p;
- param_t i;
- param_t d;
+ param_t thr_min;
+ param_t thr_max;
+ param_t alt_p;
+ param_t alt_i;
+ param_t alt_d;
+ param_t alt_rate_max;
};
/**
diff --git a/src/modules/position_estimator_inav/kalman_filter_inertial.c b/src/modules/position_estimator_inav/kalman_filter_inertial.c
new file mode 100644
index 000000000..64031ee7b
--- /dev/null
+++ b/src/modules/position_estimator_inav/kalman_filter_inertial.c
@@ -0,0 +1,27 @@
+/*
+ * kalman_filter_inertial.c
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include "kalman_filter_inertial.h"
+
+void kalman_filter_inertial_predict(float dt, float x[3]) {
+ x[0] += x[1] * dt + x[2] * dt * dt / 2.0f;
+ x[1] += x[2] * dt;
+}
+
+void kalman_filter_inertial_update(float x[3], float z[2], float k[3][2], bool use[2]) {
+ float y[2];
+ // y = z - H x
+ y[0] = z[0] - x[0];
+ y[1] = z[1] - x[2];
+ // x = x + K * y
+ for (int i = 0; i < 3; i++) { // Row
+ for (int j = 0; j < 2; j++) { // Column
+ if (use[j])
+ x[i] += k[i][j] * y[j];
+ }
+ }
+}
diff --git a/src/modules/position_estimator_inav/kalman_filter_inertial.h b/src/modules/position_estimator_inav/kalman_filter_inertial.h
new file mode 100644
index 000000000..3e5134c33
--- /dev/null
+++ b/src/modules/position_estimator_inav/kalman_filter_inertial.h
@@ -0,0 +1,12 @@
+/*
+ * kalman_filter_inertial.h
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include <stdbool.h>
+
+void kalman_filter_inertial_predict(float dt, float x[3]);
+
+void kalman_filter_inertial_update(float x[3], float z[2], float k[3][2], bool use[2]);
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
new file mode 100644
index 000000000..8ac701c53
--- /dev/null
+++ b/src/modules/position_estimator_inav/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Makefile to build position_estimator_inav
+#
+
+MODULE_COMMAND = position_estimator_inav
+SRCS = position_estimator_inav_main.c \
+ position_estimator_inav_params.c \
+ kalman_filter_inertial.c
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
new file mode 100644
index 000000000..2b485f895
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -0,0 +1,441 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file position_estimator_inav_main.c
+ * Model-identification based position estimator for multirotors
+ */
+
+#include <unistd.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <float.h>
+#include <string.h>
+#include <nuttx/config.h>
+#include <nuttx/sched.h>
+#include <sys/prctl.h>
+#include <termios.h>
+#include <errno.h>
+#include <limits.h>
+#include <math.h>
+#include <uORB/uORB.h>
+#include <uORB/topics/sensor_combined.h>
+#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_attitude.h>
+#include <uORB/topics/vehicle_status.h>
+#include <uORB/topics/vehicle_local_position.h>
+#include <uORB/topics/vehicle_gps_position.h>
+#include <mavlink/mavlink_log.h>
+#include <poll.h>
+#include <systemlib/geo/geo.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/conversions.h>
+#include <drivers/drv_hrt.h>
+
+#include "position_estimator_inav_params.h"
+#include "kalman_filter_inertial.h"
+
+static bool thread_should_exit = false; /**< Deamon exit flag */
+static bool thread_running = false; /**< Deamon status flag */
+static int position_estimator_inav_task; /**< Handle of deamon task / thread */
+static bool verbose_mode = false;
+
+__EXPORT int position_estimator_inav_main(int argc, char *argv[]);
+
+int position_estimator_inav_thread_main(int argc, char *argv[]);
+
+static void usage(const char *reason);
+
+/**
+ * Print the correct usage.
+ */
+static void usage(const char *reason) {
+ if (reason)
+ fprintf(stderr, "%s\n", reason);
+ fprintf(stderr,
+ "usage: position_estimator_inav {start|stop|status} [-v]\n\n");
+ exit(1);
+ }
+
+/**
+ * The position_estimator_inav_thread only briefly exists to start
+ * the background job. The stack size assigned in the
+ * Makefile does only apply to this management task.
+ *
+ * The actual stack size should be set in the call
+ * to task_create().
+ */
+int position_estimator_inav_main(int argc, char *argv[]) {
+ if (argc < 1)
+ usage("missing command");
+
+ if (!strcmp(argv[1], "start")) {
+ if (thread_running) {
+ printf("position_estimator_inav already running\n");
+ /* this is not an error */
+ exit(0);
+ }
+ if (argc > 1)
+ if (!strcmp(argv[2], "-v"))
+ verbose_mode = true;
+
+ thread_should_exit = false;
+ position_estimator_inav_task = task_spawn("position_estimator_inav",
+ SCHED_RR, SCHED_PRIORITY_MAX - 5, 4096,
+ position_estimator_inav_thread_main,
+ (argv) ? (const char **) &argv[2] : (const char **) NULL );
+ exit(0);
+ }
+ if (!strcmp(argv[1], "stop")) {
+ thread_should_exit = true;
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (thread_running) {
+ printf("\tposition_estimator_inav is running\n");
+ } else {
+ printf("\tposition_estimator_inav not started\n");
+ }
+ exit(0);
+ }
+
+ usage("unrecognized command");
+ exit(1);
+}
+
+/****************************************************************************
+ * main
+ ****************************************************************************/
+int position_estimator_inav_thread_main(int argc, char *argv[]) {
+ /* welcome user */
+ printf("[position_estimator_inav] started\n");
+ static int mavlink_fd;
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(mavlink_fd, "[position_estimator_inav] started");
+
+ /* initialize values */
+ float x_est[3] = { 0.0f, 0.0f, 0.0f };
+ float y_est[3] = { 0.0f, 0.0f, 0.0f };
+ float z_est[3] = { 0.0f, 0.0f, 0.0f };
+
+ int baro_loop_cnt = 0;
+ int baro_loop_end = 70; /* measurement for 1 second */
+ float baro_alt0 = 0.0f; /* to determine while start up */
+
+ static double lat_current = 0.0; //[°]] --> 47.0
+ static double lon_current = 0.0; //[°]] -->8.5
+ static double alt_current = 0.0; //[m] above MSL
+
+ /* declare and safely initialize all structs */
+ struct vehicle_status_s vehicle_status;
+ memset(&vehicle_status, 0, sizeof(vehicle_status));
+ /* make sure that baroINITdone = false */
+ struct sensor_combined_s sensor;
+ memset(&sensor, 0, sizeof(sensor));
+ struct vehicle_gps_position_s gps;
+ memset(&gps, 0, sizeof(gps));
+ struct vehicle_attitude_s att;
+ memset(&att, 0, sizeof(att));
+ struct vehicle_local_position_s pos;
+ memset(&pos, 0, sizeof(pos));
+
+ /* subscribe */
+ int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
+ int vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status));
+ int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
+ int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
+ int vehicle_gps_position_sub = orb_subscribe(ORB_ID(vehicle_gps_position));
+
+ /* advertise */
+ orb_advert_t vehicle_local_position_pub = orb_advertise(ORB_ID(vehicle_local_position), &pos);
+
+ struct position_estimator_inav_params params;
+ struct position_estimator_inav_param_handles pos_inav_param_handles;
+ /* initialize parameter handles */
+ parameters_init(&pos_inav_param_handles);
+
+ bool local_flag_baroINITdone = false; /* in any case disable baroINITdone */
+ /* FIRST PARAMETER READ at START UP*/
+ struct parameter_update_s param_update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &param_update); /* read from param to clear updated flag */
+ /* FIRST PARAMETER UPDATE */
+ parameters_update(&pos_inav_param_handles, &params);
+ /* END FIRST PARAMETER UPDATE */
+
+ /* wait until gps signal turns valid, only then can we initialize the projection */
+ if (params.use_gps) {
+ struct pollfd fds_init[1] = {
+ { .fd = vehicle_gps_position_sub, .events = POLLIN }
+ };
+
+ while (gps.fix_type < 3) {
+ if (poll(fds_init, 1, 5000)) { /* poll only two first subscriptions */
+ if (fds_init[0].revents & POLLIN) {
+ /* Wait for the GPS update to propagate (we have some time) */
+ usleep(5000);
+ orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
+ }
+ }
+ static int printcounter = 0;
+ if (printcounter == 100) {
+ printcounter = 0;
+ printf("[position_estimator_inav] wait for GPS fix type 3\n");
+ }
+ printcounter++;
+ }
+
+ /* get GPS position for first initialization */
+ orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
+ lat_current = ((double) (gps.lat)) * 1e-7;
+ lon_current = ((double) (gps.lon)) * 1e-7;
+ alt_current = gps.alt * 1e-3;
+
+ pos.home_lat = lat_current * 1e7;
+ pos.home_lon = lon_current * 1e7;
+ pos.home_timestamp = hrt_absolute_time();
+
+ /* initialize coordinates */
+ map_projection_init(lat_current, lon_current);
+ /* publish global position messages only after first GPS message */
+ }
+ printf(
+ "[position_estimator_inav] initialized projection with: lat: %.10f, lon:%.10f\n",
+ lat_current, lon_current);
+
+ hrt_abstime last_time = 0;
+ thread_running = true;
+ uint32_t accelerometer_counter = 0;
+ uint32_t baro_counter = 0;
+ uint16_t accelerometer_updates = 0;
+ uint16_t baro_updates = 0;
+ uint16_t gps_updates = 0;
+ uint16_t attitude_updates = 0;
+ hrt_abstime updates_counter_start = hrt_absolute_time();
+ uint32_t updates_counter_len = 1000000;
+ hrt_abstime pub_last = hrt_absolute_time();
+ uint32_t pub_interval = 4000; // limit publish rate to 250 Hz
+
+ /* main loop */
+ struct pollfd fds[5] = {
+ { .fd = parameter_update_sub, .events = POLLIN },
+ { .fd = vehicle_status_sub, .events = POLLIN },
+ { .fd = vehicle_attitude_sub, .events = POLLIN },
+ { .fd = sensor_combined_sub, .events = POLLIN },
+ { .fd = vehicle_gps_position_sub, .events = POLLIN }
+ };
+ printf("[position_estimator_inav] main loop started\n");
+ while (!thread_should_exit) {
+ bool accelerometer_updated = false;
+ bool baro_updated = false;
+ bool gps_updated = false;
+ float local_pos_gps[3] = { 0.0f, 0.0f, 0.0f };
+
+ int ret = poll(fds, params.use_gps ? 5 : 4, 10); // wait maximal this 10 ms = 100 Hz minimum rate
+ if (ret < 0) {
+ /* poll error */
+ printf("[position_estimator_inav] subscriptions poll error\n");
+ thread_should_exit = true;
+ continue;
+ } else if (ret > 0) {
+ /* parameter update */
+ if (fds[0].revents & POLLIN) {
+ /* read from param to clear updated flag */
+ struct parameter_update_s update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub,
+ &update);
+ /* update parameters */
+ parameters_update(&pos_inav_param_handles, &params);
+ }
+ /* vehicle status */
+ if (fds[1].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_status), vehicle_status_sub,
+ &vehicle_status);
+ }
+ /* vehicle attitude */
+ if (fds[2].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+ attitude_updates++;
+ }
+ /* sensor combined */
+ if (fds[3].revents & POLLIN) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+ if (sensor.accelerometer_counter > accelerometer_counter) {
+ accelerometer_updated = true;
+ accelerometer_counter = sensor.accelerometer_counter;
+ accelerometer_updates++;
+ }
+ if (sensor.baro_counter > baro_counter) {
+ baro_updated = true;
+ baro_counter = sensor.baro_counter;
+ baro_updates++;
+ }
+ // barometric pressure estimation at start up
+ if (!local_flag_baroINITdone && baro_updated) {
+ // mean calculation over several measurements
+ if (baro_loop_cnt < baro_loop_end) {
+ baro_alt0 += sensor.baro_alt_meter;
+ baro_loop_cnt++;
+ } else {
+ baro_alt0 /= (float) (baro_loop_cnt);
+ local_flag_baroINITdone = true;
+ char str[80];
+ sprintf(str,
+ "[position_estimator_inav] baro_alt0 = %.2f",
+ baro_alt0);
+ printf("%s\n", str);
+ mavlink_log_info(mavlink_fd, str);
+ }
+ }
+ }
+ if (params.use_gps) {
+ /* vehicle GPS position */
+ if (fds[4].revents & POLLIN) {
+ /* new GPS value */
+ orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
+ /* Project gps lat lon (Geographic coordinate system) to plane */
+ map_projection_project(((double) (gps.lat)) * 1e-7,
+ ((double) (gps.lon)) * 1e-7, &(local_pos_gps[0]),
+ &(local_pos_gps[1]));
+ local_pos_gps[2] = (float) (gps.alt * 1e-3);
+ gps_updated = true;
+ pos.valid = gps.fix_type >= 3;
+ gps_updates++;
+ }
+ } else {
+ pos.valid = true;
+ }
+
+ } /* end of poll return value check */
+
+ hrt_abstime t = hrt_absolute_time();
+ float dt = (t - last_time) / 1000000.0;
+ last_time = t;
+ if (att.R_valid) {
+ /* transform acceleration vector from UAV frame to NED frame */
+ float accel_NED[3];
+ for (int i = 0; i < 3; i++) {
+ accel_NED[i] = 0.0f;
+ for (int j = 0; j < 3; j++) {
+ accel_NED[i] += att.R[i][j] * sensor.accelerometer_m_s2[j];
+ }
+ }
+ accel_NED[2] += CONSTANTS_ONE_G;
+
+ /* kalman filter for altitude */
+ kalman_filter_inertial_predict(dt, z_est);
+ /* prepare vectors for kalman filter correction */
+ float z_meas[2]; // position, acceleration
+ bool use_z[2] = { false, false };
+ if (local_flag_baroINITdone && baro_updated) {
+ z_meas[0] = baro_alt0 - sensor.baro_alt_meter; // Z = -alt
+ use_z[0] = true;
+ }
+ if (accelerometer_updated) {
+ z_meas[1] = accel_NED[2];
+ use_z[1] = true;
+ }
+ if (use_z[0] || use_z[1]) {
+ /* correction */
+ kalman_filter_inertial_update(z_est, z_meas, params.k_alt, use_z);
+ }
+
+ if (params.use_gps) {
+ /* kalman filter for position */
+ kalman_filter_inertial_predict(dt, x_est);
+ kalman_filter_inertial_predict(dt, y_est);
+ /* prepare vectors for kalman filter correction */
+ float x_meas[2]; // position, acceleration
+ float y_meas[2]; // position, acceleration
+ bool use_xy[2] = { false, false };
+ if (gps_updated) {
+ x_meas[0] = local_pos_gps[0];
+ y_meas[0] = local_pos_gps[1];
+ use_xy[0] = true;
+ }
+ if (accelerometer_updated) {
+ x_meas[1] = accel_NED[0];
+ y_meas[1] = accel_NED[1];
+ use_xy[1] = true;
+ }
+ if (use_xy[0] || use_xy[1]) {
+ /* correction */
+ kalman_filter_inertial_update(x_est, x_meas, params.k_pos, use_xy);
+ kalman_filter_inertial_update(y_est, y_meas, params.k_pos, use_xy);
+ }
+ }
+ }
+ if (verbose_mode) {
+ /* print updates rate */
+ if (t - updates_counter_start > updates_counter_len) {
+ float updates_dt = (t - updates_counter_start) * 0.000001f;
+ printf(
+ "[position_estimator_inav] updates rate: accelerometer = %.1f/s, baro = %.1f/s, gps = %.1f/s, attitude = %.1f/s\n",
+ accelerometer_updates / updates_dt,
+ baro_updates / updates_dt,
+ gps_updates / updates_dt,
+ attitude_updates / updates_dt);
+ updates_counter_start = t;
+ accelerometer_updates = 0;
+ baro_updates = 0;
+ gps_updates = 0;
+ attitude_updates = 0;
+ }
+ }
+ if (t - pub_last > pub_interval) {
+ pub_last = t;
+ pos.x = x_est[0];
+ pos.vx = x_est[1];
+ pos.y = y_est[0];
+ pos.vy = y_est[1];
+ pos.z = z_est[0];
+ pos.vz = z_est[1];
+ pos.timestamp = hrt_absolute_time();
+ if ((isfinite(pos.x)) && (isfinite(pos.vx))
+ && (isfinite(pos.y))
+ && (isfinite(pos.vy))
+ && (isfinite(pos.z))
+ && (isfinite(pos.vz))) {
+ orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &pos);
+ }
+ }
+ }
+
+ printf("[position_estimator_inav] exiting.\n");
+ mavlink_log_info(mavlink_fd, "[position_estimator_inav] exiting");
+ thread_running = false;
+ return 0;
+}
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c
new file mode 100644
index 000000000..8466bcd0a
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file position_estimator_inav_params.c
+ *
+ * Parameters for position_estimator_inav
+ */
+
+#include "position_estimator_inav_params.h"
+
+PARAM_DEFINE_INT32(INAV_USE_GPS, 0);
+
+PARAM_DEFINE_FLOAT(INAV_K_ALT_00, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_ALT_01, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_ALT_10, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_ALT_11, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_ALT_20, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_ALT_21, 0.0f);
+
+PARAM_DEFINE_FLOAT(INAV_K_POS_00, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_POS_01, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_POS_10, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_POS_11, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_POS_20, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_K_POS_21, 0.0f);
+
+int parameters_init(struct position_estimator_inav_param_handles *h) {
+ h->use_gps = param_find("INAV_USE_GPS");
+
+ h->k_alt_00 = param_find("INAV_K_ALT_00");
+ h->k_alt_01 = param_find("INAV_K_ALT_01");
+ h->k_alt_10 = param_find("INAV_K_ALT_10");
+ h->k_alt_11 = param_find("INAV_K_ALT_11");
+ h->k_alt_20 = param_find("INAV_K_ALT_20");
+ h->k_alt_21 = param_find("INAV_K_ALT_21");
+
+ h->k_pos_00 = param_find("INAV_K_POS_00");
+ h->k_pos_01 = param_find("INAV_K_POS_01");
+ h->k_pos_10 = param_find("INAV_K_POS_10");
+ h->k_pos_11 = param_find("INAV_K_POS_11");
+ h->k_pos_20 = param_find("INAV_K_POS_20");
+ h->k_pos_21 = param_find("INAV_K_POS_21");
+
+ return OK;
+}
+
+int parameters_update(const struct position_estimator_inav_param_handles *h, struct position_estimator_inav_params *p) {
+ param_get(h->use_gps, &(p->use_gps));
+
+ param_get(h->k_alt_00, &(p->k_alt[0][0]));
+ param_get(h->k_alt_01, &(p->k_alt[0][1]));
+ param_get(h->k_alt_10, &(p->k_alt[1][0]));
+ param_get(h->k_alt_11, &(p->k_alt[1][1]));
+ param_get(h->k_alt_20, &(p->k_alt[2][0]));
+ param_get(h->k_alt_21, &(p->k_alt[2][1]));
+
+ param_get(h->k_pos_00, &(p->k_pos[0][0]));
+ param_get(h->k_pos_01, &(p->k_pos[0][1]));
+ param_get(h->k_pos_10, &(p->k_pos[1][0]));
+ param_get(h->k_pos_11, &(p->k_pos[1][1]));
+ param_get(h->k_pos_20, &(p->k_pos[2][0]));
+ param_get(h->k_pos_21, &(p->k_pos[2][1]));
+
+ return OK;
+}
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
new file mode 100644
index 000000000..8cdc2e10f
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * @file position_estimator_inav_params.h
+ *
+ * Parameters for Position Estimator
+ */
+
+#include <systemlib/param/param.h>
+
+struct position_estimator_inav_params {
+ int use_gps;
+ float k_alt[3][2];
+ float k_pos[3][2];
+};
+
+struct position_estimator_inav_param_handles {
+ param_t use_gps;
+
+ param_t k_alt_00;
+ param_t k_alt_01;
+ param_t k_alt_10;
+ param_t k_alt_11;
+ param_t k_alt_20;
+ param_t k_alt_21;
+
+ param_t k_pos_00;
+ param_t k_pos_01;
+ param_t k_pos_10;
+ param_t k_pos_11;
+ param_t k_pos_20;
+ param_t k_pos_21;
+};
+
+/**
+ * Initialize all parameter handles and values
+ *
+ */
+int parameters_init(struct position_estimator_inav_param_handles *h);
+
+/**
+ * Update all parameters
+ *
+ */
+int parameters_update(const struct position_estimator_inav_param_handles *h, struct position_estimator_inav_params *p);