mirror of https://github.com/ArduPilot/ardupilot
SITL: split out GPS and MAG parameters into their own tables
this creates space for new parameter trees
This commit is contained in:
parent
d0d7a46492
commit
925b44dee5
|
@ -38,21 +38,13 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
||||||
AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise[0], 0.2f),
|
AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise[0], 0.2f),
|
||||||
AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 0),
|
AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 0),
|
||||||
AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 0),
|
AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 0),
|
||||||
AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 0),
|
|
||||||
AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0),
|
|
||||||
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.05f),
|
AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.05f),
|
||||||
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
|
AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
|
||||||
AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 1),
|
|
||||||
AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
|
AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
|
||||||
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
|
AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
|
||||||
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
|
AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
|
||||||
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0),
|
AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0),
|
||||||
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("SERVO_SPEED", 16, SITL, servo_speed, 0.14),
|
AP_GROUPINFO("SERVO_SPEED", 16, SITL, servo_speed, 0.14),
|
||||||
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("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6f),
|
||||||
AP_GROUPINFO("ARSPD_RND", 20, SITL, arspd_noise, 0.5f),
|
AP_GROUPINFO("ARSPD_RND", 20, SITL, arspd_noise, 0.5f),
|
||||||
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
|
||||||
|
@ -60,10 +52,8 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
||||||
AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
|
AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
|
||||||
AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
|
AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
|
||||||
AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
|
AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
|
||||||
AP_GROUPINFO("GPS2_ENABLE", 26, SITL, gps2_enable, 0),
|
|
||||||
AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable[0], 0),
|
AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable[0], 0),
|
||||||
AP_GROUPINFO("FLOAT_EXCEPT", 28, SITL, float_exception, 1),
|
AP_GROUPINFO("FLOAT_EXCEPT", 28, SITL, float_exception, 1),
|
||||||
AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
|
|
||||||
AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
|
AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
|
||||||
AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch[0], 0),
|
AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch[0], 0),
|
||||||
AP_GROUPINFO("SONAR_SCALE", 32, SITL, sonar_scale, 12.1212f),
|
AP_GROUPINFO("SONAR_SCALE", 32, SITL, sonar_scale, 12.1212f),
|
||||||
|
@ -71,31 +61,24 @@ const AP_Param::GroupInfo SITL::var_info[] = {
|
||||||
AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1),
|
AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1),
|
||||||
AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10),
|
AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10),
|
||||||
AP_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0),
|
AP_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0),
|
||||||
AP_GROUPINFO("GPS_DRIFTALT", 37, SITL, gps_drift_alt, 0),
|
|
||||||
AP_GROUPINFO("BARO_DELAY", 38, SITL, baro_delay, 0),
|
AP_GROUPINFO("BARO_DELAY", 38, SITL, baro_delay, 0),
|
||||||
AP_GROUPINFO("MAG_DELAY", 39, SITL, mag_delay, 0),
|
|
||||||
AP_GROUPINFO("WIND_DELAY", 40, SITL, wind_delay, 0),
|
AP_GROUPINFO("WIND_DELAY", 40, SITL, wind_delay, 0),
|
||||||
AP_GROUPINFO("MAG_OFS", 41, SITL, mag_ofs[0], 0),
|
|
||||||
AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
|
AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
|
||||||
AP_GROUPINFO("ARSPD_FAIL", 43, SITL, arspd_fail, 0),
|
AP_GROUPINFO("ARSPD_FAIL", 43, SITL, arspd_fail, 0),
|
||||||
AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0),
|
AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0),
|
||||||
AP_GROUPINFO("ADSB_COUNT", 45, SITL, adsb_plane_count, -1),
|
AP_GROUPINFO("ADSB_COUNT", 45, SITL, adsb_plane_count, -1),
|
||||||
AP_GROUPINFO("ADSB_RADIUS", 46, SITL, adsb_radius_m, 10000),
|
AP_GROUPINFO("ADSB_RADIUS", 46, SITL, adsb_radius_m, 10000),
|
||||||
AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000),
|
AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000),
|
||||||
AP_GROUPINFO("MAG_ALY", 48, SITL, mag_anomaly_ned, 0),
|
|
||||||
AP_GROUPINFO("MAG_ALY_HGT", 49, SITL, mag_anomaly_hgt, 1.0f),
|
|
||||||
AP_GROUPINFO("PIN_MASK", 50, SITL, pin_mask, 0),
|
AP_GROUPINFO("PIN_MASK", 50, SITL, pin_mask, 0),
|
||||||
AP_GROUPINFO("ADSB_TX", 51, SITL, adsb_tx, 0),
|
AP_GROUPINFO("ADSB_TX", 51, SITL, adsb_tx, 0),
|
||||||
AP_GROUPINFO("SPEEDUP", 52, SITL, speedup, -1),
|
AP_GROUPINFO("SPEEDUP", 52, SITL, speedup, -1),
|
||||||
AP_GROUPINFO("IMU_POS", 53, SITL, imu_pos_offset, 0),
|
AP_GROUPINFO("IMU_POS", 53, SITL, imu_pos_offset, 0),
|
||||||
AP_GROUPINFO("GPS_POS1", 54, SITL, gps_pos_offset[0], 0),
|
|
||||||
AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
|
AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
|
||||||
AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
|
AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
|
||||||
AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
|
AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
|
||||||
AP_GROUPINFO("GPS_NOISE", 58, SITL, gps_noise, 0),
|
AP_GROUPINFO("ENGINE_FAIL", 58, SITL, engine_fail, 0),
|
||||||
AP_GROUPINFO("GP2_GLITCH", 59, SITL, gps_glitch[1], 0),
|
AP_SUBGROUPEXTENSION("", 60, SITL, var_mag),
|
||||||
AP_GROUPINFO("ENGINE_FAIL", 60, SITL, engine_fail, 0),
|
AP_SUBGROUPEXTENSION("", 61, SITL, var_gps),
|
||||||
AP_GROUPINFO("GPS2_TYPE", 61, SITL, gps_type[1], SITL::GPS_TYPE_UBLOX),
|
|
||||||
AP_SUBGROUPEXTENSION("", 62, SITL, var_info3),
|
AP_SUBGROUPEXTENSION("", 62, SITL, var_info3),
|
||||||
AP_SUBGROUPEXTENSION("", 63, SITL, var_info2),
|
AP_SUBGROUPEXTENSION("", 63, SITL, var_info2),
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
@ -107,10 +90,8 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||||
AP_GROUPINFO("TEMP_FLIGHT", 2, SITL, temp_flight, 35),
|
AP_GROUPINFO("TEMP_FLIGHT", 2, SITL, temp_flight, 35),
|
||||||
AP_GROUPINFO("TEMP_TCONST", 3, SITL, temp_tconst, 30),
|
AP_GROUPINFO("TEMP_TCONST", 3, SITL, temp_tconst, 30),
|
||||||
AP_GROUPINFO("TEMP_BFACTOR", 4, SITL, temp_baro_factor, 0),
|
AP_GROUPINFO("TEMP_BFACTOR", 4, SITL, temp_baro_factor, 0),
|
||||||
AP_GROUPINFO("GPS_LOCKTIME", 5, SITL, gps_lock_time, 0),
|
|
||||||
AP_GROUPINFO("ARSPD_FAIL_P", 6, SITL, arspd_fail_pressure, 0),
|
AP_GROUPINFO("ARSPD_FAIL_P", 6, SITL, arspd_fail_pressure, 0),
|
||||||
AP_GROUPINFO("ARSPD_PITOT", 7, SITL, arspd_fail_pitot_pressure, 0),
|
AP_GROUPINFO("ARSPD_PITOT", 7, SITL, arspd_fail_pitot_pressure, 0),
|
||||||
AP_GROUPINFO("GPS_ALT_OFS", 8, SITL, gps_alt_offset, 0),
|
|
||||||
AP_GROUPINFO("ARSPD_SIGN", 9, SITL, arspd_signflip, 0),
|
AP_GROUPINFO("ARSPD_SIGN", 9, SITL, arspd_signflip, 0),
|
||||||
AP_GROUPINFO("WIND_DIR_Z", 10, SITL, wind_dir_z, 0),
|
AP_GROUPINFO("WIND_DIR_Z", 10, SITL, wind_dir_z, 0),
|
||||||
AP_GROUPINFO("ARSPD2_FAIL", 11, SITL, arspd2_fail, 0),
|
AP_GROUPINFO("ARSPD2_FAIL", 11, SITL, arspd2_fail, 0),
|
||||||
|
@ -119,9 +100,6 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||||
AP_GROUPINFO("WIND_T" ,15, SITL, wind_type, SITL::WIND_TYPE_SQRT),
|
AP_GROUPINFO("WIND_T" ,15, SITL, wind_type, SITL::WIND_TYPE_SQRT),
|
||||||
AP_GROUPINFO("WIND_T_ALT" ,16, SITL, wind_type_alt, 60),
|
AP_GROUPINFO("WIND_T_ALT" ,16, SITL, wind_type_alt, 60),
|
||||||
AP_GROUPINFO("WIND_T_COEF", 17, SITL, wind_type_coef, 0.01f),
|
AP_GROUPINFO("WIND_T_COEF", 17, SITL, wind_type_coef, 0.01f),
|
||||||
AP_GROUPINFO("MAG_DIA", 18, SITL, mag_diag[0], 0),
|
|
||||||
AP_GROUPINFO("MAG_ODI", 19, SITL, mag_offdiag[0], 0),
|
|
||||||
AP_GROUPINFO("MAG_ORIENT", 20, SITL, mag_orient[0], 0),
|
|
||||||
AP_GROUPINFO("RC_CHANCOUNT",21, SITL, rc_chancount, 16),
|
AP_GROUPINFO("RC_CHANCOUNT",21, SITL, rc_chancount, 16),
|
||||||
// @Group: SPR_
|
// @Group: SPR_
|
||||||
// @Path: ./SIM_Sprayer.cpp
|
// @Path: ./SIM_Sprayer.cpp
|
||||||
|
@ -170,7 +148,6 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||||
AP_GROUPINFO("GND_BEHAV", 41, SITL, gnd_behav, -1),
|
AP_GROUPINFO("GND_BEHAV", 41, SITL, gnd_behav, -1),
|
||||||
AP_GROUPINFO("BARO_COUNT", 42, SITL, baro_count, 1),
|
AP_GROUPINFO("BARO_COUNT", 42, SITL, baro_count, 1),
|
||||||
|
|
||||||
AP_GROUPINFO("GPS_HDG", 43, SITL, gps_hdg_enabled[0], 0),
|
|
||||||
|
|
||||||
// sailboat wave and tide simulation parameters
|
// sailboat wave and tide simulation parameters
|
||||||
AP_GROUPINFO("WAVE_ENABLE", 44, SITL, wave.enable, 0.0f),
|
AP_GROUPINFO("WAVE_ENABLE", 44, SITL, wave.enable, 0.0f),
|
||||||
|
@ -200,8 +177,6 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||||
|
|
||||||
AP_GROUPINFO("SAFETY_STATE", 59, SITL, _safety_switch_state, 0),
|
AP_GROUPINFO("SAFETY_STATE", 59, SITL, _safety_switch_state, 0),
|
||||||
|
|
||||||
AP_GROUPINFO("MAG_SCALING", 60, SITL, mag_scaling, 1),
|
|
||||||
|
|
||||||
// max motor vibration frequency
|
// max motor vibration frequency
|
||||||
AP_GROUPINFO("VIB_MOT_MAX", 61, SITL, vibe_motor, 0.0f),
|
AP_GROUPINFO("VIB_MOT_MAX", 61, SITL, vibe_motor, 0.0f),
|
||||||
// minimum throttle for simulated ins noise
|
// minimum throttle for simulated ins noise
|
||||||
|
@ -216,23 +191,12 @@ const AP_Param::GroupInfo SITL::var_info2[] = {
|
||||||
// third table of user settable parameters for SITL.
|
// third table of user settable parameters for SITL.
|
||||||
const AP_Param::GroupInfo SITL::var_info3[] = {
|
const AP_Param::GroupInfo SITL::var_info3[] = {
|
||||||
AP_GROUPINFO("ODOM_ENABLE", 1, SITL, odom_enable, 0),
|
AP_GROUPINFO("ODOM_ENABLE", 1, SITL, odom_enable, 0),
|
||||||
AP_GROUPINFO("GPS_POS2", 2, SITL, gps_pos_offset[1], 0),
|
|
||||||
AP_GROUPINFO("MAG1_DEVID", 3, SITL, mag_devid[0], 97539),
|
|
||||||
AP_GROUPINFO("MAG2_DEVID", 4, SITL, mag_devid[1], 131874),
|
|
||||||
AP_GROUPINFO("MAG3_DEVID", 5, SITL, mag_devid[2], 263178),
|
|
||||||
AP_GROUPINFO("MAG4_DEVID", 6, SITL, mag_devid[3], 97283),
|
|
||||||
AP_GROUPINFO("MAG5_DEVID", 7, SITL, mag_devid[4], 97795),
|
|
||||||
AP_GROUPINFO("MAG6_DEVID", 8, SITL, mag_devid[5], 98051),
|
|
||||||
AP_GROUPINFO("MAG7_DEVID", 9, SITL, mag_devid[6], 0),
|
|
||||||
AP_GROUPINFO("MAG8_DEVID", 10, SITL, mag_devid[7], 0),
|
|
||||||
|
|
||||||
AP_GROUPINFO("LED_LAYOUT", 11, SITL, led_layout, 0),
|
AP_GROUPINFO("LED_LAYOUT", 11, SITL, led_layout, 0),
|
||||||
|
|
||||||
// Scenario for thermalling simulation, for soaring
|
// Scenario for thermalling simulation, for soaring
|
||||||
AP_GROUPINFO("THML_SCENARI", 12, SITL, thermal_scenario, 0),
|
AP_GROUPINFO("THML_SCENARI", 12, SITL, thermal_scenario, 0),
|
||||||
|
|
||||||
AP_GROUPINFO("GPS2_HDG", 13, SITL, gps_hdg_enabled[1], 0),
|
|
||||||
|
|
||||||
// vicon sensor position (position offsets in body frame)
|
// vicon sensor position (position offsets in body frame)
|
||||||
AP_GROUPINFO("VICON_POS", 14, SITL, vicon_pos_offset, 0),
|
AP_GROUPINFO("VICON_POS", 14, SITL, vicon_pos_offset, 0),
|
||||||
|
|
||||||
|
@ -259,20 +223,6 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
|
||||||
|
|
||||||
AP_GROUPINFO("RATE_HZ", 22, SITL, loop_rate_hz, 1200),
|
AP_GROUPINFO("RATE_HZ", 22, SITL, loop_rate_hz, 1200),
|
||||||
|
|
||||||
#if HAL_COMPASS_MAX_SENSORS > 1
|
|
||||||
AP_GROUPINFO("MAG2_OFS", 23, SITL, mag_ofs[1], 0),
|
|
||||||
AP_GROUPINFO("MAG2_DIA", 24, SITL, mag_diag[1], 0),
|
|
||||||
AP_GROUPINFO("MAG2_ODI", 25, SITL, mag_offdiag[1], 0),
|
|
||||||
AP_GROUPINFO("MAG2_ORIENT", 26, SITL, mag_orient[1], 0),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAL_COMPASS_MAX_SENSORS > 2
|
|
||||||
AP_GROUPINFO("MAG3_OFS", 27, SITL, mag_ofs[2], 0),
|
|
||||||
AP_GROUPINFO("MAG3_DIA", 28, SITL, mag_diag[2], 0),
|
|
||||||
AP_GROUPINFO("MAG3_ODI", 29, SITL, mag_offdiag[2], 0),
|
|
||||||
AP_GROUPINFO("MAG3_ORIENT", 30, SITL, mag_orient[2], 0),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Path: ./SIM_RichenPower.cpp
|
// @Path: ./SIM_RichenPower.cpp
|
||||||
AP_SUBGROUPINFO(richenpower_sim, "RICH_", 31, SITL, RichenPower),
|
AP_SUBGROUPINFO(richenpower_sim, "RICH_", 31, SITL, RichenPower),
|
||||||
|
|
||||||
|
@ -284,6 +234,64 @@ const AP_Param::GroupInfo SITL::var_info3[] = {
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// 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_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_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_GROUPEND
|
||||||
|
};
|
||||||
|
|
||||||
|
// Mag SITL parameters
|
||||||
|
const AP_Param::GroupInfo SITL::var_mag[] = {
|
||||||
|
AP_GROUPINFO("MAG_RND", 1, SITL, mag_noise, 0),
|
||||||
|
AP_GROUPINFO("MAG_MOT", 2, SITL, mag_mot, 0),
|
||||||
|
AP_GROUPINFO("MAG_DELAY", 3, SITL, mag_delay, 0),
|
||||||
|
AP_GROUPINFO("MAG_OFS", 4, SITL, mag_ofs[0], 0),
|
||||||
|
AP_GROUPINFO("MAG_ALY", 5, SITL, mag_anomaly_ned, 0),
|
||||||
|
AP_GROUPINFO("MAG_ALY_HGT", 6, SITL, mag_anomaly_hgt, 1.0f),
|
||||||
|
AP_GROUPINFO("MAG_DIA", 7, SITL, mag_diag[0], 0),
|
||||||
|
AP_GROUPINFO("MAG_ODI", 8, SITL, mag_offdiag[0], 0),
|
||||||
|
AP_GROUPINFO("MAG_ORIENT", 9, SITL, mag_orient[0], 0),
|
||||||
|
AP_GROUPINFO("MAG_SCALING", 10, SITL, mag_scaling, 1),
|
||||||
|
AP_GROUPINFO("MAG1_DEVID", 11, SITL, mag_devid[0], 97539),
|
||||||
|
AP_GROUPINFO("MAG2_DEVID", 12, SITL, mag_devid[1], 131874),
|
||||||
|
AP_GROUPINFO("MAG3_DEVID", 13, SITL, mag_devid[2], 263178),
|
||||||
|
AP_GROUPINFO("MAG4_DEVID", 14, SITL, mag_devid[3], 97283),
|
||||||
|
AP_GROUPINFO("MAG5_DEVID", 15, SITL, mag_devid[4], 97795),
|
||||||
|
AP_GROUPINFO("MAG6_DEVID", 16, SITL, mag_devid[5], 98051),
|
||||||
|
AP_GROUPINFO("MAG7_DEVID", 17, SITL, mag_devid[6], 0),
|
||||||
|
AP_GROUPINFO("MAG8_DEVID", 18, SITL, mag_devid[7], 0),
|
||||||
|
#if HAL_COMPASS_MAX_SENSORS > 1
|
||||||
|
AP_GROUPINFO("MAG2_OFS", 19, SITL, mag_ofs[1], 0),
|
||||||
|
AP_GROUPINFO("MAG2_DIA", 20, SITL, mag_diag[1], 0),
|
||||||
|
AP_GROUPINFO("MAG2_ODI", 21, SITL, mag_offdiag[1], 0),
|
||||||
|
AP_GROUPINFO("MAG2_ORIENT", 22, SITL, mag_orient[1], 0),
|
||||||
|
#endif
|
||||||
|
#if HAL_COMPASS_MAX_SENSORS > 2
|
||||||
|
AP_GROUPINFO("MAG3_OFS", 23, SITL, mag_ofs[2], 0),
|
||||||
|
AP_GROUPINFO("MAG3_DIA", 24, SITL, mag_diag[2], 0),
|
||||||
|
AP_GROUPINFO("MAG3_ODI", 25, SITL, mag_offdiag[2], 0),
|
||||||
|
AP_GROUPINFO("MAG3_ORIENT", 36, SITL, mag_orient[2], 0),
|
||||||
|
#endif
|
||||||
|
AP_GROUPEND
|
||||||
|
};
|
||||||
|
|
||||||
/* report SITL state via MAVLink */
|
/* report SITL state via MAVLink */
|
||||||
void SITL::simstate_send(mavlink_channel_t chan)
|
void SITL::simstate_send(mavlink_channel_t chan)
|
||||||
|
|
|
@ -81,6 +81,8 @@ public:
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
AP_Param::setup_object_defaults(this, var_info2);
|
AP_Param::setup_object_defaults(this, var_info2);
|
||||||
AP_Param::setup_object_defaults(this, var_info3);
|
AP_Param::setup_object_defaults(this, var_info3);
|
||||||
|
AP_Param::setup_object_defaults(this, var_gps);
|
||||||
|
AP_Param::setup_object_defaults(this, var_mag);
|
||||||
if (_singleton != nullptr) {
|
if (_singleton != nullptr) {
|
||||||
AP_HAL::panic("Too many SITL instances");
|
AP_HAL::panic("Too many SITL instances");
|
||||||
}
|
}
|
||||||
|
@ -127,6 +129,8 @@ public:
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
static const struct AP_Param::GroupInfo var_info2[];
|
static const struct AP_Param::GroupInfo var_info2[];
|
||||||
static const struct AP_Param::GroupInfo var_info3[];
|
static const struct AP_Param::GroupInfo var_info3[];
|
||||||
|
static const struct AP_Param::GroupInfo var_gps[];
|
||||||
|
static const struct AP_Param::GroupInfo var_mag[];
|
||||||
|
|
||||||
// Board Orientation (and inverse)
|
// Board Orientation (and inverse)
|
||||||
Matrix3f ahrs_rotation;
|
Matrix3f ahrs_rotation;
|
||||||
|
|
Loading…
Reference in New Issue