From c96de846b3b0b88859329b8a89fbc22cb8a72bed Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 8 Oct 2013 21:18:17 +0200 Subject: Added vehicle_local_position.ref_surface_timestamp to track surface level changes. Reference altitude updated continuosly when sonar available. --- src/modules/uORB/topics/vehicle_local_position.h | 1 + 1 file changed, 1 insertion(+) (limited to 'src/modules/uORB/topics/vehicle_local_position.h') diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h index 427153782..a1425d695 100644 --- a/src/modules/uORB/topics/vehicle_local_position.h +++ b/src/modules/uORB/topics/vehicle_local_position.h @@ -73,6 +73,7 @@ struct vehicle_local_position_s bool xy_global; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */ bool z_global; /**< true if z is valid and has valid global reference (ref_alt) */ uint64_t ref_timestamp; /**< Time when reference position was set */ + uint64_t ref_surface_timestamp; /**< Time when reference surface was set */ int32_t ref_lat; /**< Reference point latitude in 1E7 degrees */ 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 */ -- cgit v1.2.3 From 2fc011d20c7bd08bf5e076e79ba33a41f8fcbc30 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 9 Oct 2013 11:05:22 +0200 Subject: Remove vehicle_local_position.ref_surface_timestamp field, don't sync baro_offset and local_pos.ref_alt instead --- .../multirotor_pos_control.c | 4 +-- .../position_estimator_inav_main.c | 42 ++++++++++------------ src/modules/uORB/topics/vehicle_local_position.h | 1 - 3 files changed, 20 insertions(+), 27 deletions(-) (limited to 'src/modules/uORB/topics/vehicle_local_position.h') diff --git a/src/modules/multirotor_pos_control/multirotor_pos_control.c b/src/modules/multirotor_pos_control/multirotor_pos_control.c index 3016fcc0c..3baebf1cc 100644 --- a/src/modules/multirotor_pos_control/multirotor_pos_control.c +++ b/src/modules/multirotor_pos_control/multirotor_pos_control.c @@ -345,7 +345,7 @@ 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_surface_timestamp != ref_surface_prev_t) { + if (local_pos.ref_timestamp != ref_surface_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; @@ -674,7 +674,7 @@ static int multirotor_pos_control_thread_main(int argc, char *argv[]) } /* track local position reference even when not controlling position */ - ref_surface_prev_t = local_pos.ref_surface_timestamp; + ref_surface_prev_t = local_pos.ref_timestamp; ref_alt_prev = local_pos.ref_alt; /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */ 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 eaa21f8eb..d37c49696 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -180,7 +180,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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 from reference altitude, it's not the same as local_position.ref_alt if sonar available float alt_avg = 0.0f; bool landed = true; hrt_abstime landed_time = 0; @@ -299,15 +299,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 ref: alt=%.3f", baro_alt0); - mavlink_log_info(mavlink_fd, "[inav] init ref: 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; @@ -323,10 +323,6 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) { .fd = vehicle_attitude_sub, .events = POLLIN }, }; - if (!thread_should_exit) { - warnx("main loop started"); - } - while (!thread_should_exit) { int ret = poll(fds, 1, 20); // wait maximal 20 ms = 50 Hz minimum rate hrt_abstime t = hrt_absolute_time(); @@ -371,12 +367,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) /* reset ground level on arm if sonar is invalid */ if (armed.armed && !flag_armed && t > sonar_valid_time + sonar_valid_timeout) { flag_armed = armed.armed; - baro_alt0 -= z_est[0]; + baro_offset -= z_est[0]; z_est[0] = 0.0f; alt_avg = 0.0f; - local_pos.ref_alt = baro_alt0; + local_pos.ref_alt = baro_offset; local_pos.ref_timestamp = t; - local_pos.ref_surface_timestamp = t; } } @@ -415,7 +410,7 @@ 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 = - sensor.baro_alt_meter - z_est[0]; // should be shifted by baro_offset before applying correction baro_counter = sensor.baro_counter; baro_updates++; } @@ -442,9 +437,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) } else { /* new ground level */ - baro_alt0 += sonar_corr; - mavlink_log_info(mavlink_fd, "[inav] update ref: alt=%.3f", baro_alt0); - local_pos.ref_surface_timestamp = t; + baro_offset += sonar_corr; + mavlink_log_info(mavlink_fd, "[inav] update ref: alt=%.3f", baro_offset); + local_pos.ref_alt += sonar_corr; + local_pos.ref_timestamp = t; z_est[0] += sonar_corr; alt_avg -= sonar_corr; sonar_corr = 0.0f; @@ -619,16 +615,14 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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 */ + /* baro offset correction if sonar available, + * don't touch reference altitude, local_pos.ref_alt != baro_offset after this */ if (sonar_valid) { - baro_alt0 -= (baro_corr + baro_alt0) * params.w_alt_sonar * dt; - local_pos.ref_alt = baro_alt0; - local_pos.ref_timestamp = t; + baro_offset -= (baro_corr + baro_offset) * params.w_alt_sonar * dt; } /* accelerometer bias correction */ @@ -646,7 +640,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) accel_bias_corr[1] -= flow_corr[1] * params.w_pos_flow; } - accel_bias_corr[2] -= (baro_corr + baro_alt0) * params.w_alt_baro * params.w_alt_baro; + accel_bias_corr[2] -= (baro_corr + baro_offset) * params.w_alt_baro * params.w_alt_baro; if (sonar_valid) { accel_bias_corr[2] -= sonar_corr * params.w_alt_sonar * params.w_alt_sonar; @@ -671,7 +665,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) inertial_filter_correct(sonar_corr, dt, z_est, 0, params.w_alt_sonar); } - inertial_filter_correct(baro_corr + baro_alt0, dt, z_est, 0, params.w_alt_baro); + inertial_filter_correct(baro_corr + baro_offset, dt, z_est, 0, params.w_alt_baro); inertial_filter_correct(accel_corr[2], dt, z_est, 2, params.w_alt_acc); if (can_estimate_xy) { diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h index a1425d695..427153782 100644 --- a/src/modules/uORB/topics/vehicle_local_position.h +++ b/src/modules/uORB/topics/vehicle_local_position.h @@ -73,7 +73,6 @@ struct vehicle_local_position_s bool xy_global; /**< true if position (x, y) is valid and has valid global reference (ref_lat, ref_lon) */ bool z_global; /**< true if z is valid and has valid global reference (ref_alt) */ uint64_t ref_timestamp; /**< Time when reference position was set */ - uint64_t ref_surface_timestamp; /**< Time when reference surface was set */ int32_t ref_lat; /**< Reference point latitude in 1E7 degrees */ 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 */ -- cgit v1.2.3 From 86c53bee43ab7cb7cb18e9270af0c729440d14ed Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 10 Oct 2013 19:10:45 +0200 Subject: position_estimator_inav: use independent estimate for distance to ground (sonar), WIP --- .../position_estimator_inav_main.c | 38 +++++++++------------- src/modules/sdlog2/sdlog2.c | 2 ++ src/modules/sdlog2/sdlog2_messages.h | 4 ++- src/modules/uORB/topics/vehicle_local_position.h | 5 +++ 4 files changed, 26 insertions(+), 23 deletions(-) (limited to 'src/modules/uORB/topics/vehicle_local_position.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 506bc1bf0..6df7c69b2 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -180,7 +180,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) int baro_init_cnt = 0; int baro_init_num = 200; - float baro_offset = 0.0f; // baro offset from reference altitude, it's not the same as local_position.ref_alt if sonar available + 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; @@ -365,7 +366,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(actuator_armed), armed_sub, &armed); /* reset ground level on arm if sonar is invalid */ - if (armed.armed && !flag_armed && t > sonar_valid_time + sonar_valid_timeout) { + if (armed.armed && !flag_armed) { flag_armed = armed.armed; baro_offset -= z_est[0]; z_est[0] = 0.0f; @@ -410,7 +411,7 @@ 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]; // should be shifted by baro_offset before applying correction + baro_corr = baro_offset - sensor.baro_alt_meter - z_est[0]; baro_counter = sensor.baro_counter; baro_updates++; } @@ -425,7 +426,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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 - z_est[0]; + 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) { @@ -437,12 +438,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) } else { /* new ground level */ - baro_offset += sonar_corr; - mavlink_log_info(mavlink_fd, "[inav] update ref: alt=%.3f", baro_offset); - local_pos.ref_alt += sonar_corr; - local_pos.ref_timestamp = t; - z_est[0] += sonar_corr; - alt_avg -= sonar_corr; + surface_offset -= sonar_corr; + mavlink_log_info(mavlink_fd, "[inav] new surface level: %.3f", surface_offset); + alt_avg -= sonar_corr; // TODO check this sonar_corr = 0.0f; sonar_corr_filtered = 0.0f; sonar_valid_time = t; @@ -459,7 +457,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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] / att.R[2][2]; + 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 }; @@ -626,7 +624,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) /* baro offset correction if sonar available, * don't touch reference altitude, local_pos.ref_alt != baro_offset after this */ if (sonar_valid) { - baro_offset -= (baro_corr + baro_offset) * params.w_alt_sonar * dt; + surface_offset -= sonar_corr * params.w_alt_sonar * dt; } /* accelerometer bias correction */ @@ -644,11 +642,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) accel_bias_corr[1] -= flow_corr[1] * params.w_pos_flow; } - accel_bias_corr[2] -= (baro_corr + baro_offset) * params.w_alt_baro * params.w_alt_baro; - - if (sonar_valid) { - accel_bias_corr[2] -= sonar_corr * params.w_alt_sonar * params.w_alt_sonar; - } + 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++) { @@ -665,11 +659,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) inertial_filter_predict(dt, z_est); /* inertial filter correction for altitude */ - if (sonar_valid) { - inertial_filter_correct(sonar_corr, dt, z_est, 0, params.w_alt_sonar); - } - - inertial_filter_correct(baro_corr + baro_offset, dt, z_est, 0, params.w_alt_baro); + 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 (can_estimate_xy) { @@ -773,6 +763,10 @@ 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; 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/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 */ }; /** -- cgit v1.2.3 From c0c366d6ee076ca812fa9672709c1e66fafdb32b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 12 Oct 2013 11:20:20 +0200 Subject: position_estimator_inav: estimate distance to bottom rate, increase time of position estimation on only accelerometer, reduce weight for GPS if flow available --- .../position_estimator_inav_main.c | 55 ++++++++++++++-------- .../position_estimator_inav_params.c | 3 ++ .../position_estimator_inav_params.h | 2 + src/modules/uORB/topics/vehicle_local_position.h | 2 +- 4 files changed, 42 insertions(+), 20 deletions(-) (limited to 'src/modules/uORB/topics/vehicle_local_position.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 81271ab52..f9fb5ab1b 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -79,8 +79,8 @@ static bool verbose_mode = false; 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 hrt_abstime sonar_valid_timeout = 1000000; // estimate sonar distance during this time after sonar loss +static const hrt_abstime xy_src_timeout = 2000000; // estimate position during this time after position sources loss static const uint32_t updates_counter_len = 1000000; 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 @@ -182,6 +182,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) int baro_init_num = 200; 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 surface_offset_rate = 0.0f; // surface offset change rate float alt_avg = 0.0f; bool landed = true; hrt_abstime landed_time = 0; @@ -226,7 +227,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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) + hrt_abstime xy_src_time = 0; // time of last available position data bool gps_valid = false; // GPS is valid bool sonar_valid = false; // sonar is valid @@ -434,6 +435,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) if (fabsf(sonar_corr - sonar_corr_filtered) > params.sonar_err) { /* spike detected, ignore */ sonar_corr = 0.0f; + surface_offset_rate = 0.0f; sonar_valid = false; } else { @@ -441,6 +443,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) surface_offset -= sonar_corr; sonar_corr = 0.0f; sonar_corr_filtered = 0.0f; + surface_offset_rate = 0.0f; sonar_valid_time = t; sonar_valid = true; local_pos.surface_bottom_timestamp = t; @@ -448,8 +451,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) } } else { + /* correction is ok, use it */ sonar_valid_time = t; sonar_valid = true; + surface_offset_rate = -sonar_corr * params.w_alt_sonar; } } @@ -495,13 +500,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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 */ + flow_w = att.R[2][2] * flow_q_weight / fmaxf(1.0f, flow_dist); + /* if flow is not accurate, reduce weight for it */ // TODO make this more fuzzy if (!flow_accurate) - flow_w *= 0.2f; + flow_w *= 0.05f; flow_valid = true; - flow_valid_time = t; } else { flow_w = 0.0f; @@ -606,6 +610,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) /* check for sonar measurement timeout */ if (sonar_valid && t > sonar_time + sonar_timeout) { sonar_corr = 0.0f; + surface_offset_rate = 0.0f; sonar_valid = false; } @@ -616,24 +621,35 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) bool use_gps = ref_xy_inited && gps_valid && params.w_pos_gps_p > 0.00001f; /* 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); + /* try to estimate position during some time after position sources lost */ + if (use_gps || use_flow) { + xy_src_time = t; + } + bool can_estimate_xy = (t < xy_src_time + xy_src_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; + surface_offset += surface_offset_rate * dt; } /* accelerometer bias correction */ float accel_bias_corr[3] = { 0.0f, 0.0f, 0.0f }; + float w_pos_gps_p = params.w_pos_gps_p; + float w_pos_gps_v = params.w_pos_gps_v; + + /* reduce GPS weight if optical flow is good */ + if (use_flow && flow_accurate) { + w_pos_gps_p *= params.w_gps_flow; + w_pos_gps_v *= params.w_gps_flow; + } + 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; + accel_bias_corr[0] -= gps_corr[0][0] * w_pos_gps_p * w_pos_gps_p; + accel_bias_corr[0] -= gps_corr[0][1] * w_pos_gps_v; + accel_bias_corr[1] -= gps_corr[1][0] * w_pos_gps_p * w_pos_gps_p; + accel_bias_corr[1] -= gps_corr[1][1] * w_pos_gps_v; } if (use_flow) { @@ -681,12 +697,12 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) } 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); + inertial_filter_correct(gps_corr[0][0], dt, x_est, 0, w_pos_gps_p); + inertial_filter_correct(gps_corr[1][0], dt, y_est, 0, w_pos_gps_p); 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); + inertial_filter_correct(gps_corr[0][1], dt, x_est, 1, w_pos_gps_v); + inertial_filter_correct(gps_corr[1][1], dt, y_est, 1, w_pos_gps_v); } } @@ -765,6 +781,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) 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.dist_bottom_rate = -z_est[1] - surface_offset_rate; } local_pos.timestamp = t; 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 b3c32b180..0a00ae6bb 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -47,6 +47,7 @@ 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, 5.0f); +PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f); PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.0f); PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.0165f); PARAM_DEFINE_FLOAT(INAV_FLOW_Q_MIN, 0.5f); @@ -65,6 +66,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h) h->w_pos_gps_v = param_find("INAV_W_POS_GPS_V"); h->w_pos_acc = param_find("INAV_W_POS_ACC"); h->w_pos_flow = param_find("INAV_W_POS_FLOW"); + h->w_gps_flow = param_find("INAV_W_GPS_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"); @@ -86,6 +88,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str param_get(h->w_pos_gps_v, &(p->w_pos_gps_v)); param_get(h->w_pos_acc, &(p->w_pos_acc)); param_get(h->w_pos_flow, &(p->w_pos_flow)); + param_get(h->w_gps_flow, &(p->w_gps_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)); 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 562915f49..e394edfa4 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.h +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h @@ -48,6 +48,7 @@ struct position_estimator_inav_params { float w_pos_gps_v; float w_pos_acc; float w_pos_flow; + float w_gps_flow; float w_acc_bias; float flow_k; float flow_q_min; @@ -66,6 +67,7 @@ struct position_estimator_inav_param_handles { param_t w_pos_gps_v; param_t w_pos_acc; param_t w_pos_flow; + param_t w_gps_flow; param_t w_acc_bias; param_t flow_k; param_t flow_q_min; diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h index 807fc6c09..d567f2e02 100644 --- a/src/modules/uORB/topics/vehicle_local_position.h +++ b/src/modules/uORB/topics/vehicle_local_position.h @@ -79,7 +79,7 @@ struct vehicle_local_position_s 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 */ + float dist_bottom_rate; /**< 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 */ }; -- cgit v1.2.3