aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/commander.cpp22
-rw-r--r--src/modules/commander/state_machine_helper.cpp15
-rw-r--r--src/modules/multirotor_pos_control/multirotor_pos_control.c68
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_main.c479
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.c9
-rw-r--r--src/modules/position_estimator_inav/position_estimator_inav_params.h2
-rw-r--r--src/modules/sdlog2/sdlog2.c2
-rw-r--r--src/modules/sdlog2/sdlog2_messages.h4
-rw-r--r--src/modules/sensors/sensor_params.c1
-rw-r--r--src/modules/sensors/sensors.cpp17
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h1
-rw-r--r--src/modules/uORB/topics/rc_channels.h29
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h1
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h5
-rw-r--r--src/modules/uORB/topics/vehicle_status.h14
15 files changed, 460 insertions, 209 deletions
diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp
index 0c3546b95..45a789db4 100644
--- a/src/modules/commander/commander.cpp
+++ b/src/modules/commander/commander.cpp
@@ -864,6 +864,7 @@ int commander_thread_main(int argc, char *argv[])
/* update condition_local_position_valid and condition_local_altitude_valid */
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid, &(status.condition_local_position_valid), &status_changed);
check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed);
+ check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.v_xy_valid, &(status.condition_local_velocity_valid), &status_changed);
if (status.condition_local_altitude_valid) {
if (status.condition_landed != local_position.landed) {
@@ -1409,13 +1410,13 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
/* land switch */
if (!isfinite(sp_man->return_switch)) {
- current_status->return_switch = RETURN_SWITCH_NONE;
+ current_status->return_switch = SWITCH_OFF;
} else if (sp_man->return_switch > STICK_ON_OFF_LIMIT) {
- current_status->return_switch = RETURN_SWITCH_RETURN;
+ current_status->return_switch = SWITCH_ON;
} else {
- current_status->return_switch = RETURN_SWITCH_NONE;
+ current_status->return_switch = SWITCH_OFF;
}
/* assisted switch */
@@ -1429,7 +1430,7 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
current_status->assisted_switch = ASSISTED_SWITCH_SEATBELT;
}
- /* mission switch */
+ /* mission switch */
if (!isfinite(sp_man->mission_switch)) {
current_status->mission_switch = MISSION_SWITCH_MISSION;
@@ -1439,6 +1440,17 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta
} else {
current_status->mission_switch = MISSION_SWITCH_MISSION;
}
+
+ /* distance bottom switch */
+ if (!isfinite(sp_man->dist_bottom_switch)) {
+ current_status->dist_bottom_switch = SWITCH_OFF;
+
+ } else if (sp_man->dist_bottom_switch > STICK_ON_OFF_LIMIT) {
+ current_status->dist_bottom_switch = SWITCH_ON;
+
+ } else {
+ current_status->dist_bottom_switch = SWITCH_OFF;
+ }
}
transition_result_t
@@ -1559,7 +1571,7 @@ check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_c
/* switch to AUTO mode */
if (status->rc_signal_found_once && !status->rc_signal_lost) {
/* act depending on switches when manual control enabled */
- if (status->return_switch == RETURN_SWITCH_RETURN) {
+ if (status->return_switch == SWITCH_ON) {
/* RTL */
res = navigation_state_transition(status, NAVIGATION_STATE_AUTO_RTL, control_mode);
diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp
index efe12be57..116c53f2f 100644
--- a/src/modules/commander/state_machine_helper.cpp
+++ b/src/modules/commander/state_machine_helper.cpp
@@ -248,9 +248,8 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m
case MAIN_STATE_EASY:
- /* need at minimum local position estimate */
- if (current_state->condition_local_position_valid ||
- current_state->condition_global_position_valid) {
+ /* need at minimum local velocity estimate */
+ if (current_state->condition_local_velocity_valid) {
ret = TRANSITION_CHANGED;
}
@@ -435,6 +434,16 @@ navigation_state_transition(struct vehicle_status_s *status, navigation_state_t
}
}
+ bool use_dist_bottom_prev = control_mode->flag_use_dist_bottom;
+ control_mode->flag_use_dist_bottom = control_mode->flag_control_manual_enabled &&
+ control_mode->flag_control_altitude_enabled && status->dist_bottom_switch == SWITCH_ON;
+
+ if (ret == TRANSITION_NOT_CHANGED && control_mode->flag_use_dist_bottom != use_dist_bottom_prev) {
+ // TODO really, navigation state not changed, set this to force publishing control_mode
+ ret = TRANSITION_CHANGED;
+ navigation_state_changed = true;
+ }
+
return ret;
}
diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c
index 36dd370fb..f283a1eb4 100644
--- a/src/modules/multirotor_pos_control/multirotor_pos_control.c
+++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c
@@ -133,8 +133,14 @@ int multirotor_pos_control_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "stop")) {
- warnx("stop");
- thread_should_exit = true;
+ if (thread_running) {
+ warnx("stop");
+ thread_should_exit = true;
+
+ } else {
+ warnx("app not started");
+ }
+
exit(0);
}
@@ -223,14 +229,16 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
bool reset_auto_sp_xy = true;
bool reset_auto_sp_z = true;
bool reset_takeoff_sp = true;
+ bool reset_z_sp_dist = false;
+ float surface_offset = 0.0f; // Z of ground level
+ float z_sp_dist = 0.0f; // distance to ground setpoint (positive)
hrt_abstime t_prev = 0;
const float alt_ctl_dz = 0.2f;
const float pos_ctl_dz = 0.05f;
- float ref_alt = 0.0f;
- hrt_abstime ref_alt_t = 0;
uint64_t local_ref_timestamp = 0;
+ uint64_t surface_bottom_timestamp = 0;
PID_t xy_pos_pids[2];
PID_t xy_vel_pids[2];
@@ -244,7 +252,6 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
parameters_init(&params_h);
parameters_update(&params_h, &params);
-
for (int i = 0; i < 2; i++) {
pid_init(&(xy_pos_pids[i]), params.xy_p, 0.0f, params.xy_d, 1.0f, 0.0f, PID_MODE_DERIVATIV_SET, 0.02f);
pid_init(&(xy_vel_pids[i]), params.xy_vel_p, params.xy_vel_i, params.xy_vel_d, 1.0f, params.tilt_max, PID_MODE_DERIVATIV_CALC_NO_SP, 0.02f);
@@ -325,11 +332,12 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
t_prev = t;
+ orb_copy(ORB_ID(vehicle_local_position), local_pos_sub, &local_pos);
+
if (control_mode.flag_control_altitude_enabled || control_mode.flag_control_velocity_enabled || control_mode.flag_control_position_enabled) {
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);
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;
@@ -338,32 +346,48 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
if (control_mode.flag_control_manual_enabled) {
/* 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 - ref_alt;
- }
-
- ref_alt_t = local_pos.ref_timestamp;
- ref_alt = local_pos.ref_alt;
+ //if (local_pos.ref_timestamp != ref_prev_t) {
+ /* reference alt changed, don't follow large ground level changes in manual flight */
+ //local_pos_sp.z += local_pos.ref_alt - ref_alt_prev;
// TODO also correct XY setpoint
- }
+ //}
- /* reset setpoints to current position if needed */
if (control_mode.flag_control_altitude_enabled) {
+ /* reset setpoints to current position if needed */
if (reset_man_sp_z) {
reset_man_sp_z = false;
local_pos_sp.z = local_pos.z;
+ reset_z_sp_dist = true;
mavlink_log_info(mavlink_fd, "[mpc] reset alt sp: %.2f", (double) - local_pos_sp.z);
}
+ /* if distance to surface is available, use it */
+ if (control_mode.flag_use_dist_bottom && local_pos.dist_bottom_valid) {
+ if (reset_z_sp_dist) {
+ reset_z_sp_dist = false;
+ surface_offset = local_pos.z + local_pos.dist_bottom;
+ z_sp_dist = -local_pos_sp.z + surface_offset;
+ mavlink_log_info(mavlink_fd, "[mpc] surface offset: %.2f", surface_offset);
+ } else {
+ if (local_pos.surface_bottom_timestamp != surface_bottom_timestamp) {
+ /* new surface level */
+ z_sp_dist += local_pos.z + local_pos.dist_bottom - surface_offset;
+ }
+ surface_offset = local_pos.z + local_pos.dist_bottom;
+ }
+ /* move altitude setpoint according to ground distance */
+ local_pos_sp.z = surface_offset - z_sp_dist;
+ }
+
/* 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) {
sp_move_rate[2] = -z_sp_ctl * params.z_vel_max;
local_pos_sp.z += sp_move_rate[2] * dt;
+ z_sp_dist -= sp_move_rate[2] * dt; // this will have effect only if distance sensor used
+ // TODO add z_sp_dist correction here
if (local_pos_sp.z > local_pos.z + z_sp_offs_max) {
local_pos_sp.z = local_pos.z + z_sp_offs_max;
@@ -471,6 +495,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
} else {
local_pos_sp.z = local_pos.ref_alt - global_pos_sp.altitude;
}
+
att_sp.yaw_body = global_pos_sp.yaw;
mavlink_log_info(mavlink_fd, "[mpc] new sp: %.7f, %.7f (%.2f, %.2f)", (double)sp_lat, sp_lon, (double)local_pos_sp.x, (double)local_pos_sp.y);
@@ -672,8 +697,15 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[])
/* 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);
+ /* reset distance setpoint if distance is not available */
+ if (!local_pos.dist_bottom_valid) {
+ reset_z_sp_dist = true;
+ }
+
+ surface_bottom_timestamp = local_pos.surface_bottom_timestamp;
+
+ /* run at approximately 100 Hz */
+ usleep(10000);
}
warnx("stopped");
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 10007bf96..8cd161075 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_main.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c
@@ -76,10 +76,14 @@ static bool thread_running = false; /**< Deamon status flag */
static int position_estimator_inav_task; /**< Handle of deamon task / thread */
static bool verbose_mode = false;
-static const hrt_abstime gps_timeout = 1000000; // GPS timeout = 1s
-static const hrt_abstime flow_timeout = 1000000; // optical flow timeout = 1s
+static const hrt_abstime gps_topic_timeout = 1000000; // GPS topic timeout = 1s
+static const hrt_abstime flow_topic_timeout = 1000000; // optical flow topic timeout = 1s
+static const hrt_abstime sonar_timeout = 150000; // sonar timeout = 150ms
+static const hrt_abstime sonar_valid_timeout = 1000000; // assume that altitude == distance to surface during this time
+static const hrt_abstime flow_valid_timeout = 1000000; // assume that altitude == distance to surface during this time
static const uint32_t updates_counter_len = 1000000;
-static const uint32_t pub_interval = 4000; // limit publish rate to 250 Hz
+static const uint32_t pub_interval = 10000; // limit publish rate to 100 Hz
+static const float max_flow = 1.0f; // max flow value that can be used, rad/s
__EXPORT int position_estimator_inav_main(int argc, char *argv[]);
@@ -95,8 +99,7 @@ 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");
+ fprintf(stderr, "usage: position_estimator_inav {start|stop|status} [-v]\n\n");
exit(1);
}
@@ -115,7 +118,7 @@ int position_estimator_inav_main(int argc, char *argv[])
if (!strcmp(argv[1], "start")) {
if (thread_running) {
- printf("position_estimator_inav already running\n");
+ warnx("already running");
/* this is not an error */
exit(0);
}
@@ -135,16 +138,23 @@ int position_estimator_inav_main(int argc, char *argv[])
}
if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
+ if (thread_running) {
+ warnx("stop");
+ thread_should_exit = true;
+
+ } else {
+ warnx("app not started");
+ }
+
exit(0);
}
if (!strcmp(argv[1], "status")) {
if (thread_running) {
- printf("\tposition_estimator_inav is running\n");
+ warnx("app is running");
} else {
- printf("\tposition_estimator_inav not started\n");
+ warnx("app not started");
}
exit(0);
@@ -159,27 +169,70 @@ int position_estimator_inav_main(int argc, char *argv[])
****************************************************************************/
int position_estimator_inav_thread_main(int argc, char *argv[])
{
- warnx("started.");
+ 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 = 200;
- float baro_alt0 = 0.0f; /* to determine while start up */
+ float baro_offset = 0.0f; // baro offset for reference altitude, initialized only once
+ float surface_offset = 0.0f; // ground level offset from reference altitude
float alt_avg = 0.0f;
bool landed = true;
hrt_abstime landed_time = 0;
+
bool flag_armed = false;
uint32_t accel_counter = 0;
uint32_t baro_counter = 0;
+ bool ref_xy_inited = false;
+ hrt_abstime ref_xy_init_start = 0;
+ const hrt_abstime ref_xy_init_delay = 1000000; // wait for 1s after 3D fix
+
+ uint16_t accel_updates = 0;
+ uint16_t baro_updates = 0;
+ uint16_t gps_updates = 0;
+ uint16_t attitude_updates = 0;
+ uint16_t flow_updates = 0;
+
+ hrt_abstime updates_counter_start = hrt_absolute_time();
+ hrt_abstime pub_last = hrt_absolute_time();
+
+ hrt_abstime t_prev = 0;
+
+ /* acceleration in NED frame */
+ float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G };
+
+ /* 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 accel_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
+ 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)
+ };
+ float sonar_corr = 0.0f;
+ float sonar_corr_filtered = 0.0f;
+
+ float flow_corr[] = { 0.0f, 0.0f }; // X, Y
+ float flow_w = 0.0f;
+
+ float sonar_prev = 0.0f;
+ hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
+ hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered)
+ hrt_abstime flow_valid_time = 0; // time of last flow measurement used for correction (filtered)
+
+ bool gps_valid = false; // GPS is valid
+ bool sonar_valid = false; // sonar is valid
+ bool flow_valid = false; // flow is valid
+ bool flow_accurate = false; // flow should be accurate (this flag not updated if flow_valid == false)
+
/* declare and safely initialize all structs */
struct actuator_controls_s actuator;
memset(&actuator, 0, sizeof(actuator));
@@ -247,15 +300,15 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
/* mean calculation over several measurements */
if (baro_init_cnt < baro_init_num) {
- baro_alt0 += sensor.baro_alt_meter;
+ baro_offset += 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.ref_alt = baro_alt0;
+ baro_offset /= (float) baro_init_cnt;
+ warnx("init ref: alt=%.3f", baro_offset);
+ mavlink_log_info(mavlink_fd, "[inav] init ref: alt=%.3f", baro_offset);
+ local_pos.ref_alt = baro_offset;
local_pos.ref_timestamp = hrt_absolute_time();
local_pos.z_valid = true;
local_pos.v_z_valid = true;
@@ -266,56 +319,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
- bool ref_xy_inited = false;
- hrt_abstime ref_xy_init_start = 0;
- const hrt_abstime ref_xy_init_delay = 5000000; // wait for 5s after 3D fix
-
- hrt_abstime t_prev = 0;
-
- uint16_t accel_updates = 0;
- uint16_t baro_updates = 0;
- uint16_t gps_updates = 0;
- uint16_t attitude_updates = 0;
- uint16_t flow_updates = 0;
-
- hrt_abstime updates_counter_start = hrt_absolute_time();
- hrt_abstime pub_last = hrt_absolute_time();
-
- /* acceleration in NED frame */
- float accel_NED[3] = { 0.0f, 0.0f, -CONSTANTS_ONE_G };
-
- /* 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 accel_bias[] = { 0.0f, 0.0f, 0.0f }; // body frame
- 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)
- };
- float sonar_corr = 0.0f;
- float sonar_corr_filtered = 0.0f;
- float flow_corr[] = { 0.0f, 0.0f }; // X, Y
-
- float sonar_prev = 0.0f;
- hrt_abstime sonar_time = 0;
-
/* main loop */
- struct pollfd fds[7] = {
- { .fd = parameter_update_sub, .events = POLLIN },
- { .fd = actuator_sub, .events = POLLIN },
- { .fd = armed_sub, .events = POLLIN },
+ struct pollfd fds[1] = {
{ .fd = vehicle_attitude_sub, .events = POLLIN },
- { .fd = sensor_combined_sub, .events = POLLIN },
- { .fd = optical_flow_sub, .events = POLLIN },
- { .fd = vehicle_gps_position_sub, .events = POLLIN }
};
- if (!thread_should_exit) {
- warnx("main loop started.");
- }
-
while (!thread_should_exit) {
- int ret = poll(fds, 7, 10); // wait maximal this 10 ms = 100 Hz minimum rate
+ int ret = poll(fds, 1, 20); // wait maximal 20 ms = 50 Hz minimum rate
hrt_abstime t = hrt_absolute_time();
if (ret < 0) {
@@ -325,39 +335,58 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
continue;
} else if (ret > 0) {
+ /* act on attitude updates */
+
+ /* vehicle attitude */
+ orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
+ attitude_updates++;
+
+ bool updated;
+
/* parameter update */
- if (fds[0].revents & POLLIN) {
- /* read from param to clear updated flag */
+ orb_check(parameter_update_sub, &updated);
+
+ if (updated) {
struct parameter_update_s update;
- orb_copy(ORB_ID(parameter_update), parameter_update_sub,
- &update);
- /* update parameters */
+ orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
parameters_update(&pos_inav_param_handles, &params);
}
/* actuator */
- if (fds[1].revents & POLLIN) {
+ orb_check(actuator_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_sub, &actuator);
}
/* armed */
- if (fds[2].revents & POLLIN) {
+ orb_check(armed_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
- }
- /* vehicle attitude */
- if (fds[3].revents & POLLIN) {
- orb_copy(ORB_ID(vehicle_attitude), vehicle_attitude_sub, &att);
- attitude_updates++;
+ /* reset ground level on arm if sonar is invalid */
+ if (armed.armed && !flag_armed) {
+ flag_armed = armed.armed;
+ baro_offset -= z_est[0];
+ z_est[0] = 0.0f;
+ alt_avg = 0.0f;
+ local_pos.ref_alt = baro_offset;
+ local_pos.ref_timestamp = t;
+ }
}
/* sensor combined */
- if (fds[4].revents & POLLIN) {
+ orb_check(sensor_combined_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor);
if (sensor.accelerometer_counter > accel_counter) {
if (att.R_valid) {
/* correct accel bias, now only for Z */
+ sensor.accelerometer_m_s2[0] -= accel_bias[0];
+ sensor.accelerometer_m_s2[1] -= accel_bias[1];
sensor.accelerometer_m_s2[2] -= accel_bias[2];
/* transform acceleration vector from body frame to NED frame */
@@ -382,78 +411,150 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
if (sensor.baro_counter > baro_counter) {
- baro_corr = - sensor.baro_alt_meter - z_est[0];
+ baro_corr = baro_offset - sensor.baro_alt_meter - z_est[0];
baro_counter = sensor.baro_counter;
baro_updates++;
}
}
/* optical flow */
- if (fds[5].revents & POLLIN) {
+ orb_check(optical_flow_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow);
- if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && (flow.ground_distance_m != sonar_prev || t - sonar_time < 150000)) {
- if (flow.ground_distance_m != sonar_prev) {
- sonar_time = t;
- sonar_prev = flow.ground_distance_m;
- sonar_corr = -flow.ground_distance_m - z_est[0];
- sonar_corr_filtered += (sonar_corr - sonar_corr_filtered) * params.sonar_filt;
-
- if (fabsf(sonar_corr) > params.sonar_err) {
- // correction is too large: spike or new ground level?
- if (fabsf(sonar_corr - sonar_corr_filtered) > params.sonar_err) {
- // spike detected, ignore
- sonar_corr = 0.0f;
-
- } else {
- // new ground level
- baro_alt0 += sonar_corr;
- mavlink_log_info(mavlink_fd, "[inav] new home: alt = %.3f", baro_alt0);
- local_pos.ref_alt = baro_alt0;
- local_pos.ref_timestamp = hrt_absolute_time();
- z_est[0] += sonar_corr;
- sonar_corr = 0.0f;
- sonar_corr_filtered = 0.0f;
- }
+ if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && att.R[2][2] > 0.7 && flow.ground_distance_m != sonar_prev) {
+ sonar_time = t;
+ sonar_prev = flow.ground_distance_m;
+ sonar_corr = flow.ground_distance_m + surface_offset + z_est[0];
+ sonar_corr_filtered += (sonar_corr - sonar_corr_filtered) * params.sonar_filt;
+
+ if (fabsf(sonar_corr) > params.sonar_err) {
+ /* correction is too large: spike or new ground level? */
+ if (fabsf(sonar_corr - sonar_corr_filtered) > params.sonar_err) {
+ /* spike detected, ignore */
+ sonar_corr = 0.0f;
+ sonar_valid = false;
+
+ } else {
+ /* new ground level */
+ surface_offset -= sonar_corr;
+ sonar_corr = 0.0f;
+ sonar_corr_filtered = 0.0f;
+ sonar_valid_time = t;
+ sonar_valid = true;
+ local_pos.surface_bottom_timestamp = t;
+ mavlink_log_info(mavlink_fd, "[inav] new surface level: %.2f", surface_offset);
+ }
+
+ } else {
+ sonar_valid_time = t;
+ sonar_valid = true;
+ }
+ }
+
+ float flow_q = flow.quality / 255.0f;
+
+ if (z_est[0] < - 0.31f && flow_q > params.flow_q_min && t < sonar_valid_time + sonar_valid_timeout && att.R[2][2] > 0.7) {
+ /* distance to surface */
+ float flow_dist = (- z_est[0] - surface_offset) / att.R[2][2];
+ /* check if flow if too large for accurate measurements */
+ /* calculate estimated velocity in body frame */
+ float body_v_est[2] = { 0.0f, 0.0f };
+
+ for (int i = 0; i < 2; i++) {
+ body_v_est[i] = att.R[0][i] * x_est[1] + att.R[1][i] * y_est[1] + att.R[2][i] * z_est[1];
+ }
+
+ /* set this flag if flow should be accurate according to current velocity and attitude rate estimate */
+ flow_accurate = fabsf(body_v_est[1] / flow_dist - att.rollspeed) < max_flow &&
+ fabsf(body_v_est[0] / flow_dist + att.pitchspeed) < max_flow;
+
+ /* convert raw flow to angular flow */
+ float flow_ang[2];
+ flow_ang[0] = flow.flow_raw_x * params.flow_k;
+ flow_ang[1] = flow.flow_raw_y * params.flow_k;
+ /* flow measurements vector */
+ float flow_m[3];
+ flow_m[0] = -flow_ang[0] * flow_dist;
+ flow_m[1] = -flow_ang[1] * flow_dist;
+ flow_m[2] = z_est[1];
+ /* velocity in NED */
+ float flow_v[2] = { 0.0f, 0.0f };
+
+ /* project measurements vector to NED basis, skip Z component */
+ for (int i = 0; i < 2; i++) {
+ for (int j = 0; j < 3; j++) {
+ flow_v[i] += att.R[i][j] * flow_m[j];
}
}
+ /* velocity correction */
+ flow_corr[0] = flow_v[0] - x_est[1];
+ flow_corr[1] = flow_v[1] - y_est[1];
+ /* adjust correction weight */
+ float flow_q_weight = (flow_q - params.flow_q_min) / (1.0f - params.flow_q_min);
+ flow_w = att.R[2][2] * flow_q_weight;
+ /* if flow is not accurate, lower weight for it */
+ // TODO make this more fuzzy
+ if (!flow_accurate)
+ flow_w *= 0.2f;
+ flow_valid = true;
+ flow_valid_time = t;
+
} else {
- sonar_corr = 0.0f;
+ flow_w = 0.0f;
+ flow_valid = false;
}
flow_updates++;
}
/* vehicle GPS position */
- if (fds[6].revents & POLLIN) {
+ orb_check(vehicle_gps_position_sub, &updated);
+
+ if (updated) {
orb_copy(ORB_ID(vehicle_gps_position), vehicle_gps_position_sub, &gps);
- if (gps.fix_type >= 3 && t < gps.timestamp_position + gps_timeout) {
+ if (gps.fix_type >= 3) {
+ /* hysteresis for GPS quality */
+ if (gps_valid) {
+ if (gps.eph_m > 10.0f) {
+ gps_valid = false;
+ mavlink_log_info(mavlink_fd, "[inav] GPS signal lost");
+ }
+
+ } else {
+ if (gps.eph_m < 5.0f) {
+ gps_valid = true;
+ mavlink_log_info(mavlink_fd, "[inav] GPS signal found");
+ }
+ }
+
+ } else {
+ gps_valid = false;
+ }
+
+ if (gps_valid) {
/* initialize reference position if needed */
if (!ref_xy_inited) {
- /* require EPH < 10m */
- if (gps.eph_m < 10.0f) {
- if (ref_xy_init_start == 0) {
- ref_xy_init_start = t;
-
- } else if (t > ref_xy_init_start + ref_xy_init_delay) {
- ref_xy_inited = true;
- /* reference GPS position */
- double lat = gps.lat * 1e-7;
- double lon = gps.lon * 1e-7;
-
- local_pos.ref_lat = gps.lat;
- local_pos.ref_lon = gps.lon;
- local_pos.ref_timestamp = t;
-
- /* initialize projection */
- map_projection_init(lat, lon);
- warnx("init GPS: lat = %.10f, lon = %.10f", lat, lon);
- mavlink_log_info(mavlink_fd, "[inav] init GPS: %.7f, %.7f", lat, lon);
- }
- } else {
- ref_xy_init_start = 0;
+ if (ref_xy_init_start == 0) {
+ ref_xy_init_start = t;
+
+ } else if (t > ref_xy_init_start + ref_xy_init_delay) {
+ ref_xy_inited = true;
+ /* reference GPS position */
+ double lat = gps.lat * 1e-7;
+ double lon = gps.lon * 1e-7;
+
+ local_pos.ref_lat = gps.lat;
+ local_pos.ref_lon = gps.lon;
+ local_pos.ref_timestamp = t;
+
+ /* initialize projection */
+ map_projection_init(lat, lon);
+ warnx("init ref: lat=%.7f, lon=%.7f", lat, lon);
+ mavlink_log_info(mavlink_fd, "[inav] init ref: lat=%.7f, lon=%.7f", lat, lon);
}
}
@@ -486,76 +587,131 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
}
}
- /* end of poll return value check */
+ /* check for timeout on FLOW topic */
+ if ((flow_valid || sonar_valid) && t > flow.timestamp + flow_topic_timeout) {
+ flow_valid = false;
+ sonar_valid = false;
+ warnx("FLOW timeout");
+ mavlink_log_info(mavlink_fd, "[inav] FLOW timeout");
+ }
+
+ /* check for timeout on GPS topic */
+ if (gps_valid && t > gps.timestamp_position + gps_topic_timeout) {
+ gps_valid = false;
+ warnx("GPS timeout");
+ mavlink_log_info(mavlink_fd, "[inav] GPS timeout");
+ }
+
+ /* check for sonar measurement timeout */
+ if (sonar_valid && t > sonar_time + sonar_timeout) {
+ sonar_corr = 0.0f;
+ sonar_valid = false;
+ }
float dt = t_prev > 0 ? (t - t_prev) / 1000000.0f : 0.0f;
t_prev = t;
- /* reset ground level on arm */
- if (armed.armed && !flag_armed) {
- baro_alt0 -= z_est[0];
- z_est[0] = 0.0f;
- local_pos.ref_alt = baro_alt0;
- local_pos.ref_timestamp = hrt_absolute_time();
- mavlink_log_info(mavlink_fd, "[inav] new home on arm: alt = %.3f", baro_alt0);
+ /* use GPS if it's valid and reference position initialized */
+ bool use_gps = ref_xy_inited && gps_valid;
+ /* use flow if it's valid and (accurate or no GPS available) */
+ bool use_flow = flow_valid && (flow_accurate || !use_gps);
+ /* try to estimate xy even if no absolute position source available,
+ * if using optical flow velocity will be valid */
+ bool can_estimate_xy = use_gps || use_flow || (t < flow_valid_time + flow_valid_timeout);
+
+ /* baro offset correction if sonar available,
+ * don't touch reference altitude, local_pos.ref_alt != baro_offset after this */
+ if (sonar_valid) {
+ surface_offset -= sonar_corr * params.w_alt_sonar * dt;
}
- /* accel bias correction, now only for Z
- * not strictly correct, but stable and works */
- accel_bias[2] += (accel_NED[2] + CONSTANTS_ONE_G) * params.w_acc_bias * dt;
+ /* accelerometer bias correction */
+ float accel_bias_corr[3] = { 0.0f, 0.0f, 0.0f };
+
+ if (use_gps) {
+ accel_bias_corr[0] -= gps_corr[0][0] * params.w_pos_gps_p * params.w_pos_gps_p;
+ accel_bias_corr[0] -= gps_corr[0][1] * params.w_pos_gps_v;
+ accel_bias_corr[1] -= gps_corr[1][0] * params.w_pos_gps_p * params.w_pos_gps_p;
+ accel_bias_corr[1] -= gps_corr[1][1] * params.w_pos_gps_v;
+ }
+
+ if (use_flow) {
+ accel_bias_corr[0] -= flow_corr[0] * params.w_pos_flow;
+ accel_bias_corr[1] -= flow_corr[1] * params.w_pos_flow;
+ }
+
+ accel_bias_corr[2] -= baro_corr * params.w_alt_baro * params.w_alt_baro;
+
+ /* transform error vector from NED frame to body frame */
+ for (int i = 0; i < 3; i++) {
+ float c = 0.0f;
+
+ for (int j = 0; j < 3; j++) {
+ c += att.R[j][i] * accel_bias_corr[j];
+ }
+
+ accel_bias[i] += c * params.w_acc_bias * dt;
+ }
/* inertial filter prediction for altitude */
inertial_filter_predict(dt, z_est);
/* inertial filter correction for altitude */
- baro_alt0 += sonar_corr * params.w_alt_sonar * dt;
- inertial_filter_correct(baro_corr + baro_alt0, dt, z_est, 0, params.w_alt_baro);
- inertial_filter_correct(sonar_corr, dt, z_est, 0, params.w_alt_sonar);
+ 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);
- bool gps_valid = ref_xy_inited && gps.fix_type >= 3 && t < gps.timestamp_position + gps_timeout;
- bool flow_valid = false; // TODO implement opt flow
-
- /* try to estimate xy even if no absolute position source available,
- * if using optical flow velocity will be correct in this case */
- bool can_estimate_xy = gps_valid || flow_valid;
-
if (can_estimate_xy) {
/* inertial filter prediction for position */
inertial_filter_predict(dt, x_est);
inertial_filter_predict(dt, y_est);
+ if (!isfinite(x_est[0]) || !isfinite(y_est[0])) {
+ warnx("BAD ESTIMATE AFTER PREDICTION %.6f x: %.3f %.3f %.3f y: %.3f %.3f %.3f", dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2]);
+ thread_should_exit = true;
+ }
+
/* inertial filter correction for position */
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 (gps_valid) {
+ if (use_flow) {
+ inertial_filter_correct(flow_corr[0], dt, x_est, 1, params.w_pos_flow * flow_w);
+ inertial_filter_correct(flow_corr[1], dt, y_est, 1, params.w_pos_flow * flow_w);
+ }
+
+ if (use_gps) {
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) {
+ if (gps.vel_ned_valid && t < gps.timestamp_velocity + gps_topic_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);
}
}
+
+ if (!isfinite(x_est[0]) || !isfinite(y_est[0])) {
+ warnx("BAD ESTIMATE AFTER CORRECTION dt: %.6f x: %.3f %.3f %.3f y: %.3f %.3f %.3f", dt, x_est[0], x_est[1], x_est[2], y_est[0], y_est[1], y_est[2]);
+ warnx("BAD ESTIMATE AFTER CORRECTION acc: %.3f %.3f gps x: %.3f %.3f gps y: %.3f %.3f", accel_corr[0], accel_corr[1], gps_corr[0][0], gps_corr[0][1], gps_corr[1][0], gps_corr[1][1]);
+ thread_should_exit = true;
+ }
}
/* detect land */
- alt_avg += (z_est[0] - alt_avg) * dt / params.land_t;
- float alt_disp = z_est[0] - alt_avg;
- alt_disp = alt_disp * alt_disp;
+ alt_avg += (- z_est[0] - alt_avg) * dt / params.land_t;
+ float alt_disp2 = - z_est[0] - alt_avg;
+ alt_disp2 = alt_disp2 * alt_disp2;
float land_disp2 = params.land_disp * params.land_disp;
/* get actual thrust output */
float thrust = armed.armed ? actuator.control[3] : 0.0f;
if (landed) {
- if (alt_disp > land_disp2 && thrust > params.land_thr) {
+ if (alt_disp2 > land_disp2 && thrust > params.land_thr) {
landed = false;
landed_time = 0;
}
} else {
- if (alt_disp < land_disp2 && thrust < params.land_thr) {
+ if (alt_disp2 < land_disp2 && thrust < params.land_thr) {
if (landed_time == 0) {
landed_time = t; // land detected first time
@@ -594,10 +750,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (t > pub_last + pub_interval) {
pub_last = t;
/* publish local position */
- local_pos.timestamp = t;
- local_pos.xy_valid = can_estimate_xy && gps_valid;
+ local_pos.xy_valid = can_estimate_xy && use_gps;
local_pos.v_xy_valid = can_estimate_xy;
- local_pos.xy_global = local_pos.xy_valid && gps_valid; // will make sense when local position sources (e.g. vicon) will be implemented
+ local_pos.xy_global = local_pos.xy_valid && use_gps; // will make sense when local position sources (e.g. vicon) will be implemented
local_pos.x = x_est[0];
local_pos.vx = x_est[1];
local_pos.y = y_est[0];
@@ -606,6 +761,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
local_pos.vz = z_est[1];
local_pos.landed = landed;
local_pos.yaw = att.yaw;
+ local_pos.dist_bottom_valid = t < sonar_valid_time + sonar_valid_timeout;
+ if (local_pos.dist_bottom_valid) {
+ local_pos.dist_bottom = -z_est[0] - surface_offset;
+ }
+
+ local_pos.timestamp = t;
orb_publish(ORB_ID(vehicle_local_position), vehicle_local_position_pub, &local_pos);
@@ -637,17 +798,17 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
if (local_pos.v_z_valid) {
global_pos.vz = local_pos.vz;
}
+
global_pos.yaw = local_pos.yaw;
global_pos.timestamp = t;
orb_publish(ORB_ID(vehicle_global_position), vehicle_global_position_pub, &global_pos);
}
- flag_armed = armed.armed;
}
- warnx("exiting.");
- mavlink_log_info(mavlink_fd, "[inav] exiting");
+ warnx("stopped");
+ mavlink_log_info(mavlink_fd, "[inav] stopped");
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
index 4f9ddd009..b3c32b180 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.c
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c
@@ -41,14 +41,15 @@
#include "position_estimator_inav_params.h"
PARAM_DEFINE_FLOAT(INAV_W_ALT_BARO, 0.5f);
-PARAM_DEFINE_FLOAT(INAV_W_ALT_ACC, 50.0f);
+PARAM_DEFINE_FLOAT(INAV_W_ALT_ACC, 20.0f);
PARAM_DEFINE_FLOAT(INAV_W_ALT_SONAR, 3.0f);
PARAM_DEFINE_FLOAT(INAV_W_POS_GPS_P, 1.0f);
PARAM_DEFINE_FLOAT(INAV_W_POS_GPS_V, 2.0f);
PARAM_DEFINE_FLOAT(INAV_W_POS_ACC, 10.0f);
-PARAM_DEFINE_FLOAT(INAV_W_POS_FLOW, 0.0f);
+PARAM_DEFINE_FLOAT(INAV_W_POS_FLOW, 5.0f);
PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.0f);
-PARAM_DEFINE_FLOAT(INAV_FLOW_K, 1.0f);
+PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.0165f);
+PARAM_DEFINE_FLOAT(INAV_FLOW_Q_MIN, 0.5f);
PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.02f);
PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f);
PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f);
@@ -66,6 +67,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h)
h->w_pos_flow = param_find("INAV_W_POS_FLOW");
h->w_acc_bias = param_find("INAV_W_ACC_BIAS");
h->flow_k = param_find("INAV_FLOW_K");
+ h->flow_q_min = param_find("INAV_FLOW_Q_MIN");
h->sonar_filt = param_find("INAV_SONAR_FILT");
h->sonar_err = param_find("INAV_SONAR_ERR");
h->land_t = param_find("INAV_LAND_T");
@@ -86,6 +88,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str
param_get(h->w_pos_flow, &(p->w_pos_flow));
param_get(h->w_acc_bias, &(p->w_acc_bias));
param_get(h->flow_k, &(p->flow_k));
+ param_get(h->flow_q_min, &(p->flow_q_min));
param_get(h->sonar_filt, &(p->sonar_filt));
param_get(h->sonar_err, &(p->sonar_err));
param_get(h->land_t, &(p->land_t));
diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h
index 61570aea7..562915f49 100644
--- a/src/modules/position_estimator_inav/position_estimator_inav_params.h
+++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h
@@ -50,6 +50,7 @@ struct position_estimator_inav_params {
float w_pos_flow;
float w_acc_bias;
float flow_k;
+ float flow_q_min;
float sonar_filt;
float sonar_err;
float land_t;
@@ -67,6 +68,7 @@ struct position_estimator_inav_param_handles {
param_t w_pos_flow;
param_t w_acc_bias;
param_t flow_k;
+ param_t flow_q_min;
param_t sonar_filt;
param_t sonar_err;
param_t land_t;
diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c
index ec8033202..7541910d1 100644
--- a/src/modules/sdlog2/sdlog2.c
+++ b/src/modules/sdlog2/sdlog2.c
@@ -1046,8 +1046,10 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.body.log_LPOS.ref_lat = buf.local_pos.ref_lat;
log_msg.body.log_LPOS.ref_lon = buf.local_pos.ref_lon;
log_msg.body.log_LPOS.ref_alt = buf.local_pos.ref_alt;
+ log_msg.body.log_LPOS.dist_bottom = buf.local_pos.dist_bottom;
log_msg.body.log_LPOS.xy_flags = (buf.local_pos.xy_valid ? 1 : 0) | (buf.local_pos.v_xy_valid ? 2 : 0) | (buf.local_pos.xy_global ? 8 : 0);
log_msg.body.log_LPOS.z_flags = (buf.local_pos.z_valid ? 1 : 0) | (buf.local_pos.v_z_valid ? 2 : 0) | (buf.local_pos.z_global ? 8 : 0);
+ log_msg.body.log_LPOS.dist_flags = (buf.local_pos.dist_bottom_valid ? 1 : 0);
log_msg.body.log_LPOS.landed = buf.local_pos.landed;
LOGBUFFER_WRITE_AND_COUNT(LPOS);
}
diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h
index 0e88da054..32dd4f714 100644
--- a/src/modules/sdlog2/sdlog2_messages.h
+++ b/src/modules/sdlog2/sdlog2_messages.h
@@ -109,8 +109,10 @@ struct log_LPOS_s {
int32_t ref_lat;
int32_t ref_lon;
float ref_alt;
+ float dist_bottom;
uint8_t xy_flags;
uint8_t z_flags;
+ uint8_t dist_flags;
uint8_t landed;
};
@@ -281,7 +283,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, "ffffffLLfBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,XYFlags,ZFlags,Landed"),
+ LOG_FORMAT(LPOS, "ffffffLLffBBBB", "X,Y,Z,VX,VY,VZ,RefLat,RefLon,RefAlt,DstB,XYFl,ZFl,DstFl,Land"),
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/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index 4d719e0e1..6f5c20d39 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -188,6 +188,7 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5);
PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0);
PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 6);
PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0);
+PARAM_DEFINE_INT32(RC_MAP_DIST_B_SW, 0);
//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0);
diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp
index 9ef0d3c83..1f04fba40 100644
--- a/src/modules/sensors/sensors.cpp
+++ b/src/modules/sensors/sensors.cpp
@@ -315,6 +315,7 @@ private:
int rc_map_return_sw;
int rc_map_assisted_sw;
int rc_map_mission_sw;
+ int rc_map_dist_bottom_sw;
// int rc_map_offboard_ctrl_mode_sw;
@@ -360,6 +361,7 @@ private:
param_t rc_map_return_sw;
param_t rc_map_assisted_sw;
param_t rc_map_mission_sw;
+ param_t rc_map_dist_bottom_sw;
// param_t rc_map_offboard_ctrl_mode_sw;
@@ -578,6 +580,7 @@ Sensors::Sensors() :
/* optional mode switches, not mapped per default */
_parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW");
_parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW");
+ _parameter_handles.rc_map_dist_bottom_sw = param_find("RC_MAP_DIST_B_SW");
// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW");
@@ -726,6 +729,10 @@ Sensors::parameters_update()
warnx("Failed getting mission sw chan index");
}
+ if (param_get(_parameter_handles.rc_map_dist_bottom_sw, &(_parameters.rc_map_dist_bottom_sw)) != OK) {
+ warnx("Failed getting distance bottom sw chan index");
+ }
+
if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) {
warnx("Failed getting flaps chan index");
}
@@ -754,6 +761,7 @@ Sensors::parameters_update()
_rc.function[RETURN] = _parameters.rc_map_return_sw - 1;
_rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1;
_rc.function[MISSION] = _parameters.rc_map_mission_sw - 1;
+ _rc.function[DIST_BOTTOM] = _parameters.rc_map_dist_bottom_sw - 1;
_rc.function[FLAPS] = _parameters.rc_map_flaps - 1;
@@ -1333,6 +1341,8 @@ Sensors::ppm_poll()
manual_control.return_switch = NAN;
manual_control.assisted_switch = NAN;
manual_control.mission_switch = NAN;
+ manual_control.dist_bottom_switch = NAN;
+
// manual_control.auto_offboard_input_switch = NAN;
manual_control.flaps = NAN;
@@ -1445,6 +1455,9 @@ Sensors::ppm_poll()
/* mission switch input */
manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
+ /* distance bottom switch input */
+ manual_control.dist_bottom_switch = limit_minus_one_to_one(_rc.chan[_rc.function[DIST_BOTTOM]].scaled);
+
/* flaps */
if (_rc.function[FLAPS] >= 0) {
@@ -1463,6 +1476,10 @@ Sensors::ppm_poll()
manual_control.mission_switch = limit_minus_one_to_one(_rc.chan[_rc.function[MISSION]].scaled);
}
+ if (_rc.function[DIST_BOTTOM] >= 0) {
+ manual_control.dist_bottom_switch = limit_minus_one_to_one(_rc.chan[_rc.function[DIST_BOTTOM]].scaled);
+ }
+
// if (_rc.function[OFFBOARD_MODE] >= 0) {
// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled);
// }
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
index eac6d6e98..6e14d4bee 100644
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -60,6 +60,7 @@ struct manual_control_setpoint_s {
float return_switch; /**< land 2 position switch (mandatory): land, no effect */
float assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */
float mission_switch; /**< mission 2 position switch (optional): mission, loiter */
+ float dist_bottom_switch; /**< distance bottom 2 position switch (optional): off, on */
/**
* Any of the channels below may not be available and be set to NaN
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
index 5a8580143..8b952c28f 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -63,20 +63,21 @@
enum RC_CHANNELS_FUNCTION
{
THROTTLE = 0,
- ROLL = 1,
- PITCH = 2,
- YAW = 3,
- MODE = 4,
- RETURN = 5,
- ASSISTED = 6,
- MISSION = 7,
- OFFBOARD_MODE = 8,
- FLAPS = 9,
- AUX_1 = 10,
- AUX_2 = 11,
- AUX_3 = 12,
- AUX_4 = 13,
- AUX_5 = 14,
+ ROLL,
+ PITCH,
+ YAW,
+ MODE,
+ RETURN,
+ ASSISTED,
+ MISSION,
+ DIST_BOTTOM,
+ OFFBOARD_MODE,
+ FLAPS,
+ AUX_1,
+ AUX_2,
+ AUX_3,
+ AUX_4,
+ AUX_5,
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
index 093c6775d..cd004844c 100644
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ b/src/modules/uORB/topics/vehicle_control_mode.h
@@ -79,6 +79,7 @@ struct vehicle_control_mode_s
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 */
+ bool flag_use_dist_bottom; /**< true if bottom distance sensor should be used for altitude control */
bool flag_control_auto_enabled; // TEMP
uint8_t auto_state; // TEMP navigation state for AUTO modes
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
index 427153782..807fc6c09 100644
--- a/src/modules/uORB/topics/vehicle_local_position.h
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -77,6 +77,11 @@ struct vehicle_local_position_s
int32_t ref_lon; /**< Reference point longitude in 1E7 degrees */
float ref_alt; /**< Reference altitude AMSL in meters, MUST be set to current (not at reference point!) ground level */
bool landed; /**< true if vehicle is landed */
+ /* Distance to surface */
+ float dist_bottom; /**< Distance to bottom surface (ground) */
+ float v_dist_bottom; /**< Distance to bottom surface (ground) change rate */
+ uint64_t surface_bottom_timestamp; /**< Time when new bottom surface found */
+ bool dist_bottom_valid; /**< true if distance to bottom surface is valid */
};
/**
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index 1c184d3a7..96ae9cbce 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -107,15 +107,15 @@ typedef enum {
} assisted_switch_pos_t;
typedef enum {
- RETURN_SWITCH_NONE = 0,
- RETURN_SWITCH_RETURN
-} return_switch_pos_t;
-
-typedef enum {
MISSION_SWITCH_NONE = 0,
MISSION_SWITCH_MISSION
} mission_switch_pos_t;
+typedef enum {
+ SWITCH_OFF = 0,
+ SWITCH_ON
+} on_off_switch_pos_t;
+
enum VEHICLE_MODE_FLAG {
VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
@@ -187,9 +187,10 @@ struct vehicle_status_s
bool is_rotary_wing;
mode_switch_pos_t mode_switch;
- return_switch_pos_t return_switch;
+ on_off_switch_pos_t return_switch;
assisted_switch_pos_t assisted_switch;
mission_switch_pos_t mission_switch;
+ on_off_switch_pos_t dist_bottom_switch;
bool condition_battery_voltage_valid;
bool condition_system_in_air_restore; /**< true if we can restore in mid air */
@@ -201,6 +202,7 @@ struct vehicle_status_s
bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
bool condition_local_position_valid;
bool condition_local_altitude_valid;
+ bool condition_local_velocity_valid;
bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
bool condition_landed; /**< true if vehicle is landed, always true if disarmed */