SITL: added SIM_GPS_NUMSATS parameter

this allows testing of the DCM code with less than 6 satellites
This commit is contained in:
Andrew Tridgell 2013-05-07 10:38:36 +10:00
parent 324200b52c
commit 055da3c4b6
3 changed files with 6 additions and 4 deletions

View File

@ -232,7 +232,7 @@ void SITL_State::_update_gps_ubx(const struct gps_data *d)
memset(&sol, 0, sizeof(sol));
sol.fix_type = d->have_lock?3:0;
sol.fix_status = 221;
sol.satellites = d->have_lock?10:3;
sol.satellites = d->have_lock?_sitl->gps_numsats:3;
_gps_send_ubx(MSG_POSLLH, (uint8_t*)&pos, sizeof(pos));
_gps_send_ubx(MSG_STATUS, (uint8_t*)&status, sizeof(status));
@ -297,7 +297,7 @@ void SITL_State::_update_gps_mtk(const struct gps_data *d)
if (p.ground_course < 0.0) {
p.ground_course += 360.0 * 1000000.0;
}
p.satellites = d->have_lock?10:3;
p.satellites = d->have_lock?_sitl->gps_numsats:3;
p.fix_type = d->have_lock?3:1;
// the spec is not very clear, but the time field seems to be
@ -353,7 +353,7 @@ void SITL_State::_update_gps_mtk16(const struct gps_data *d)
if (p.ground_course < 0.0) {
p.ground_course += 360.0 * 100.0;
}
p.satellites = d->have_lock?10:3;
p.satellites = d->have_lock?_sitl->gps_numsats:3;
p.fix_type = d->have_lock?3:1;
// the spec is not very clear, but the time field seems to be
@ -411,7 +411,7 @@ void SITL_State::_update_gps_mtk19(const struct gps_data *d)
if (p.ground_course < 0.0) {
p.ground_course += 360.0 * 100.0;
}
p.satellites = d->have_lock?10:3;
p.satellites = d->have_lock?_sitl->gps_numsats:3;
p.fix_type = d->have_lock?3:1;
// the spec is not very clear, but the time field seems to be

View File

@ -28,6 +28,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0.2),
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
AP_GROUPEND
};

View File

@ -60,6 +60,7 @@ public:
AP_Int8 gps_delay; // delay in samples
AP_Int8 gps_type; // see enum GPSType
AP_Float gps_byteloss;// byte loss as a percent
AP_Int8 gps_numsats; // number of visible satellites
// wind control
AP_Float wind_speed;