SITL: added SIM_GPS2_POS

and re-arrange two sets of GPS parameters to be arrays
This commit is contained in:
Andrew Tridgell 2020-01-26 15:16:46 +11:00
parent 73f138ff45
commit fb3496b63b
2 changed files with 18 additions and 11 deletions

View File

@ -47,12 +47,12 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0),
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type[0], SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
AP_GROUPINFO("MAG_ERROR", 15, SITL, mag_error, 0),
AP_GROUPINFO("SERVO_SPEED", 16, SITL, servo_speed, 0.14),
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch[0], 0),
AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6f),
AP_GROUPINFO("ARSPD_RND", 20, SITL, arspd_noise, 0.5f),
@ -89,15 +89,15 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("ADSB_TX", 51, SITL, adsb_tx, 0),
AP_GROUPINFO("SPEEDUP", 52, SITL, speedup, -1),
AP_GROUPINFO("IMU_POS", 53, SITL, imu_pos_offset, 0),
AP_GROUPINFO("GPS_POS", 54, SITL, gps_pos_offset, 0),
AP_GROUPINFO("GPS_POS", 54, SITL, gps_pos_offset[0], 0),
AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
AP_GROUPINFO("GPS_NOISE", 58, SITL, gps_noise, 0),
AP_GROUPINFO("GP2_GLITCH", 59, SITL, gps2_glitch, 0),
AP_GROUPINFO("GP2_GLITCH", 59, SITL, gps_glitch[1], 0),
AP_GROUPINFO("ENGINE_FAIL", 60, SITL, engine_fail, 0),
AP_GROUPINFO("GPS2_TYPE", 61, SITL, gps2_type, SITL::GPS_TYPE_UBLOX),
AP_GROUPINFO("ODOM_ENABLE", 62, SITL, odom_enable, 0),
AP_GROUPINFO("GPS2_TYPE", 61, SITL, gps_type[1], SITL::GPS_TYPE_UBLOX),
AP_SUBGROUPEXTENSION("", 62, SITL, var_info3),
AP_SUBGROUPEXTENSION("", 63, SITL, var_info2),
AP_GROUPEND
};
@ -213,6 +213,13 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
};
// third table of user settable parameters for SITL.
const AP_Param::GroupInfo SITL::var_info3[] = {
AP_GROUPINFO("ODOM_ENABLE", 1, SITL, odom_enable, 0),
AP_GROUPINFO("GPS2_POS", 2, SITL, gps_pos_offset[1], 0),
AP_GROUPEND
};
/* report SITL state via MAVLink */
void SITL::simstate_send(mavlink_channel_t chan)

View File

@ -71,6 +71,7 @@ public:
mag_ofs.set(Vector3f(5, 13, -18));
AP_Param::setup_object_defaults(this, var_info);
AP_Param::setup_object_defaults(this, var_info2);
AP_Param::setup_object_defaults(this, var_info3);
if (_singleton != nullptr) {
AP_HAL::panic("Too many SITL instances");
}
@ -116,6 +117,7 @@ public:
static const struct AP_Param::GroupInfo var_info[];
static const struct AP_Param::GroupInfo var_info2[];
static const struct AP_Param::GroupInfo var_info3[];
// noise levels for simulated sensors
AP_Float baro_noise; // in metres
@ -159,12 +161,10 @@ public:
AP_Int8 gps_disable; // disable simulated GPS
AP_Int8 gps2_enable; // enable 2nd simulated GPS
AP_Int8 gps_delay; // delay in samples
AP_Int8 gps_type; // see enum GPSType
AP_Int8 gps2_type; // see enum GPSType
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_Vector3f gps_glitch; // glitch offsets in lat, lon and altitude
AP_Vector3f gps2_glitch; // glitch offsets in lat, lon and altitude for 2nd GPS
AP_Vector3f gps_glitch[2]; // glitch offsets in lat, lon and altitude
AP_Int8 gps_hertz; // GPS update rate in Hz
AP_Float batt_voltage; // battery voltage base
AP_Float accel_fail; // accelerometer failure value
@ -229,7 +229,7 @@ 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; // XYZ position of the GPS antenna phase centre 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)