1 Star 0 Fork 2

mmmmachine/NaveGo

加入 Gitee
与超过 1200万 开发者一起发现、参与优秀开源项目,私有仓库也完全免费 :)
免费加入
克隆/下载
coriolis.m 1.71 KB
一键复制 编辑 原始数据 按行查看 历史
rodralez 提交于 2019-03-15 10:00 . 2019-03-15
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
马建仓 AI 助手
尝试更多
代码解读
代码找茬
代码优化
Matlab
1
https://gitee.com/mmmmachine/NaveGo.git
git@gitee.com:mmmmachine/NaveGo.git
mmmmachine
NaveGo
NaveGo
master

搜索帮助