Browse Source

SITL: make all GPS params available for both GPS

zr-v5.1
Andrew Tridgell 5 years ago
parent
commit
a6df0745a6
  1. 42
      libraries/SITL/SITL.cpp
  2. 25
      libraries/SITL/SITL.h

42
libraries/SITL/SITL.cpp

@ -238,24 +238,34 @@ const AP_Param::GroupInfo SITL::var_info3[] = { @@ -238,24 +238,34 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
// GPS SITL parameters
const AP_Param::GroupInfo SITL::var_gps[] = {
AP_GROUPINFO("GPS_DISABLE", 1, SITL, gps_disable, 0),
AP_GROUPINFO("GPS_DELAY", 2, SITL, gps_delay, 1),
AP_GROUPINFO("GPS_DISABLE", 1, SITL, gps_disable[0], 0),
AP_GROUPINFO("GPS_DELAY", 2, SITL, gps_delay[0], 1),
AP_GROUPINFO("GPS_TYPE", 3, SITL, gps_type[0], SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS_BYTELOSS", 4, SITL, gps_byteloss, 0),
AP_GROUPINFO("GPS_NUMSATS", 5, SITL, gps_numsats, 10),
AP_GROUPINFO("GPS_BYTELOSS", 4, SITL, gps_byteloss[0], 0),
AP_GROUPINFO("GPS_NUMSATS", 5, SITL, gps_numsats[0], 10),
AP_GROUPINFO("GPS_GLITCH", 6, SITL, gps_glitch[0], 0),
AP_GROUPINFO("GPS_HZ", 7, SITL, gps_hertz, 5),
AP_GROUPINFO("GPS2_ENABLE", 8, SITL, gps2_enable, 0),
AP_GROUPINFO("GPS_DRIFTALT", 9, SITL, gps_drift_alt, 0),
AP_GROUPINFO("GPS_POS1", 10, SITL, gps_pos_offset[0], 0),
AP_GROUPINFO("GPS_NOISE", 11, SITL, gps_noise, 0),
AP_GROUPINFO("GP2_GLITCH", 12, SITL, gps_glitch[1], 0),
AP_GROUPINFO("GPS2_TYPE", 13, SITL, gps_type[1], SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS_LOCKTIME", 14, SITL, gps_lock_time, 0),
AP_GROUPINFO("GPS_ALT_OFS", 15, SITL, gps_alt_offset, 0),
AP_GROUPINFO("GPS_HDG", 16, SITL, gps_hdg_enabled[0], 0),
AP_GROUPINFO("GPS_POS2", 17, SITL, gps_pos_offset[1], 0),
AP_GROUPINFO("GPS2_HDG", 18, SITL, gps_hdg_enabled[1], 0),
AP_GROUPINFO("GPS_HZ", 7, SITL, gps_hertz[0], 5),
AP_GROUPINFO("GPS_DRIFTALT", 8, SITL, gps_drift_alt[0], 0),
AP_GROUPINFO("GPS_POS1", 9, SITL, gps_pos_offset[0], 0),
AP_GROUPINFO("GPS_NOISE", 10, SITL, gps_noise[0], 0),
AP_GROUPINFO("GPS_LOCKTIME", 11, SITL, gps_lock_time[0], 0),
AP_GROUPINFO("GPS_ALT_OFS", 12, SITL, gps_alt_offset[0], 0),
AP_GROUPINFO("GPS_HDG", 13, SITL, gps_hdg_enabled[0], 0),
AP_GROUPINFO("GPS2_DISABLE", 30, SITL, gps_disable[1], 1),
AP_GROUPINFO("GPS2_DELAY", 31, SITL, gps_delay[1], 1),
AP_GROUPINFO("GPS2_TYPE", 32, SITL, gps_type[1], SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS2_BYTELOS", 33, SITL, gps_byteloss[1], 0),
AP_GROUPINFO("GPS2_NUMSATS", 34, SITL, gps_numsats[1], 10),
AP_GROUPINFO("GPS2_GLTCH", 35, SITL, gps_glitch[1], 0),
AP_GROUPINFO("GPS2_HZ", 36, SITL, gps_hertz[1], 5),
AP_GROUPINFO("GPS2_DRFTALT", 37, SITL, gps_drift_alt[1], 0),
AP_GROUPINFO("GPS2_POS1", 38, SITL, gps_pos_offset[1], 0),
AP_GROUPINFO("GPS2_NOISE", 39, SITL, gps_noise[1], 0),
AP_GROUPINFO("GPS2_LCKTIME", 40, SITL, gps_lock_time[1], 0),
AP_GROUPINFO("GPS2_ALT_OFS", 41, SITL, gps_alt_offset[1], 0),
AP_GROUPINFO("GPS2_HDG", 42, SITL, gps_hdg_enabled[1], 0),
AP_GROUPEND
};

25
libraries/SITL/SITL.h

@ -154,9 +154,6 @@ public: @@ -154,9 +154,6 @@ public:
AP_Float arspd_fail_pitot_pressure; // 1st pitot tube failure pressure
AP_Float arspd2_fail_pressure; // 2nd pitot tube failure pressure
AP_Float arspd2_fail_pitot_pressure; // 2nd pitot tube failure pressure
AP_Float gps_noise; // amplitude of the gps altitude error
AP_Int16 gps_lock_time; // delay in seconds before GPS gets lock
AP_Int16 gps_alt_offset; // gps alt error
AP_Float mag_noise; // in mag units (earth field is 818)
AP_Vector3f mag_mot; // in mag units per amp
@ -174,14 +171,21 @@ public: @@ -174,14 +171,21 @@ public:
AP_Float drift_time; // period in minutes
AP_Float engine_mul; // engine multiplier
AP_Int8 engine_fail; // engine servo to fail (0-7)
AP_Int8 gps_disable; // disable simulated GPS
AP_Int8 gps2_enable; // enable 2nd simulated GPS
AP_Int8 gps_delay; // delay in samples
AP_Float gps_noise[2]; // amplitude of the gps altitude error
AP_Int16 gps_lock_time[2]; // delay in seconds before GPS gets lock
AP_Int16 gps_alt_offset[2]; // gps alt error
AP_Int8 gps_disable[2]; // disable simulated GPS
AP_Int8 gps_delay[2]; // delay in samples
AP_Int8 gps_type[2]; // see enum GPSType
AP_Float gps_byteloss;// byte loss as a percent
AP_Int8 gps_numsats; // number of visible satellites
AP_Float gps_byteloss[2];// byte loss as a percent
AP_Int8 gps_numsats[2]; // number of visible satellites
AP_Vector3f gps_glitch[2]; // glitch offsets in lat, lon and altitude
AP_Int8 gps_hertz; // GPS update rate in Hz
AP_Int8 gps_hertz[2]; // GPS update rate in Hz
AP_Int8 gps_hdg_enabled[2]; // enable the output of a NMEA heading HDT sentence or UBLOX RELPOSNED
AP_Float gps_drift_alt[2];
AP_Vector3f gps_pos_offset[2]; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m)
AP_Float batt_voltage; // battery voltage base
AP_Float accel_fail; // accelerometer failure value
AP_Int8 rc_fail; // fail RC input
@ -198,7 +202,6 @@ public: @@ -198,7 +202,6 @@ public:
AP_Int8 telem_baudlimit_enable; // enable baudrate limiting on links
AP_Float flow_noise; // optical flow measurement noise (rad/sec)
AP_Int8 baro_count; // number of simulated baros to create
AP_Int8 gps_hdg_enabled[2]; // enable the output of a NMEA heading HDT sentence or UBLOX RELPOSNED
AP_Int32 loop_delay; // extra delay to add to every loop
AP_Float mag_scaling; // scaling factor on first compasses
AP_Int32 mag_devid[MAX_CONNECTED_MAGS]; // Mag devid
@ -226,7 +229,6 @@ public: @@ -226,7 +229,6 @@ public:
AP_Float wind_speed;
AP_Float wind_direction;
AP_Float wind_turbulance;
AP_Float gps_drift_alt;
AP_Float wind_dir_z;
AP_Int8 wind_type; // enum WindLimitType
AP_Float wind_type_alt;
@ -248,7 +250,6 @@ public: @@ -248,7 +250,6 @@ public:
// Body frame sensor position offsets
AP_Vector3f imu_pos_offset; // XYZ position of the IMU accelerometer relative to the body frame origin (m)
AP_Vector3f gps_pos_offset[2]; // XYZ position of the GPS antenna phase centre relative to the body frame origin (m)
AP_Vector3f rngfnd_pos_offset; // XYZ position of the range finder zero range datum relative to the body frame origin (m)
AP_Vector3f optflow_pos_offset; // XYZ position of the optical flow sensor focal point relative to the body frame origin (m)
AP_Vector3f vicon_pos_offset; // XYZ position of the vicon sensor relative to the body frame origin (m)

Loading…
Cancel
Save