2010-12-10 06:17:27 -04:00
|
|
|
/*
|
2012-08-17 02:40:30 -03:00
|
|
|
* APM_AHRS_HIL.cpp
|
|
|
|
*
|
|
|
|
* Hardware in the loop AHRS object
|
2013-08-26 03:55:30 -03:00
|
|
|
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
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 General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
2012-08-17 02:40:30 -03:00
|
|
|
*/
|
2010-12-10 06:17:27 -04:00
|
|
|
|
2012-03-11 05:00:06 -03:00
|
|
|
#include <AP_AHRS.h>
|
2010-12-10 06:17:27 -04:00
|
|
|
|
|
|
|
/**************************************************/
|
|
|
|
void
|
2012-03-11 05:00:06 -03:00
|
|
|
AP_AHRS_HIL::setHil(float _roll, float _pitch, float _yaw,
|
2012-08-17 02:40:30 -03:00
|
|
|
float _rollRate, float _pitchRate, float _yawRate)
|
2010-12-10 06:17:27 -04:00
|
|
|
{
|
2012-08-17 02:40:30 -03:00
|
|
|
roll = _roll;
|
|
|
|
pitch = _pitch;
|
|
|
|
yaw = _yaw;
|
2010-12-10 06:17:27 -04:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
_omega(_rollRate, _pitchRate, _yawRate);
|
2010-12-10 06:17:27 -04:00
|
|
|
|
2012-08-17 02:40:30 -03:00
|
|
|
roll_sensor = ToDeg(roll)*100;
|
|
|
|
pitch_sensor = ToDeg(pitch)*100;
|
|
|
|
yaw_sensor = ToDeg(yaw)*100;
|
2013-04-21 09:27:04 -03:00
|
|
|
|
|
|
|
_dcm_matrix.from_euler(roll, pitch, yaw);
|
2010-12-10 06:17:27 -04:00
|
|
|
}
|