aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-08-19 18:33:04 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-08-19 18:33:04 +0200
commit449dc78ae69e888d986185f120aa8c6549ef5c2b (patch)
tree9b3de04f5b287c32ec9c7cfe6094ead84ba980d3 /src
parentf96bb824d4fc6f6d36ddf24e8879d3025af39d70 (diff)
downloadpx4-firmware-449dc78ae69e888d986185f120aa8c6549ef5c2b.tar.gz
px4-firmware-449dc78ae69e888d986185f120aa8c6549ef5c2b.tar.bz2
px4-firmware-449dc78ae69e888d986185f120aa8c6549ef5c2b.zip
commander, multirotor_pos_control, sdlog2: bugfixes
Diffstat (limited to 'src')
-rw-r--r--src/modules/commander/commander.cpp17
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c249
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.c7
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control_params.h11
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c7
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h2
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h6
7 files changed, 197 insertions, 102 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 7d74e0cfe..50acec7e0 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -353,16 +353,21 @@ void handle_command(struct vehicle_status_s *status, const struct safety_s *safe
}
case VEHICLE_CMD_NAV_TAKEOFF: {
- transition_result_t nav_res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
+ if (armed->armed) {
+ transition_result_t nav_res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_TAKEOFF, control_mode);
- if (nav_res == TRANSITION_CHANGED) {
- mavlink_log_info(mavlink_fd, "[cmd] TAKEOFF on command");
- }
+ if (nav_res == TRANSITION_CHANGED) {
+ mavlink_log_info(mavlink_fd, "[cmd] TAKEOFF on command");
+ }
- if (nav_res != TRANSITION_DENIED) {
- result = VEHICLE_CMD_RESULT_ACCEPTED;
+ if (nav_res != TRANSITION_DENIED) {
+ result = VEHICLE_CMD_RESULT_ACCEPTED;
+ } else {
+ result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
+ }
} else {
+ /* reject TAKEOFF not armed */
result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
}
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index b2f6b33e3..0d5a537ea 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) 2013 Anton Babushkin. All rights reserved.
- * Author: Anton Babushkin <rk3dov@gmail.com>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -211,14 +211,23 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
orb_advert_t global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &global_vel_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;
+ bool global_pos_sp_reproject = false;
+ bool global_pos_sp_valid = false;
+ bool local_pos_sp_valid = false;
+ bool reset_sp_z = true;
+ bool reset_sp_xy = true;
+ bool reset_int_z = true;
+ bool reset_int_z_manual = false;
+ bool reset_int_xy = true;
+ bool was_armed = false;
+ bool reset_integral = true;
+
hrt_abstime t_prev = 0;
/* integrate in NED frame to estimate wind but not attitude offset */
const float alt_ctl_dz = 0.2f;
const float pos_ctl_dz = 0.05f;
- float home_alt = 0.0f;
- hrt_abstime home_alt_t = 0;
+ float ref_alt = 0.0f;
+ hrt_abstime ref_alt_t = 0;
uint64_t local_ref_timestamp = 0;
PID_t xy_pos_pids[2];
@@ -242,11 +251,8 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
thrust_pid_init(&z_vel_pid, params.z_vel_p, params.z_vel_i, params.z_vel_d, -params.thr_max, -params.thr_min, PID_MODE_DERIVATIV_CALC_NO_SP, 0.02f);
int paramcheck_counter = 0;
- bool global_pos_sp_updated = false;
while (!thread_should_exit) {
- orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
-
/* check parameters at 1 Hz */
if (++paramcheck_counter >= 50) {
paramcheck_counter = 0;
@@ -260,11 +266,14 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
pid_set_parameters(&(xy_pos_pids[i]), params.xy_p, 0.0f, params.xy_d, 1.0f, 0.0f);
/* use integral_limit_out = tilt_max / 2 */
float i_limit;
+
if (params.xy_vel_i == 0.0) {
i_limit = params.tilt_max / params.xy_vel_i / 2.0;
+
} else {
i_limit = 1.0f; // not used really
}
+
pid_set_parameters(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, i_limit, params.tilt_max);
}
@@ -273,9 +282,20 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
}
}
- /* only check global position setpoint updates but not read */
- if (!global_pos_sp_updated) {
- orb_check(global_pos_sp_sub, &global_pos_sp_updated);
+ bool updated;
+
+ orb_check(control_mode_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
+ }
+
+ orb_check(global_pos_sp_sub, &updated);
+
+ if (updated) {
+ orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp);
+ global_pos_sp_valid = true;
+ global_pos_sp_reproject = true;
}
hrt_abstime t = hrt_absolute_time();
@@ -288,6 +308,16 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
dt = 0.0f;
}
+ if (control_mode.flag_armed && !was_armed) {
+ /* reset setpoints and integrals on arming */
+ reset_sp_z = true;
+ reset_sp_xy = true;
+ reset_int_z = true;
+ reset_int_xy = true;
+ }
+
+ was_armed = control_mode.flag_armed;
+
t_prev = t;
if (control_mode.flag_control_altitude_enabled || control_mode.flag_control_velocity_enabled || control_mode.flag_control_position_enabled) {
@@ -296,77 +326,33 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
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 (control_mode.flag_control_manual_enabled) {
- /* manual mode, reset setpoints if needed */
- if (reset_sp_alt) {
- reset_sp_alt = false;
- local_pos_sp.z = local_pos.z;
- thrust_pid_set_integral(&z_vel_pid, -manual.throttle); // thrust PID uses Z downside
- mavlink_log_info(mavlink_fd, "reset alt setpoint: z = %.2f, throttle = %.2f", local_pos_sp.z, manual.throttle);
- }
-
- if (control_mode.flag_control_position_enabled && reset_sp_pos) {
- reset_sp_pos = false;
- local_pos_sp.x = local_pos.x;
- local_pos_sp.y = local_pos.y;
- pid_reset_integral(&xy_vel_pids[0]);
- pid_reset_integral(&xy_vel_pids[1]);
- mavlink_log_info(mavlink_fd, "reset pos setpoint: x = %.2f, y = %.2f", local_pos_sp.x, local_pos_sp.y);
- }
- } else {
- /* non-manual mode, project global setpoints to local frame */
- //orb_copy(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_sub, &local_pos_sp);
- if (local_pos.ref_timestamp != local_ref_timestamp) {
- local_ref_timestamp = local_pos.ref_timestamp;
- /* init local projection using local position home */
- double lat_home = local_pos.ref_lat * 1e-7;
- double lon_home = local_pos.ref_lon * 1e-7;
- map_projection_init(lat_home, lon_home);
- warnx("local pos home: lat = %.10f, lon = %.10f", lat_home, lon_home);
- mavlink_log_info(mavlink_fd, "local pos home: %.7f, %.7f", lat_home, lon_home);
- }
-
- if (global_pos_sp_updated) {
- global_pos_sp_updated = false;
- orb_copy(ORB_ID(vehicle_global_position_setpoint), global_pos_sp_sub, &global_pos_sp);
- double sp_lat = global_pos_sp.lat * 1e-7;
- double sp_lon = global_pos_sp.lon * 1e-7;
- /* project global setpoint to local setpoint */
- map_projection_project(sp_lat, sp_lon, &(local_pos_sp.x), &(local_pos_sp.y));
-
- if (global_pos_sp.altitude_is_relative) {
- local_pos_sp.z = -global_pos_sp.altitude;
-
- } else {
- local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude;
- }
-
- warnx("new setpoint: lat = %.10f, lon = %.10f, x = %.2f, y = %.2f", sp_lat, sp_lon, local_pos_sp.x, local_pos_sp.y);
- mavlink_log_info(mavlink_fd, "new setpoint: %.7f, %.7f, %.2f, %.2f", sp_lat, sp_lon, local_pos_sp.x, local_pos_sp.y);
- /* publish local position setpoint as projection of global position setpoint */
- orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
- }
- }
-
float z_sp_offs_max = params.z_vel_max / params.z_p * 2.0f;
float xy_sp_offs_max = params.xy_vel_max / params.xy_p * 2.0f;
-
float sp_move_rate[3] = { 0.0f, 0.0f, 0.0f };
- /* manual control - move setpoints */
if (control_mode.flag_control_manual_enabled) {
- if (local_pos.ref_timestamp != home_alt_t) {
- if (home_alt_t != 0) {
+ /* manual control */
+ /* check for reference point updates and correct setpoint */
+ if (local_pos.ref_timestamp != ref_alt_t) {
+ if (ref_alt_t != 0) {
/* home alt changed, don't follow large ground level changes in manual flight */
- local_pos_sp.z += local_pos.ref_alt - home_alt;
+ local_pos_sp.z += local_pos.ref_alt - ref_alt;
}
- home_alt_t = local_pos.ref_timestamp;
- home_alt = local_pos.ref_alt;
+ ref_alt_t = local_pos.ref_timestamp;
+ ref_alt = local_pos.ref_alt;
+ // TODO also correct XY setpoint
}
+ /* reset setpoints to current position if needed */
if (control_mode.flag_control_altitude_enabled) {
- /* move altitude setpoint with manual controls */
+ if (reset_sp_z) {
+ reset_sp_z = false;
+ local_pos_sp.z = local_pos.z;
+ mavlink_log_info(mavlink_fd, "[mpc] reset alt sp: %.2f", -local_pos_sp.z);
+ }
+
+ /* move altitude setpoint with throttle stick */
float z_sp_ctl = scale_control(manual.throttle - 0.5f, 0.5f, alt_ctl_dz);
if (z_sp_ctl != 0.0f) {
@@ -383,7 +369,16 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
}
if (control_mode.flag_control_position_enabled) {
- /* move position setpoint with manual controls */
+ if (reset_sp_xy) {
+ reset_sp_xy = false;
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ pid_reset_integral(&xy_vel_pids[0]);
+ pid_reset_integral(&xy_vel_pids[1]);
+ mavlink_log_info(mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", local_pos_sp.x, local_pos_sp.y);
+ }
+
+ /* move position setpoint with roll/pitch stick */
float pos_pitch_sp_ctl = scale_control(-manual.pitch / params.rc_scale_pitch, 1.0f, pos_ctl_dz);
float pos_roll_sp_ctl = scale_control(manual.roll / params.rc_scale_roll, 1.0f, pos_ctl_dz);
@@ -410,12 +405,68 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* publish local position setpoint */
orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
+
+ /* local position setpoint is valid and can be used for loiter after position controlled mode */
+ local_pos_sp_valid = control_mode.flag_control_position_enabled;
+
+ /* force reprojection of global setpoint after manual mode */
+ global_pos_sp_reproject = true;
+
+ } else {
+ /* non-manual mode, use global setpoint */
+ /* init local projection using local position ref */
+ if (local_pos.ref_timestamp != local_ref_timestamp) {
+ global_pos_sp_reproject = true;
+ local_ref_timestamp = local_pos.ref_timestamp;
+ double lat_home = local_pos.ref_lat * 1e-7;
+ double lon_home = local_pos.ref_lon * 1e-7;
+ map_projection_init(lat_home, lon_home);
+ mavlink_log_info(mavlink_fd, "[mpc] local pos ref: %.7f, %.7f", lat_home, lon_home);
+ }
+
+ if (global_pos_sp_reproject) {
+ /* update global setpoint projection */
+ global_pos_sp_reproject = false;
+
+ if (global_pos_sp_valid) {
+ /* global position setpoint valid, use it */
+ double sp_lat = global_pos_sp.lat * 1e-7;
+ double sp_lon = global_pos_sp.lon * 1e-7;
+ /* project global setpoint to local setpoint */
+ map_projection_project(sp_lat, sp_lon, &(local_pos_sp.x), &(local_pos_sp.y));
+
+ if (global_pos_sp.altitude_is_relative) {
+ local_pos_sp.z = -global_pos_sp.altitude;
+
+ } else {
+ local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude;
+ }
+
+ mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", sp_lat, sp_lon, local_pos_sp.x, local_pos_sp.y);
+
+ } else {
+ if (!local_pos_sp_valid) {
+ /* local position setpoint is invalid,
+ * use current position as setpoint for loiter */
+ local_pos_sp.x = local_pos.x;
+ local_pos_sp.y = local_pos.y;
+ local_pos_sp.z = local_pos.z;
+ }
+
+ mavlink_log_info(mavlink_fd, "[mpc] no global pos sp, loiter: %.2f, %.2f", local_pos_sp.x, local_pos_sp.y);
+ }
+
+ /* publish local position setpoint as projection of global position setpoint */
+ orb_publish(ORB_ID(vehicle_local_position_setpoint), local_pos_sp_pub, &local_pos_sp);
+ }
}
/* run position & altitude controllers, calculate velocity setpoint */
if (control_mode.flag_control_altitude_enabled) {
global_vel_sp.vz = pid_calculate(&z_pos_pid, local_pos_sp.z, local_pos.z, local_pos.vz - sp_move_rate[2], dt) + sp_move_rate[2];
+
} else {
+ reset_sp_z = true;
global_vel_sp.vz = 0.0f;
}
@@ -426,13 +477,14 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* limit horizontal speed */
float xy_vel_sp_norm = norm(global_vel_sp.vx, global_vel_sp.vy) / params.xy_vel_max;
+
if (xy_vel_sp_norm > 1.0f) {
global_vel_sp.vx /= xy_vel_sp_norm;
global_vel_sp.vy /= xy_vel_sp_norm;
}
} else {
- reset_sp_pos = true;
+ reset_sp_xy = true;
global_vel_sp.vx = 0.0f;
global_vel_sp.vy = 0.0f;
}
@@ -444,20 +496,44 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
if (control_mode.flag_control_climb_rate_enabled || control_mode.flag_control_velocity_enabled) {
/* run velocity controllers, calculate thrust vector with attitude-thrust compensation */
float thrust_sp[3] = { 0.0f, 0.0f, 0.0f };
- bool reset_integral = !control_mode.flag_armed;
+
if (control_mode.flag_control_climb_rate_enabled) {
- if (reset_integral) {
- thrust_pid_set_integral(&z_vel_pid, params.thr_min);
+ if (reset_int_z) {
+ reset_int_z = false;
+ float i = params.thr_min;
+
+ if (reset_int_z_manual) {
+ i = manual.throttle;
+
+ if (i < params.thr_min) {
+ i = params.thr_min;
+
+ } else if (i > params.thr_max) {
+ i = params.thr_max;
+ }
+ }
+
+ thrust_pid_set_integral(&z_vel_pid, -i);
+ mavlink_log_info(mavlink_fd, "[mpc] reset hovering thrust: %.2f", i);
}
+
thrust_sp[2] = thrust_pid_calculate(&z_vel_pid, global_vel_sp.vz, local_pos.vz, dt, att.R[2][2]);
att_sp.thrust = -thrust_sp[2];
+
+ } else {
+ /* reset thrust integral when altitude control enabled */
+ reset_int_z = true;
}
+
if (control_mode.flag_control_velocity_enabled) {
/* calculate thrust set point in NED frame */
- if (reset_integral) {
+ if (reset_int_xy) {
+ reset_int_xy = false;
pid_reset_integral(&xy_vel_pids[0]);
pid_reset_integral(&xy_vel_pids[1]);
+ mavlink_log_info(mavlink_fd, "[mpc] reset pos integral");
}
+
thrust_sp[0] = pid_calculate(&xy_vel_pids[0], global_vel_sp.vx, local_pos.vx, 0.0f, dt);
thrust_sp[1] = pid_calculate(&xy_vel_pids[1], global_vel_sp.vy, local_pos.vy, 0.0f, dt);
@@ -471,11 +547,15 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
if (tilt > params.tilt_max) {
tilt = params.tilt_max;
}
+
/* convert direction to body frame */
thrust_xy_dir -= att.yaw;
/* calculate roll and pitch */
att_sp.roll_body = sinf(thrust_xy_dir) * tilt;
att_sp.pitch_body = -cosf(thrust_xy_dir) * tilt / cosf(att_sp.roll_body);
+
+ } else {
+ reset_int_xy = true;
}
att_sp.timestamp = hrt_absolute_time();
@@ -483,14 +563,21 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* publish new attitude setpoint */
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
}
+
} else {
- reset_sp_alt = true;
- reset_sp_pos = true;
+ /* position controller disabled, reset setpoints */
+ reset_sp_z = true;
+ reset_sp_xy = true;
+ reset_int_z = true;
+ reset_int_xy = true;
+ global_pos_sp_reproject = true;
}
+ /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */
+ reset_int_z_manual = control_mode.flag_armed && control_mode.flag_control_manual_enabled && !control_mode.flag_control_climb_rate_enabled;
+
/* run at approximately 50 Hz */
usleep(20000);
-
}
warnx("stopped");
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 1094fd23b..0b09c9ea7 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.c
@@ -1,8 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -35,7 +34,7 @@
/*
* @file multirotor_pos_control_params.c
- *
+ *
* Parameters for multirotor_pos_control
*/
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 14a3de2e5..3ec85a364 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control_params.h
@@ -1,8 +1,7 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Tobias Naegeli <naegelit@student.ethz.ch>
- * Lorenz Meier <lm@inf.ethz.ch>
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -34,9 +33,9 @@
****************************************************************************/
/*
- * @file multirotor_position_control_params.h
- *
- * Parameters for position controller
+ * @file multirotor_pos_control_params.h
+ *
+ * Parameters for multirotor_pos_control
*/
#include <systemlib/param/param.h>
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c
index 81f938719..c0cfac880 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -508,6 +508,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (gps_valid) {
inertial_filter_correct(gps_corr[0][0], dt, x_est, 0, params.w_pos_gps_p);
inertial_filter_correct(gps_corr[1][0], dt, y_est, 0, params.w_pos_gps_p);
+
if (gps.vel_ned_valid && t < gps.timestamp_velocity + gps_timeout) {
inertial_filter_correct(gps_corr[0][1], dt, x_est, 1, params.w_pos_gps_v);
inertial_filter_correct(gps_corr[1][1], dt, y_est, 1, params.w_pos_gps_v);
@@ -554,6 +555,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* publish global position */
global_pos.valid = local_pos.global_xy;
+
if (local_pos.global_xy) {
double est_lat, est_lon;
map_projection_reproject(local_pos.x, local_pos.y, &est_lat, &est_lon);
@@ -561,21 +563,26 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
global_pos.lon = (int32_t)(est_lon * 1e7);
global_pos.time_gps_usec = gps.time_gps_usec;
}
+
/* set valid values even if position is not valid */
if (local_pos.v_xy_valid) {
global_pos.vx = local_pos.vx;
global_pos.vy = local_pos.vy;
global_pos.hdg = atan2f(local_pos.vy, local_pos.vx);
}
+
if (local_pos.z_valid) {
global_pos.relative_alt = -local_pos.z;
}
+
if (local_pos.global_z) {
global_pos.alt = local_pos.ref_alt - local_pos.z;
}
+
if (local_pos.v_z_valid) {
global_pos.vz = local_pos.vz;
}
+
global_pos.timestamp = t;
orb_publish(ORB_ID(vehicle_global_position), vehicle_global_position_pub, &global_pos);
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index dd98f65a9..d99892fe2 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -259,7 +259,7 @@ static const struct log_format_s log_formats[] = {
LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"),
LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"),
LOG_FORMAT(SENS, "ffff", "BaroPres,BaroAlt,BaroTemp,DiffPres"),
- LOG_FORMAT(LPOS, "fffffffLLf", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt"),
+ LOG_FORMAT(LPOS, "ffffffLLf", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt"),
LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"),
LOG_FORMAT(GPS, "QBffLLfffff", "GPSTime,FixType,EPH,EPV,Lat,Lon,Alt,VelN,VelE,VelD,Cog"),
LOG_FORMAT(ATTC, "ffff", "Roll,Pitch,Yaw,Thrust"),
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 67aeac372..4f4db5dbc 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -61,7 +61,7 @@
*/
struct vehicle_control_mode_s
{
- uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
+ uint16_t counter; /**< incremented by the writing thread every time new data is stored */
uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
bool flag_armed;
@@ -73,11 +73,9 @@ struct vehicle_control_mode_s
bool flag_control_manual_enabled; /**< true if manual input is mixed in */
bool flag_control_offboard_enabled; /**< true if offboard control input is on */
- // XXX shouldn't be necessairy
- //bool flag_auto_enabled;
bool flag_control_rates_enabled; /**< true if rates are stabilized */
bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool flag_control_velocity_enabled; /**< true if horisontal speed (implies direction) is controlled */
+ bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
bool flag_control_position_enabled; /**< true if position is controlled */
bool flag_control_altitude_enabled; /**< true if altitude is controlled */
bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */