mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AC_PrecLand: small improvements in comments
This commit is contained in:
parent
f0ea4af514
commit
4a71ac5e93
@ -93,7 +93,7 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
|
||||
|
||||
// @Param: LAG
|
||||
// @DisplayName: Precision Landing sensor lag
|
||||
// @Description: Precision Landing sensor lag in ms, to cope with variable landing_target latency
|
||||
// @Description: Precision Landing sensor lag, to cope with variable landing_target latency
|
||||
// @Range: 0.02 0.250
|
||||
// @Increment: 1
|
||||
// @Units: s
|
||||
@ -283,7 +283,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va
|
||||
_target_vel_rel_est_NE.y = -inertial_data_delayed->inertialNavVelocity.y;
|
||||
}
|
||||
|
||||
// Update if a new LOS measurement is available
|
||||
// Update if a new Line-Of-Sight measurement is available
|
||||
if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {
|
||||
_target_pos_rel_est_NE.x = _target_pos_rel_meas_NED.x;
|
||||
_target_pos_rel_est_NE.y = _target_pos_rel_meas_NED.y;
|
||||
@ -310,7 +310,7 @@ void AC_PrecLand::run_estimator(float rangefinder_alt_m, bool rangefinder_alt_va
|
||||
_ekf_y.predict(dt, -vehicleDelVel.y, _accel_noise*dt);
|
||||
}
|
||||
|
||||
// Update if a new LOS measurement is available
|
||||
// Update if a new Line-Of-Sight measurement is available
|
||||
if (construct_pos_meas_using_rangefinder(rangefinder_alt_m, rangefinder_alt_valid)) {
|
||||
float xy_pos_var = sq(_target_pos_rel_meas_NED.z*(0.01f + 0.01f*AP::ahrs().get_gyro().length()) + 0.02f);
|
||||
if (!target_acquired()) {
|
||||
|
@ -105,7 +105,7 @@ private:
|
||||
// run target position estimator
|
||||
void run_estimator(float rangefinder_alt_m, bool rangefinder_alt_valid);
|
||||
|
||||
// If a new measurement was retreived, sets _target_pos_rel_meas_NED and returns true
|
||||
// If a new measurement was retrieved, sets _target_pos_rel_meas_NED and returns true
|
||||
bool construct_pos_meas_using_rangefinder(float rangefinder_alt_m, bool rangefinder_alt_valid);
|
||||
|
||||
// get vehicle body frame 3D vector from vehicle to target. returns true on success, false on failure
|
||||
@ -124,7 +124,7 @@ private:
|
||||
AP_Float _yaw_align; // Yaw angle from body x-axis to sensor x-axis.
|
||||
AP_Float _land_ofs_cm_x; // Desired landing position of the camera forward of the target in vehicle body frame
|
||||
AP_Float _land_ofs_cm_y; // Desired landing position of the camera right of the target in vehicle body frame
|
||||
AP_Float _accel_noise; // accelometer process noise
|
||||
AP_Float _accel_noise; // accelerometer process noise
|
||||
AP_Vector3f _cam_offset; // Position of the camera relative to the CG
|
||||
|
||||
uint32_t _last_update_ms; // system time in millisecond when update was last called
|
||||
|
@ -7,6 +7,8 @@
|
||||
/*
|
||||
* AC_PrecLand_Companion - implements precision landing using target vectors provided
|
||||
* by a companion computer (i.e. Odroid) communicating via MAVLink
|
||||
* The companion computer must provide "Line-Of-Sight" measurements
|
||||
* in the form of LANDING_TARGET mavlink messages.
|
||||
*/
|
||||
|
||||
class AC_PrecLand_Companion : public AC_PrecLand_Backend
|
||||
|
Loading…
Reference in New Issue
Block a user