代码拉取完成,页面将自动刷新
同步操作将从 mmmmachine/NaveGo 强制同步,此操作会覆盖自 Fork 仓库以来所做的任何修改,且无法恢复!!!
确定后同步将在后台操作,完成时将刷新页面,请耐心等待。
function cor_n = coriolis(lat, vel, h)
% coriolis: calculates Coriolis forces in the navigation frame.
%
% INPUT:
% lat: Mx1 latitude (radians).
% vel: Mx3 NED velocities (m/s).
% h: Mx1 altitude (m).
%
% OUTPUT:
% cor_n: Mx1 Coriolis forces vector in the nav-frame (m/s^2).
%
%
% Copyright (C) 2014, Rodrigo Gonzalez, all rights reserved.
%
% This file is part of NaveGo, an open-source MATLAB toolbox for
% simulation of integrated navigation systems.
%
% NaveGo is free software: you can redistribute it and/or modify
% it under the terms of the GNU Lesser General Public License (LGPL)
% version 3 as published by the Free Software Foundation.
%
% This program is distributed in the hope that it will be useful,
% but WITHOUT ANY WARRANTY; without even the implied warranty of
% MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
% GNU Lesser General Public License for more details.
%
% You should have received a copy of the GNU Lesser General Public
% License along with this program. If not, see
% <http://www.gnu.org/licenses/>.
%
% Reference:
% R. Gonzalez, J. Giribet, and H. Patiño. NaveGo: a
% simulation framework for low-cost integrated navigation systems,
% Journal of Control Engineering and Applied Informatics}, vol. 17,
% issue 2, pp. 110-120, 2015. Eq. 11.
%
% Version: 001
% Date: 2014/09/11
% Author: Rodrigo Gonzalez <rodralez@frm.utn.edu.ar>
% URL: https://github.com/rodralez/navego
kn = max(size(lat));
cor_n = zeros(kn, 3);
for i = 1:kn
omega_en_N = transportrate(lat(i), vel(i,1), vel(i,2), h(i));
omega_ie_N = earthrate(lat(i));
S = skewm(vel(i,:));
cor_n(i,:) = (S * (omega_en_N + 2*omega_ie_N))';
end
此处可能存在不合适展示的内容,页面不予展示。您可通过相关编辑功能自查并修改。
如您确认内容无涉及 不当用语 / 纯广告导流 / 暴力 / 低俗色情 / 侵权 / 盗版 / 虚假 / 无价值内容或违法国家有关法律法规的内容,可点击提交进行申诉,我们将尽快为您处理。