aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-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.c324
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c54
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.h38
-rw-r--r--src/modules/multirotor_pos_control/position_control.c235
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.c28
-rw-r--r--src/modules/position_estimator_inav/inertial_filter.h13
-rw-r--r--src/modules/position_estimator_inav/module.mk41
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c481
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c72
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h (renamed from src/modules/multirotor_pos_control/position_control.h)49
-rw-r--r--src/modules/sdlog2/sdlog2.c11
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h14
14 files changed, 1079 insertions, 380 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..c94972e7d 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,13 +35,14 @@
/**
* @file multirotor_pos_control.c
*
- * Skeleton for multirotor position controller
+ * Multirotor position controller
*/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
+#include <math.h>
#include <stdbool.h>
#include <unistd.h>
#include <fcntl.h>
@@ -52,13 +53,15 @@
#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,13 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]);
*/
static void usage(const char *reason);
-static void
-usage(const char *reason)
-{
+static float scale_control(float ctl, float end, float dz);
+
+static float limit_value(float v, float limit);
+
+static float norm(float x, float y);
+
+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 +103,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 +132,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 +143,258 @@ int multirotor_pos_control_main(int argc, char *argv[])
exit(1);
}
-static int
-multirotor_pos_control_thread_main(int argc, char *argv[])
-{
+static float scale_control(float ctl, float end, float dz) {
+ if (ctl > dz) {
+ return (ctl - dz) / (end - dz);
+ } else if (ctl < -dz) {
+ return (ctl + dz) / (end - dz);
+ } else {
+ return 0.0f;
+ }
+}
+
+static float limit_value(float v, float limit) {
+ if (v > limit) {
+ v = limit;
+ } else if (v < -limit) {
+ v = -limit;
+ }
+ return v;
+}
+
+static float norm(float x, float y) {
+ return sqrtf(x * x + y * y);
+}
+
+static int multirotor_pos_control_thread_main(int argc, char *argv[]) {
/* welcome user */
- printf("[multirotor pos control] Control started, taking over position control\n");
+ warnx("started.");
+ 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;
+ /* integrate in NED frame to estimate wind but not attitude offset */
+ float pos_x_integral = 0.0f;
+ float pos_y_integral = 0.0f;
+ const float alt_ctl_dz = 0.2f;
+ const float pos_ctl_dz = 0.05f;
+
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;
+ mavlink_log_info(mavlink_fd, "reset alt setpoint: z = %.2f, throttle = %.2f", local_pos_sp.z, manual.throttle);
+ }
+
+ 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;
+ pos_x_integral = 0.0f;
+ pos_y_integral = 0.0f;
+ mavlink_log_info(mavlink_fd, "reset pos setpoint: x = %.2f, y = %.2f", local_pos_sp.x, local_pos_sp.y);
+ }
+
+ float alt_err_linear_limit = params.alt_d / params.alt_p * params.alt_rate_max;
+ float pos_err_linear_limit = params.pos_d / params.pos_p * params.pos_rate_max;
+
+ float pos_sp_speed_x = 0.0f;
+ float pos_sp_speed_y = 0.0f;
+ float pos_sp_speed_z = 0.0f;
+
+ if (status.flag_control_manual_enabled) {
+ /* move altitude setpoint with manual controls */
+ float alt_sp_ctl = scale_control(manual.throttle - 0.5f, 0.5f, alt_ctl_dz);
+ if (alt_sp_ctl != 0.0f) {
+ pos_sp_speed_z = -alt_sp_ctl * params.alt_rate_max;
+ local_pos_sp.z += pos_sp_speed_z * dt;
+ if (local_pos_sp.z > local_pos.z + alt_err_linear_limit) {
+ local_pos_sp.z = local_pos.z + alt_err_linear_limit;
+ } else if (local_pos_sp.z < local_pos.z - alt_err_linear_limit) {
+ local_pos_sp.z = local_pos.z - alt_err_linear_limit;
+ }
+ }
+
+ if (status.manual_sas_mode == VEHICLE_MANUAL_SAS_MODE_SIMPLE) {
+ /* move position setpoint with manual controls */
+ float pos_x_sp_ctl = scale_control(-manual.pitch / params.rc_scale_pitch, 1.0f, pos_ctl_dz);
+ float pos_y_sp_ctl = scale_control(manual.roll / params.rc_scale_roll, 1.0f, pos_ctl_dz);
+ if (pos_x_sp_ctl != 0.0f || pos_y_sp_ctl != 0.0f) {
+ /* calculate direction and increment of control in NED frame */
+ float dir_sp_ctl = att.yaw + atan2f(pos_y_sp_ctl, pos_x_sp_ctl);
+ float d_sp_ctl = norm(pos_x_sp_ctl, pos_y_sp_ctl) * params.pos_rate_max;
+ pos_sp_speed_x = cosf(dir_sp_ctl) * d_sp_ctl;
+ pos_sp_speed_x = sinf(dir_sp_ctl) * d_sp_ctl;
+ local_pos_sp.x += pos_sp_speed_x * dt;
+ local_pos_sp.y += pos_sp_speed_y * dt;
+ /* limit maximum setpoint from position offset and preserve direction */
+ float pos_vec_x = local_pos_sp.x - local_pos.x;
+ float pos_vec_y = local_pos_sp.y - local_pos.y;
+ float pos_vec_norm = norm(pos_vec_x, pos_vec_y) / pos_err_linear_limit;
+ if (pos_vec_norm > 1.0f) {
+ local_pos_sp.x = local_pos.x + pos_vec_x / pos_vec_norm;
+ local_pos_sp.y = local_pos.y + pos_vec_y / pos_vec_norm;
+ }
+ }
+ }
+
+ if (params.hard == 0) {
+ pos_sp_speed_x = 0.0f;
+ pos_sp_speed_y = 0.0f;
+ pos_sp_speed_z = 0.0f;
+ }
+ }
+
+ /* PID for altitude */
+ /* don't accelerate more than ALT_RATE_MAX, limit error to corresponding value */
+ float alt_err = limit_value(local_pos_sp.z - local_pos.z, alt_err_linear_limit);
+ /* P and D components */
+ float thrust_ctl_pd = -(alt_err * params.alt_p + (pos_sp_speed_z - local_pos.vz) * params.alt_d); // altitude = -z
+ /* integrate */
+ alt_integral += thrust_ctl_pd / params.alt_p * params.alt_i * dt;
+ if (alt_integral < params.thr_min) {
+ alt_integral = params.thr_min;
+ } else if (alt_integral > params.thr_max) {
+ alt_integral = params.thr_max;
+ }
+ /* add I component */
+ float thrust_ctl = thrust_ctl_pd + alt_integral;
+ 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) {
+ /* PID for position */
+ /* don't accelerate more than POS_RATE_MAX, limit error to corresponding value */
+ float pos_x_err = limit_value(local_pos.x - local_pos_sp.x, pos_err_linear_limit);
+ float pos_y_err = limit_value(local_pos.y - local_pos_sp.y, pos_err_linear_limit);
+ /* P and D components */
+ float pos_x_ctl_pd = - pos_x_err * params.pos_p + (pos_sp_speed_x - local_pos.vx) * params.pos_d;
+ float pos_y_ctl_pd = - pos_y_err * params.pos_p + (pos_sp_speed_y - local_pos.vy) * params.pos_d;
+ /* integrate */
+ pos_x_integral = limit_value(pos_x_integral + pos_x_ctl_pd / params.pos_p * params.pos_i * dt, params.slope_max);
+ pos_y_integral = limit_value(pos_y_integral + pos_y_ctl_pd / params.pos_p * params.pos_i * dt, params.slope_max);
+ /* add I component */
+ float pos_x_ctl = pos_x_ctl_pd + pos_x_integral;
+ float pos_y_ctl = pos_y_ctl_pd + pos_y_integral;
+ /* calculate direction and slope in NED frame */
+ float dir = atan2f(pos_y_ctl, pos_x_ctl);
+ /* use approximation: slope ~ sin(slope) = force */
+ float slope = limit_value(sqrtf(pos_x_ctl * pos_x_ctl + pos_y_ctl * pos_y_ctl), params.slope_max);
+ /* convert direction to body frame */
+ dir -= att.yaw;
+ /* calculate roll and pitch */
+ att_sp.pitch_body = -cosf(dir) * slope; // reverse pitch
+ att_sp.roll_body = sinf(dir) * slope;
+ } 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..7c3296cae 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,67 @@
****************************************************************************/
/*
- * @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.1f);
+PARAM_DEFINE_FLOAT(MPC_ALT_D, 0.1f);
+PARAM_DEFINE_FLOAT(MPC_ALT_RATE_MAX, 3.0f);
+PARAM_DEFINE_FLOAT(MPC_POS_P, 0.1f);
+PARAM_DEFINE_FLOAT(MPC_POS_I, 0.0f);
+PARAM_DEFINE_FLOAT(MPC_POS_D, 0.2f);
+PARAM_DEFINE_FLOAT(MPC_POS_RATE_MAX, 10.0f);
+PARAM_DEFINE_FLOAT(MPC_SLOPE_MAX, 0.5f);
+PARAM_DEFINE_INT32(MPC_HARD, 0);
int parameters_init(struct multirotor_position_control_param_handles *h)
{
- /* PID parameters */
- h->p = param_find("MC_POS_P");
+ h->thr_min = param_find("MPC_THR_MIN");
+ h->thr_max = param_find("MPC_THR_MAX");
+ 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");
+ h->pos_p = param_find("MPC_POS_P");
+ h->pos_i = param_find("MPC_POS_I");
+ h->pos_d = param_find("MPC_POS_D");
+ h->pos_rate_max = param_find("MPC_POS_RATE_MAX");
+ h->slope_max = param_find("MPC_SLOPE_MAX");
+ h->slope_max = param_find("MPC_HARD");
+
+ h->rc_scale_pitch = param_find("RC_SCALE_PITCH");
+ h->rc_scale_roll = param_find("RC_SCALE_ROLL");
+ h->rc_scale_yaw = param_find("RC_SCALE_YAW");
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));
+ param_get(h->pos_p, &(p->pos_p));
+ param_get(h->pos_i, &(p->pos_i));
+ param_get(h->pos_d, &(p->pos_d));
+ param_get(h->pos_rate_max, &(p->pos_rate_max));
+ param_get(h->slope_max, &(p->slope_max));
+ param_get(h->hard, &(p->hard));
+
+ param_get(h->rc_scale_pitch, &(p->rc_scale_pitch));
+ param_get(h->rc_scale_roll, &(p->rc_scale_roll));
+ param_get(h->rc_scale_yaw, &(p->rc_scale_yaw));
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..13b667ad3 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,41 @@
#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;
+ float pos_p;
+ float pos_i;
+ float pos_d;
+ float pos_rate_max;
+ float slope_max;
+ int hard;
+
+ float rc_scale_pitch;
+ float rc_scale_roll;
+ float rc_scale_yaw;
};
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;
+ param_t pos_p;
+ param_t pos_i;
+ param_t pos_d;
+ param_t pos_rate_max;
+ param_t slope_max;
+ param_t hard;
+
+ param_t rc_scale_pitch;
+ param_t rc_scale_roll;
+ param_t rc_scale_yaw;
};
/**
diff --git a/src/modules/multirotor_pos_control/position_control.c b/src/modules/multirotor_pos_control/position_control.c
deleted file mode 100644
index 9c53a5bf6..000000000
--- a/src/modules/multirotor_pos_control/position_control.c
+++ /dev/null
@@ -1,235 +0,0 @@
-// /****************************************************************************
-// *
-// * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
-// * Author: @author Lorenz Meier <lm@inf.ethz.ch>
-// * @author Laurens Mackay <mackayl@student.ethz.ch>
-// * @author Tobias Naegeli <naegelit@student.ethz.ch>
-// * @author Martin Rutschmann <rutmarti@student.ethz.ch>
-// *
-// * 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 multirotor_position_control.c
-// * Implementation of the position control for a multirotor VTOL
-// */
-
-// #include <stdio.h>
-// #include <stdlib.h>
-// #include <stdio.h>
-// #include <stdint.h>
-// #include <math.h>
-// #include <stdbool.h>
-// #include <float.h>
-// #include <systemlib/pid/pid.h>
-
-// #include "multirotor_position_control.h"
-
-// void control_multirotor_position(const struct vehicle_state_s *vstatus, const struct vehicle_manual_control_s *manual,
-// const struct vehicle_attitude_s *att, const struct vehicle_local_position_s *local_pos,
-// const struct vehicle_local_position_setpoint_s *local_pos_sp, struct vehicle_attitude_setpoint_s *att_sp)
-// {
-// static PID_t distance_controller;
-
-// static int read_ret;
-// static global_data_position_t position_estimated;
-
-// static uint16_t counter;
-
-// static bool initialized;
-// static uint16_t pm_counter;
-
-// static float lat_next;
-// static float lon_next;
-
-// static float pitch_current;
-
-// static float thrust_total;
-
-
-// if (initialized == false) {
-
-// pid_init(&distance_controller,
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_P],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_I],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_D],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_AWU],
-// PID_MODE_DERIVATIV_CALC, 150);//150
-
-// // pid_pos_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_LIM];
-// // pid_pos_z_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_Z_LIM];
-
-// thrust_total = 0.0f;
-
-// /* Position initialization */
-// /* Wait for new position estimate */
-// do {
-// read_ret = read_lock_position(&position_estimated);
-// } while (read_ret != 0);
-
-// lat_next = position_estimated.lat;
-// lon_next = position_estimated.lon;
-
-// /* attitude initialization */
-// global_data_lock(&global_data_attitude->access_conf);
-// pitch_current = global_data_attitude->pitch;
-// global_data_unlock(&global_data_attitude->access_conf);
-
-// initialized = true;
-// }
-
-// /* load new parameters with 10Hz */
-// if (counter % 50 == 0) {
-// if (global_data_trylock(&global_data_parameter_storage->access_conf) == 0) {
-// /* check whether new parameters are available */
-// if (global_data_parameter_storage->counter > pm_counter) {
-// pid_set_parameters(&distance_controller,
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_P],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_I],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_D],
-// global_data_parameter_storage->pm.param_values[PARAM_PID_POS_AWU]);
-
-// //
-// // pid_pos_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_LIM];
-// // pid_pos_z_lim = global_data_parameter_storage->pm.param_values[PARAM_PID_POS_Z_LIM];
-
-// pm_counter = global_data_parameter_storage->counter;
-// printf("Position controller changed pid parameters\n");
-// }
-// }
-
-// global_data_unlock(&global_data_parameter_storage->access_conf);
-// }
-
-
-// /* Wait for new position estimate */
-// do {
-// read_ret = read_lock_position(&position_estimated);
-// } while (read_ret != 0);
-
-// /* Get next waypoint */ //TODO: add local copy
-
-// if (0 == global_data_trylock(&global_data_position_setpoint->access_conf)) {
-// lat_next = global_data_position_setpoint->x;
-// lon_next = global_data_position_setpoint->y;
-// global_data_unlock(&global_data_position_setpoint->access_conf);
-// }
-
-// /* Get distance to waypoint */
-// float distance_to_waypoint = get_distance_to_next_waypoint(position_estimated.lat , position_estimated.lon, lat_next, lon_next);
-// // if(counter % 5 == 0)
-// // printf("distance_to_waypoint: %.4f\n", distance_to_waypoint);
-
-// /* Get bearing to waypoint (direction on earth surface to next waypoint) */
-// float bearing = get_bearing_to_next_waypoint(position_estimated.lat, position_estimated.lon, lat_next, lon_next);
-
-// if (counter % 5 == 0)
-// printf("bearing: %.4f\n", bearing);
-
-// /* Calculate speed in direction of bearing (needed for controller) */
-// float speed_norm = sqrtf(position_estimated.vx * position_estimated.vx + position_estimated.vy * position_estimated.vy);
-// // if(counter % 5 == 0)
-// // printf("speed_norm: %.4f\n", speed_norm);
-// float speed_to_waypoint = 0; //(position_estimated.vx * cosf(bearing) + position_estimated.vy * sinf(bearing))/speed_norm; //FIXME, TODO: re-enable this once we have a full estimate of the speed, then we can do a PID for the distance controller
-
-// /* Control Thrust in bearing direction */
-// float horizontal_thrust = -pid_calculate(&distance_controller, 0, distance_to_waypoint, speed_to_waypoint,
-// CONTROL_PID_POSITION_INTERVAL); //TODO: maybe this "-" sign is an error somewhere else
-
-// // if(counter % 5 == 0)
-// // printf("horizontal thrust: %.4f\n", horizontal_thrust);
-
-// /* Get total thrust (from remote for now) */
-// if (0 == global_data_trylock(&global_data_rc_channels->access_conf)) {
-// thrust_total = (float)global_data_rc_channels->chan[THROTTLE].scale; //TODO: how should we use the RC_CHANNELS_FUNCTION enum?
-// global_data_unlock(&global_data_rc_channels->access_conf);
-// }
-
-// const float max_gas = 500.0f;
-// thrust_total *= max_gas / 20000.0f; //TODO: check this
-// thrust_total += max_gas / 2.0f;
-
-
-// if (horizontal_thrust > thrust_total) {
-// horizontal_thrust = thrust_total;
-
-// } else if (horizontal_thrust < -thrust_total) {
-// horizontal_thrust = -thrust_total;
-// }
-
-
-
-// //TODO: maybe we want to add a speed controller later...
-
-// /* Calclulate thrust in east and north direction */
-// float thrust_north = cosf(bearing) * horizontal_thrust;
-// float thrust_east = sinf(bearing) * horizontal_thrust;
-
-// if (counter % 10 == 0) {
-// printf("thrust north: %.4f\n", thrust_north);
-// printf("thrust east: %.4f\n", thrust_east);
-// fflush(stdout);
-// }
-
-// /* Get current attitude */
-// if (0 == global_data_trylock(&global_data_attitude->access_conf)) {
-// pitch_current = global_data_attitude->pitch;
-// global_data_unlock(&global_data_attitude->access_conf);
-// }
-
-// /* Get desired pitch & roll */
-// float pitch_desired = 0.0f;
-// float roll_desired = 0.0f;
-
-// if (thrust_total != 0) {
-// float pitch_fraction = -thrust_north / thrust_total;
-// float roll_fraction = thrust_east / (cosf(pitch_current) * thrust_total);
-
-// if (roll_fraction < -1) {
-// roll_fraction = -1;
-
-// } else if (roll_fraction > 1) {
-// roll_fraction = 1;
-// }
-
-// // if(counter % 5 == 0)
-// // {
-// // printf("pitch_fraction: %.4f, roll_fraction: %.4f\n",pitch_fraction, roll_fraction);
-// // fflush(stdout);
-// // }
-
-// pitch_desired = asinf(pitch_fraction);
-// roll_desired = asinf(roll_fraction);
-// }
-
-// att_sp.roll = roll_desired;
-// att_sp.pitch = pitch_desired;
-
-// counter++;
-// }
diff --git a/src/modules/position_estimator_inav/inertial_filter.c b/src/modules/position_estimator_inav/inertial_filter.c
new file mode 100644
index 000000000..8cdde5e1a
--- /dev/null
+++ b/src/modules/position_estimator_inav/inertial_filter.c
@@ -0,0 +1,28 @@
+/*
+ * inertial_filter.c
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include "inertial_filter.h"
+
+void inertial_filter_predict(float dt, float x[3])
+{
+ x[0] += x[1] * dt + x[2] * dt * dt / 2.0f;
+ x[1] += x[2] * dt;
+}
+
+void inertial_filter_correct(float edt, float x[3], int i, float w)
+{
+ float ewdt = w * edt;
+ x[i] += ewdt;
+
+ if (i == 0) {
+ x[1] += w * ewdt;
+ //x[2] += e * w * w * w * dt / 3.0; // ~ 0.0
+
+ } else if (i == 1) {
+ x[2] += w * ewdt;
+ }
+}
diff --git a/src/modules/position_estimator_inav/inertial_filter.h b/src/modules/position_estimator_inav/inertial_filter.h
new file mode 100644
index 000000000..dca6375dc
--- /dev/null
+++ b/src/modules/position_estimator_inav/inertial_filter.h
@@ -0,0 +1,13 @@
+/*
+ * inertial_filter.h
+ *
+ * Copyright (C) 2013 Anton Babushkin. All rights reserved.
+ * Author: Anton Babushkin <rk3dov@gmail.com>
+ */
+
+#include <stdbool.h>
+#include <drivers/drv_hrt.h>
+
+void inertial_filter_predict(float dt, float x[3]);
+
+void inertial_filter_correct(float edt, float x[3], int i, float w);
diff --git a/src/modules/position_estimator_inav/module.mk b/src/modules/position_estimator_inav/module.mk
new file mode 100644
index 000000000..939d76849
--- /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 \
+ inertial_filter.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..ac51a7010
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -0,0 +1,481 @@
+/****************************************************************************
+ *
+ * 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_global_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 "inertial_filter.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[])
+{
+ warnx("started.");
+ int mavlink_fd;
+ mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
+ mavlink_log_info(mavlink_fd, "[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_init_cnt = 0;
+ int baro_init_num = 70; /* measurement for 1 second */
+ float baro_alt0 = 0.0f; /* to determine while start up */
+
+ double lat_current = 0.0; //[°]] --> 47.0
+ double lon_current = 0.0; //[°]] -->8.5
+ double alt_current = 0.0; //[m] above MSL
+
+ uint32_t accel_counter = 0;
+ uint32_t baro_counter = 0;
+
+ /* 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 local_pos;
+ memset(&local_pos, 0, sizeof(local_pos));
+ struct vehicle_global_position_s global_pos;
+ memset(&global_pos, 0, sizeof(global_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), &local_pos);
+ orb_advert_t vehicle_global_position_pub = orb_advertise(ORB_ID(vehicle_global_position), &global_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);
+
+ /* first parameters read at start up */
+ struct parameter_update_s param_update;
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &param_update); /* read from param topic to clear updated flag */
+ /* first parameters update */
+ parameters_update(&pos_inav_param_handles, &params);
+
+ struct pollfd fds_init[2] = {
+ { .fd = sensor_combined_sub, .events = POLLIN },
+ { .fd = vehicle_gps_position_sub, .events = POLLIN }
+ };
+
+ /* wait for initial sensors values: baro, GPS fix, only then can we initialize the projection */
+ bool wait_gps = params.use_gps;
+ bool wait_baro = true;
+
+ while (wait_gps || wait_baro) {
+ if (poll(fds_init, 2, 1000)) {
+ if (fds_init[0].revents & POLLIN) {
+ orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
+ if (wait_baro && sensor.baro_counter > baro_counter) {
+ /* mean calculation over several measurements */
+ if (baro_init_cnt < baro_init_num) {
+ baro_alt0 += sensor.baro_alt_meter;
+ baro_init_cnt++;
+
+ } else {
+ wait_baro = false;
+ baro_alt0 /= (float) baro_init_cnt;
+ warnx("init baro: alt = %.3f", baro_alt0);
+ mavlink_log_info(mavlink_fd, "[inav] init baro: alt = %.3f", baro_alt0);
+ local_pos.home_alt = baro_alt0;
+ local_pos.home_timestamp = hrt_absolute_time();
+ }
+ }
+ }
+ if (fds_init[1].revents & POLLIN) {
+ orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
+ if (wait_gps && gps.fix_type >= 3) {
+ wait_gps = false;
+ /* get GPS position for first initialization */
+ lat_current = gps.lat * 1e-7;
+ lon_current = gps.lon * 1e-7;
+ alt_current = gps.alt * 1e-3;
+
+ local_pos.home_lat = lat_current * 1e7;
+ local_pos.home_lon = lon_current * 1e7;
+ local_pos.home_hdg = 0.0f;
+ local_pos.home_timestamp = hrt_absolute_time();
+
+ /* initialize coordinates */
+ map_projection_init(lat_current, lon_current);
+ warnx("init GPS: lat = %.10f, lon = %.10f", lat_current, lon_current);
+ mavlink_log_info(mavlink_fd, "[inav] init GPS: lat = %.10f, lon = %.10f", lat_current, lon_current);
+ }
+ }
+ }
+ }
+
+ hrt_abstime t_prev = 0;
+
+ uint16_t accel_updates = 0;
+ hrt_abstime accel_t = 0;
+ uint16_t baro_updates = 0;
+ hrt_abstime baro_t = 0;
+ hrt_abstime gps_t = 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
+
+ /* store error when sensor updates, but correct on each time step to avoid jumps in estimated value */
+ float accel_corr[] = { 0.0f, 0.0f, 0.0f }; // N E D
+ float baro_corr = 0.0f; // D
+ float gps_corr[2][2] = {
+ { 0.0f, 0.0f }, // N (pos, vel)
+ { 0.0f, 0.0f }, // E (pos, vel)
+ };
+
+ /* 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 }
+ };
+
+ thread_running = true;
+ warnx("main loop started.");
+
+ while (!thread_should_exit) {
+ int ret = poll(fds, params.use_gps ? 5 : 4, 10); // wait maximal this 10 ms = 100 Hz minimum rate
+ hrt_abstime t = hrt_absolute_time();
+
+ if (ret < 0) {
+ /* poll error */
+ warnx("subscriptions poll error.");
+ 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 > accel_counter) {
+ if (att.R_valid) {
+ /* transform acceleration vector from body 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;
+ accel_corr[0] = accel_NED[0] - x_est[2];
+ accel_corr[1] = accel_NED[1] - y_est[2];
+ accel_corr[2] = accel_NED[2] - z_est[2];
+ } else {
+ memset(accel_corr, 0, sizeof(accel_corr));
+ }
+ accel_counter = sensor.accelerometer_counter;
+ accel_updates++;
+ }
+
+ if (sensor.baro_counter > baro_counter) {
+ baro_corr = baro_alt0 - sensor.baro_alt_meter - z_est[2];
+ baro_counter = sensor.baro_counter;
+ baro_updates++;
+ }
+ }
+
+ 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);
+ if (gps.fix_type >= 3) {
+ /* project GPS lat lon to plane */
+ float gps_proj[2];
+ map_projection_project(gps.lat * 1e-7, gps.lon * 1e-7, &(gps_proj[0]), &(gps_proj[1]));
+ gps_corr[0][0] = gps_proj[0] - x_est[0];
+ gps_corr[1][0] = gps_proj[1] - y_est[0];
+ if (gps.vel_ned_valid) {
+ gps_corr[0][1] = gps.vel_n_m_s;
+ gps_corr[1][1] = gps.vel_e_m_s;
+ } else {
+ gps_corr[0][1] = 0.0f;
+ gps_corr[1][1] = 0.0f;
+ }
+ local_pos.valid = true;
+ gps_updates++;
+ } else {
+ local_pos.valid = false;
+ }
+ }
+ } else {
+ local_pos.valid = true;
+ }
+
+ }
+
+ /* end of poll return value check */
+
+ float dt = t_prev > 0 ? (t - t_prev) / 1000000.0f : 0.0f;
+ t_prev = t;
+
+ /* inertial filter prediction for altitude */
+ inertial_filter_predict(dt, z_est);
+
+ /* inertial filter correction for altitude */
+ inertial_filter_correct(baro_corr * dt, z_est, 0, params.w_alt_baro);
+ inertial_filter_correct(accel_corr[2] * dt, z_est, 2, params.w_alt_acc);
+
+ if (params.use_gps) {
+ /* inertial filter prediction for position */
+ inertial_filter_predict(dt, x_est);
+ inertial_filter_predict(dt, y_est);
+
+ /* inertial filter correction for position */
+ inertial_filter_correct(gps_corr[0][0] * dt, x_est, 0, params.w_pos_gps_p);
+ inertial_filter_correct(gps_corr[0][1] * dt, x_est, 1, params.w_pos_gps_v);
+ inertial_filter_correct(gps_corr[1][0] * dt, y_est, 0, params.w_pos_gps_p);
+ inertial_filter_correct(gps_corr[1][1] * dt, y_est, 1, params.w_pos_gps_v);
+
+ inertial_filter_correct(accel_corr[0] * dt, x_est, 2, params.w_pos_acc);
+ inertial_filter_correct(accel_corr[1] * dt, y_est, 2, params.w_pos_acc);
+ }
+
+ if (verbose_mode) {
+ /* print updates rate */
+ if (t - updates_counter_start > updates_counter_len) {
+ float updates_dt = (t - updates_counter_start) * 0.000001f;
+ printf(
+ "[inav] updates rate: accelerometer = %.1f/s, baro = %.1f/s, gps = %.1f/s, attitude = %.1f/s\n",
+ accel_updates / updates_dt,
+ baro_updates / updates_dt,
+ gps_updates / updates_dt,
+ attitude_updates / updates_dt);
+ updates_counter_start = t;
+ accel_updates = 0;
+ baro_updates = 0;
+ gps_updates = 0;
+ attitude_updates = 0;
+ }
+ }
+
+ if (t - pub_last > pub_interval) {
+ pub_last = t;
+ local_pos.timestamp = t;
+ local_pos.x = x_est[0];
+ local_pos.vx = x_est[1];
+ local_pos.y = y_est[0];
+ local_pos.vy = y_est[1];
+ local_pos.z = z_est[0];
+ local_pos.vz = z_est[1];
+ local_pos.absolute_alt = local_pos.home_alt - local_pos.z;
+ local_pos.hdg = att.yaw;
+
+ if ((isfinite(local_pos.x)) && (isfinite(local_pos.vx))
+ && (isfinite(local_pos.y))
+ && (isfinite(local_pos.vy))
+ && (isfinite(local_pos.z))
+ && (isfinite(local_pos.vz))) {
+ orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos);
+
+ if (params.use_gps) {
+ global_pos.valid = local_pos.valid;
+ double est_lat, est_lon;
+ map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon);
+ global_pos.lat = (int32_t) (est_lat * 1e7);
+ global_pos.lon = (int32_t) (est_lon * 1e7);
+ global_pos.alt = -local_pos.z - local_pos.home_alt;
+ global_pos.relative_alt = -local_pos.z;
+ global_pos.vx = local_pos.vx;
+ global_pos.vy = local_pos.vy;
+ global_pos.vz = local_pos.vz;
+ global_pos.hdg = local_pos.hdg;
+
+ orb_publish(ORB_ID(vehicle_global_position), vehicle_global_position_pub, &global_pos);
+ }
+ }
+ }
+ }
+
+ warnx("exiting.");
+ mavlink_log_info(mavlink_fd, "[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..49dc7f51f
--- /dev/null
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -0,0 +1,72 @@
+/****************************************************************************
+ *
+ * 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, 1);
+PARAM_DEFINE_FLOAT(INAV_W_ALT_BARO, 1.0f);
+PARAM_DEFINE_FLOAT(INAV_W_ALT_ACC, 50.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_GPS_P, 4.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_GPS_V, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_ACC, 10.0f);
+
+int parameters_init(struct position_estimator_inav_param_handles *h)
+{
+ h->use_gps = param_find("INAV_USE_GPS");
+ h->w_alt_baro = param_find("INAV_W_ALT_BARO");
+ h->w_alt_acc = param_find("INAV_W_ALT_ACC");
+ h->w_pos_gps_p = param_find("INAV_W_POS_GPS_P");
+ h->w_pos_gps_v = param_find("INAV_W_POS_GPS_V");
+ h->w_pos_acc = param_find("INAV_W_POS_ACC");
+
+ 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->w_alt_baro, &(p->w_alt_baro));
+ param_get(h->w_alt_acc, &(p->w_alt_acc));
+ param_get(h->w_pos_gps_p, &(p->w_pos_gps_p));
+ param_get(h->w_pos_gps_v, &(p->w_pos_gps_v));
+ param_get(h->w_pos_acc, &(p->w_pos_acc));
+
+ return OK;
+}
diff --git a/src/modules/multirotor_pos_control/position_control.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index 2144ebc34..870227fef 100644
--- a/src/modules/multirotor_pos_control/position_control.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -1,10 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
- * @author Laurens Mackay <mackayl@student.ethz.ch>
- * @author Tobias Naegeli <naegelit@student.ethz.ch>
- * @author Martin Rutschmann <rutmarti@student.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,16 +32,40 @@
*
****************************************************************************/
-/**
- * @file multirotor_position_control.h
- * Definition of the position control for a multirotor VTOL
+/*
+ * @file position_estimator_inav_params.h
+ *
+ * Parameters for Position Estimator
*/
-// #ifndef POSITION_CONTROL_H_
-// #define POSITION_CONTROL_H_
+#include <systemlib/param/param.h>
+
+struct position_estimator_inav_params {
+ int use_gps;
+ float w_alt_baro;
+ float w_alt_acc;
+ float w_pos_gps_p;
+ float w_pos_gps_v;
+ float w_pos_acc;
+};
-// void control_multirotor_position(const struct vehicle_state_s *vstatus, const struct vehicle_manual_control_s *manual,
-// const struct vehicle_attitude_s *att, const struct vehicle_local_position_s *local_pos,
-// const struct vehicle_local_position_setpoint_s *local_pos_sp, struct vehicle_attitude_setpoint_s *att_sp);
+struct position_estimator_inav_param_handles {
+ param_t use_gps;
+ param_t w_alt_baro;
+ param_t w_alt_acc;
+ param_t w_pos_gps_p;
+ param_t w_pos_gps_v;
+ param_t w_pos_acc;
+};
+
+/**
+ * Initialize all parameter handles and values
+ *
+ */
+int parameters_init(struct position_estimator_inav_param_handles *h);
-// #endif /* POSITION_CONTROL_H_ */
+/**
+ * Update all parameters
+ *
+ */
+int parameters_update(const struct position_estimator_inav_param_handles *h, struct position_estimator_inav_params *p);
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index 6715b57f5..c318f18c3 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -668,6 +668,7 @@ int sdlog2_thread_main(int argc, char *argv[])
struct log_OUT0_s log_OUT0;
struct log_AIRS_s log_AIRS;
struct log_ARSP_s log_ARSP;
+ struct log_GPOS_s log_GPOS;
} body;
} log_msg = {
LOG_PACKET_HEADER_INIT(0)
@@ -1039,7 +1040,15 @@ int sdlog2_thread_main(int argc, char *argv[])
/* --- GLOBAL POSITION --- */
if (fds[ifds++].revents & POLLIN) {
orb_copy(ORB_ID(vehicle_global_position), subs.global_pos_sub, &buf.global_pos);
- // TODO not implemented yet
+ log_msg.msg_type = LOG_GPOS_MSG;
+ log_msg.body.log_GPOS.lat = buf.global_pos.lat;
+ log_msg.body.log_GPOS.lon = buf.global_pos.lon;
+ log_msg.body.log_GPOS.alt = buf.global_pos.alt;
+ log_msg.body.log_GPOS.vel_n = buf.global_pos.vx;
+ log_msg.body.log_GPOS.vel_e = buf.global_pos.vy;
+ log_msg.body.log_GPOS.vel_d = buf.global_pos.vz;
+ log_msg.body.log_GPOS.hdg = buf.global_pos.hdg;
+ LOGBUFFER_WRITE_AND_COUNT(GPOS);
}
/* --- VICON POSITION --- */
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 7f7bf6053..b42f11e61 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -186,6 +186,19 @@ struct log_ARSP_s {
float pitch_rate_sp;
float yaw_rate_sp;
};
+
+/* --- GPOS - GLOBAL POSITION --- */
+#define LOG_GPOS_MSG 15
+struct log_GPOS_s {
+ int32_t lat;
+ int32_t lon;
+ float alt;
+ float vel_n;
+ float vel_e;
+ float vel_d;
+ float hdg;
+};
+
#pragma pack(pop)
/* construct list of all message formats */
@@ -205,6 +218,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
LOG_FORMAT(AIRS, "ff", "IndSpeed,TrueSpeed"),
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
+ LOG_FORMAT(GPOS, "LLfffff", "Lat,Lon,Alt,VelN,VelE,VelD"),
};
static const int log_formats_num = sizeof(log_formats) / sizeof(struct log_format_s);