2012-06-29 02:06:28 -03:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -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-06-29 02:06:28 -03:00
|
|
|
/*
|
|
|
|
SITL.cpp - software in the loop state
|
|
|
|
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include <AP_Common.h>
|
2014-01-03 01:01:18 -04:00
|
|
|
#include <AP_HAL.h>
|
2012-06-29 02:06:28 -03:00
|
|
|
#include <GCS_MAVLink.h>
|
|
|
|
#include <SITL.h>
|
|
|
|
|
2014-01-03 01:01:18 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2012-06-29 02:06:28 -03:00
|
|
|
// table of user settable parameters
|
|
|
|
const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
2012-08-06 22:02:14 -03:00
|
|
|
AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 3),
|
|
|
|
AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 30),
|
|
|
|
AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 3),
|
|
|
|
AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 10),
|
|
|
|
AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0),
|
|
|
|
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.2),
|
|
|
|
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
|
2013-09-15 22:41:51 -03:00
|
|
|
AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 2),
|
2012-08-17 01:21:43 -03:00
|
|
|
AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
|
2013-04-16 22:39:23 -03:00
|
|
|
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
|
2012-08-24 08:22:20 -03:00
|
|
|
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
|
|
|
|
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0.2),
|
2013-02-16 05:15:57 -04:00
|
|
|
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
|
2013-02-16 07:00:16 -04:00
|
|
|
AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
|
2013-05-06 21:38:36 -03:00
|
|
|
AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
|
2013-05-27 00:37:18 -03:00
|
|
|
AP_GROUPINFO("MAG_ERROR", 15, SITL, mag_error, 0),
|
2013-09-15 20:16:52 -03:00
|
|
|
AP_GROUPINFO("SERVO_RATE", 16, SITL, servo_rate, 0),
|
2013-09-19 03:51:03 -03:00
|
|
|
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
|
2013-10-01 03:39:16 -03:00
|
|
|
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
|
2013-10-02 05:44:20 -03:00
|
|
|
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6),
|
2013-10-14 01:40:45 -03:00
|
|
|
AP_GROUPINFO("ASPD_RND", 20, SITL, aspd_noise, 0.5),
|
2013-11-06 21:49:08 -04:00
|
|
|
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
2013-11-24 05:16:46 -04:00
|
|
|
AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
|
2013-11-28 06:43:25 -04:00
|
|
|
AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
|
|
|
|
AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
|
2013-12-19 18:40:31 -04:00
|
|
|
AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
|
2014-03-02 16:07:09 -04:00
|
|
|
AP_GROUPINFO("GPS2_ENABLE", 26, SITL, gps2_enable, 0),
|
2014-04-11 03:47:26 -03:00
|
|
|
AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable, 0),
|
2014-04-21 02:24:45 -03:00
|
|
|
AP_GROUPINFO("FLOAT_EXCEPT", 28, SITL, float_exception, 1),
|
2014-05-12 06:44:15 -03:00
|
|
|
AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
|
2012-06-29 02:06:28 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
/* report SITL state via MAVLink */
|
|
|
|
void SITL::simstate_send(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
double p, q, r;
|
|
|
|
float yaw;
|
|
|
|
|
|
|
|
// we want the gyro values to be directly comparable to the
|
|
|
|
// raw_imu message, which is in body frame
|
|
|
|
convert_body_frame(state.rollDeg, state.pitchDeg,
|
|
|
|
state.rollRate, state.pitchRate, state.yawRate,
|
|
|
|
&p, &q, &r);
|
|
|
|
|
|
|
|
// convert to same conventions as DCM
|
|
|
|
yaw = state.yawDeg;
|
|
|
|
if (yaw > 180) {
|
|
|
|
yaw -= 360;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_msg_simstate_send(chan,
|
|
|
|
ToRad(state.rollDeg),
|
|
|
|
ToRad(state.pitchDeg),
|
|
|
|
ToRad(yaw),
|
|
|
|
state.xAccel,
|
|
|
|
state.yAccel,
|
|
|
|
state.zAccel,
|
2012-08-10 22:58:25 -03:00
|
|
|
p, q, r,
|
2013-08-14 01:27:39 -03:00
|
|
|
state.latitude*1.0e7,
|
|
|
|
state.longitude*1.0e7);
|
2012-06-29 02:06:28 -03:00
|
|
|
}
|
|
|
|
|
2014-01-03 01:01:18 -04:00
|
|
|
/* report SITL state to DataFlash */
|
|
|
|
void SITL::Log_Write_SIMSTATE(DataFlash_Class &DataFlash)
|
|
|
|
{
|
|
|
|
double p, q, r;
|
|
|
|
float yaw;
|
|
|
|
|
|
|
|
// we want the gyro values to be directly comparable to the
|
|
|
|
// raw_imu message, which is in body frame
|
|
|
|
convert_body_frame(state.rollDeg, state.pitchDeg,
|
|
|
|
state.rollRate, state.pitchRate, state.yawRate,
|
|
|
|
&p, &q, &r);
|
|
|
|
|
|
|
|
// convert to same conventions as DCM
|
|
|
|
yaw = state.yawDeg;
|
|
|
|
if (yaw > 180) {
|
|
|
|
yaw -= 360;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct log_AHRS pkt = {
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_SIMSTATE_MSG),
|
|
|
|
time_ms : hal.scheduler->millis(),
|
|
|
|
roll : (int16_t)(state.rollDeg*100),
|
|
|
|
pitch : (int16_t)(state.pitchDeg*100),
|
|
|
|
yaw : (uint16_t)(wrap_360_cd(yaw*100)),
|
2014-01-03 21:21:49 -04:00
|
|
|
alt : (float)state.altitude,
|
2014-01-03 01:01:18 -04:00
|
|
|
lat : (int32_t)(state.latitude*1.0e7),
|
|
|
|
lng : (int32_t)(state.longitude*1.0e7)
|
|
|
|
};
|
|
|
|
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
|
|
|
}
|
|
|
|
|
2012-06-29 02:06:28 -03:00
|
|
|
// convert a set of roll rates from earth frame to body frame
|
|
|
|
void SITL::convert_body_frame(double rollDeg, double pitchDeg,
|
|
|
|
double rollRate, double pitchRate, double yawRate,
|
|
|
|
double *p, double *q, double *r)
|
|
|
|
{
|
|
|
|
double phi, theta, phiDot, thetaDot, psiDot;
|
|
|
|
|
|
|
|
phi = ToRad(rollDeg);
|
|
|
|
theta = ToRad(pitchDeg);
|
|
|
|
phiDot = ToRad(rollRate);
|
|
|
|
thetaDot = ToRad(pitchRate);
|
|
|
|
psiDot = ToRad(yawRate);
|
|
|
|
|
2014-01-04 02:45:20 -04:00
|
|
|
*p = phiDot - psiDot*sinf(theta);
|
|
|
|
*q = cosf(phi)*thetaDot + sinf(phi)*psiDot*cosf(theta);
|
|
|
|
*r = cosf(phi)*psiDot*cosf(theta) - sinf(phi)*thetaDot;
|
2012-06-29 02:06:28 -03:00
|
|
|
}
|
|
|
|
|