AP_GROUPINFO("TC_Z", 2, AP_InertialNav, _time_constant_z, AP_INTERTIALNAV_TC_Z),
// Z axis time constant
if (_time_constant_z == 0.0f) {
_k1_z = _k2_z = _k3_z = 0.0f;
}else{
_k1_z = 3.0f / _time_constant_z;
_k2_z = 3.0f / (_time_constant_z*_time_constant_z);
_k3_z = 1.0f / (_time_constant_z*_time_constant_z*_time_constant_z);
}
accel_correction_hbf.z += _position_error.z * _k3_z * dt;
....
_velocity.z += _position_error.z * _k2_z * dt;
....
_position_correction.z += _position_error.z * _k1_z * dt;
// calculate error in position from baro with our estimate
_position_error.z = baro_alt - (hist_position_base_z + _position_correction.z);
correct_with_baro(_baro.get_altitude()*100.0f, dt);
float AP_Baro::get_altitude(void)
{
if (_ground_pressure == 0) {
// called before initialisation
return 0;
}
if (_last_altitude_t == _last_update) {
// no new information
return _altitude + _alt_offset;
}
float pressure = get_pressure();
float alt = get_altitude_difference(_ground_pressure, pressure);
// record that we have consumed latest data
_last_altitude_t = _last_update;
// sanity check altitude
if (isnan(alt) || isinf(alt)) {
_flags.alt_ok = false;
} else {
_altitude = alt;
_flags.alt_ok = true;
}
// ensure the climb rate filter is updated
_climb_rate_filter.update(_altitude, _last_update);
return _altitude + _alt_offset;
}
float AP_Baro_MS5611::get_pressure()
{
return Press;
}
Yliangding 发表于 2018-6-4 18:21
楼主得到的结论,
是因为气压传感计得到的数据计算出的高度不对?
连恩 发表于 2018-6-4 18:40
pix适用不?
Yliangding 发表于 2018-6-4 19:32
风吹了一下,应该是气压变低。相对于是更高的高度,这时候飞控以为飞机跳高了,就应该降低高度。这时候就 ...
ezk 发表于 2018-6-20 00:27
用lidar啊 100多米高度都没问题 别用不靠谱的气压计了
欢迎光临 5iMX.com 我爱模型 玩家论坛 ——专业遥控模型和无人机玩家论坛(玩模型就上我爱模型,创始于2003年) (http://5imx.com./) | Powered by Discuz! X3.3 |