mirror of https://github.com/ArduPilot/ardupilot
Tools: revert compass parameter changes
This commit is contained in:
parent
ba8ce12b67
commit
9ee140cbbf
|
@ -181,9 +181,9 @@ const AP_Param::Info AP_Periph_FW::var_info[] = {
|
|||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_MAG
|
||||
// @Group: COMPASS
|
||||
// @Group: COMPASS_
|
||||
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||
GOBJECT(compass, "COMPASS", Compass),
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
#endif
|
||||
|
||||
#ifdef HAL_PERIPH_ENABLE_BARO
|
||||
|
|
|
@ -30,9 +30,9 @@ class TestCompass(Test):
|
|||
warnOffset = 300
|
||||
failOffset = 500
|
||||
param_offsets = (
|
||||
logdata.parameters["COMPASS1_OFS_X"],
|
||||
logdata.parameters["COMPASS1_OFS_Y"],
|
||||
logdata.parameters["COMPASS1_OFS_Z"]
|
||||
logdata.parameters["COMPASS_OFS_X"],
|
||||
logdata.parameters["COMPASS_OFS_Y"],
|
||||
logdata.parameters["COMPASS_OFS_Z"]
|
||||
)
|
||||
|
||||
if vec_len(param_offsets) > failOffset:
|
||||
|
|
|
@ -66,9 +66,9 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
|
|||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||
GOBJECTN(ekf2, NavEKF2, "EK2_", NavEKF2),
|
||||
|
||||
// @Group: COMPASS
|
||||
// @Group: COMPASS_
|
||||
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||
GOBJECT(compass, "COMPASS", Compass),
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
|
||||
// @Group: LOG
|
||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
||||
|
|
|
@ -6813,9 +6813,9 @@ class AutoTestCopter(AutoTest):
|
|||
self.start_subtest("missing required yaw source")
|
||||
self.set_parameters({
|
||||
"EK3_SRC3_YAW": 3, # External Yaw with Compass Fallback
|
||||
"COMPASS1_USE": 0,
|
||||
"COMPASS2_USE": 0,
|
||||
"COMPASS3_USE": 0,
|
||||
"COMPASS_USE": 0,
|
||||
"COMPASS_USE2": 0,
|
||||
"COMPASS_USE3": 0,
|
||||
})
|
||||
self.assert_prearm_failure("EK3 sources require Compass")
|
||||
self.context_pop()
|
||||
|
|
|
@ -7056,12 +7056,16 @@ Also, ignores heartbeats not from our target system'''
|
|||
0 # param7
|
||||
)
|
||||
self.progress("zeroed mag parameters")
|
||||
params = []
|
||||
for count in range(1, compass_count + 1):
|
||||
params = [
|
||||
[("SIM_MAG_OFS_X", "COMPASS_OFS_X", 0),
|
||||
("SIM_MAG_OFS_Y", "COMPASS_OFS_Y", 0),
|
||||
("SIM_MAG_OFS_Z", "COMPASS_OFS_Z", 0), ],
|
||||
]
|
||||
for count in range(2, compass_count + 1):
|
||||
params += [
|
||||
[("SIM_MAG%d_OFS_X" % count, "COMPASS%d_OFS_X" % count, 0),
|
||||
("SIM_MAG%d_OFS_Y" % count, "COMPASS%d_OFS_Y" % count, 0),
|
||||
("SIM_MAG%d_OFS_Z" % count, "COMPASS%d_OFS_Z" % count, 0), ],
|
||||
[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, 0),
|
||||
("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, 0),
|
||||
("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, 0), ],
|
||||
]
|
||||
self.check_zero_mag_parameters(params)
|
||||
|
||||
|
@ -7069,15 +7073,22 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.progress("Forty twoing Mag DIA and ODI parameters")
|
||||
self.drain_mav()
|
||||
self.get_sim_time()
|
||||
params = []
|
||||
for count in range(1, compass_count + 1):
|
||||
params = [
|
||||
[("SIM_MAG_DIA_X", "COMPASS_DIA_X", 42.0),
|
||||
("SIM_MAG_DIA_Y", "COMPASS_DIA_Y", 42.0),
|
||||
("SIM_MAG_DIA_Z", "COMPASS_DIA_Z", 42.0),
|
||||
("SIM_MAG_ODI_X", "COMPASS_ODI_X", 42.0),
|
||||
("SIM_MAG_ODI_Y", "COMPASS_ODI_Y", 42.0),
|
||||
("SIM_MAG_ODI_Z", "COMPASS_ODI_Z", 42.0), ],
|
||||
]
|
||||
for count in range(2, compass_count + 1):
|
||||
params += [
|
||||
[("SIM_MAG%d_DIA_X" % count, "COMPASS%d_DIA_X" % count, 42.0),
|
||||
("SIM_MAG%d_DIA_Y" % count, "COMPASS%d_DIA_Y" % count, 42.0),
|
||||
("SIM_MAG%d_DIA_Z" % count, "COMPASS%d_DIA_Z" % count, 42.0),
|
||||
("SIM_MAG%d_ODI_X" % count, "COMPASS%d_ODI_X" % count, 42.0),
|
||||
("SIM_MAG%d_ODI_Y" % count, "COMPASS%d_ODI_Y" % count, 42.0),
|
||||
("SIM_MAG%d_ODI_Z" % count, "COMPASS%d_ODI_Z" % count, 42.0), ],
|
||||
[("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, 42.0),
|
||||
("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, 42.0),
|
||||
("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, 42.0),
|
||||
("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, 42.0),
|
||||
("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, 42.0),
|
||||
("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, 42.0), ],
|
||||
]
|
||||
self.wait_heartbeat()
|
||||
to_set = {}
|
||||
|
@ -7113,8 +7124,9 @@ Also, ignores heartbeats not from our target system'''
|
|||
|
||||
def check_zeros_mag_orient(self, compass_count=3):
|
||||
self.progress("zeroed mag parameters")
|
||||
for count in range(1, compass_count + 1):
|
||||
self.verify_parameter_values({"COMPASS%d_ORIENT" % count: 0})
|
||||
self.verify_parameter_values({"COMPASS_ORIENT": 0})
|
||||
for count in range(2, compass_count + 1):
|
||||
self.verify_parameter_values({"COMPASS_ORIENT%d" % count: 0})
|
||||
|
||||
def test_mag_calibration(self, compass_count=3, timeout=1000):
|
||||
def reset_pos_and_start_magcal(mavproxy, tmask):
|
||||
|
@ -7141,27 +7153,27 @@ Also, ignores heartbeats not from our target system'''
|
|||
MAG_DIA = 1.0
|
||||
MAG_ODI = 0.004
|
||||
params += [
|
||||
[("SIM_MAG_OFS_X", "COMPASS1_OFS_X", MAG_OFS),
|
||||
("SIM_MAG_OFS_Y", "COMPASS1_OFS_Y", MAG_OFS + 100),
|
||||
("SIM_MAG_OFS_Z", "COMPASS1_OFS_Z", MAG_OFS + 200),
|
||||
("SIM_MAG_DIA_X", "COMPASS1_DIA_X", MAG_DIA),
|
||||
("SIM_MAG_DIA_Y", "COMPASS1_DIA_Y", MAG_DIA + 0.1),
|
||||
("SIM_MAG_DIA_Z", "COMPASS1_DIA_Z", MAG_DIA + 0.2),
|
||||
("SIM_MAG_ODI_X", "COMPASS1_ODI_X", MAG_ODI),
|
||||
("SIM_MAG_ODI_Y", "COMPASS1_ODI_Y", MAG_ODI + 0.001),
|
||||
("SIM_MAG_ODI_Z", "COMPASS1_ODI_Z", MAG_ODI + 0.001), ],
|
||||
[("SIM_MAG_OFS_X", "COMPASS_OFS_X", MAG_OFS),
|
||||
("SIM_MAG_OFS_Y", "COMPASS_OFS_Y", MAG_OFS + 100),
|
||||
("SIM_MAG_OFS_Z", "COMPASS_OFS_Z", MAG_OFS + 200),
|
||||
("SIM_MAG_DIA_X", "COMPASS_DIA_X", MAG_DIA),
|
||||
("SIM_MAG_DIA_Y", "COMPASS_DIA_Y", MAG_DIA + 0.1),
|
||||
("SIM_MAG_DIA_Z", "COMPASS_DIA_Z", MAG_DIA + 0.2),
|
||||
("SIM_MAG_ODI_X", "COMPASS_ODI_X", MAG_ODI),
|
||||
("SIM_MAG_ODI_Y", "COMPASS_ODI_Y", MAG_ODI + 0.001),
|
||||
("SIM_MAG_ODI_Z", "COMPASS_ODI_Z", MAG_ODI + 0.001), ],
|
||||
]
|
||||
for count in range(2, compass_count + 1):
|
||||
params += [
|
||||
[("SIM_MAG%d_OFS_X" % count, "COMPASS%d_OFS_X" % count, MAG_OFS + 100 * ((count+2) % compass_count)),
|
||||
("SIM_MAG%d_OFS_Y" % count, "COMPASS%d_OFS_Y" % count, MAG_OFS + 100 * ((count+3) % compass_count)),
|
||||
("SIM_MAG%d_OFS_Z" % count, "COMPASS%d_OFS_Z" % count, MAG_OFS + 100 * ((count+1) % compass_count)),
|
||||
("SIM_MAG%d_DIA_X" % count, "COMPASS%d_DIA_X" % count, MAG_DIA + 0.1 * ((count+2) % compass_count)),
|
||||
("SIM_MAG%d_DIA_Y" % count, "COMPASS%d_DIA_Y" % count, MAG_DIA + 0.1 * ((count+3) % compass_count)),
|
||||
("SIM_MAG%d_DIA_Z" % count, "COMPASS%d_DIA_Z" % count, MAG_DIA + 0.1 * ((count+1) % compass_count)),
|
||||
("SIM_MAG%d_ODI_X" % count, "COMPASS%d_ODI_X" % count, MAG_ODI + 0.001 * ((count+2) % compass_count)),
|
||||
("SIM_MAG%d_ODI_Y" % count, "COMPASS%d_ODI_Y" % count, MAG_ODI + 0.001 * ((count+3) % compass_count)),
|
||||
("SIM_MAG%d_ODI_Z" % count, "COMPASS%d_ODI_Z" % count, MAG_ODI + 0.001 * ((count+1) % compass_count)), ],
|
||||
[("SIM_MAG%d_OFS_X" % count, "COMPASS_OFS%d_X" % count, MAG_OFS + 100 * ((count+2) % compass_count)),
|
||||
("SIM_MAG%d_OFS_Y" % count, "COMPASS_OFS%d_Y" % count, MAG_OFS + 100 * ((count+3) % compass_count)),
|
||||
("SIM_MAG%d_OFS_Z" % count, "COMPASS_OFS%d_Z" % count, MAG_OFS + 100 * ((count+1) % compass_count)),
|
||||
("SIM_MAG%d_DIA_X" % count, "COMPASS_DIA%d_X" % count, MAG_DIA + 0.1 * ((count+2) % compass_count)),
|
||||
("SIM_MAG%d_DIA_Y" % count, "COMPASS_DIA%d_Y" % count, MAG_DIA + 0.1 * ((count+3) % compass_count)),
|
||||
("SIM_MAG%d_DIA_Z" % count, "COMPASS_DIA%d_Z" % count, MAG_DIA + 0.1 * ((count+1) % compass_count)),
|
||||
("SIM_MAG%d_ODI_X" % count, "COMPASS_ODI%d_X" % count, MAG_ODI + 0.001 * ((count+2) % compass_count)),
|
||||
("SIM_MAG%d_ODI_Y" % count, "COMPASS_ODI%d_Y" % count, MAG_ODI + 0.001 * ((count+3) % compass_count)),
|
||||
("SIM_MAG%d_ODI_Z" % count, "COMPASS_ODI%d_Z" % count, MAG_ODI + 0.001 * ((count+1) % compass_count)), ],
|
||||
]
|
||||
self.progress("Setting calibration mode")
|
||||
self.wait_heartbeat()
|
||||
|
@ -7185,7 +7197,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
# for count in range(2, compass_count + 1):
|
||||
# self.set_parameter("SIM_MAG%d_ORIENT" % count, MAG_ORIENT * (count % 41))
|
||||
# # set compass external to check that orientation is found and auto set
|
||||
# self.set_parameter("COMPASS%d_EXTERN" % count, 1)
|
||||
# self.set_parameter("COMPASS_EXTERN%d" % count, 1)
|
||||
to_set = {}
|
||||
for param_set in params:
|
||||
for param in param_set:
|
||||
|
@ -7199,8 +7211,9 @@ Also, ignores heartbeats not from our target system'''
|
|||
# Change the default value to unexpected 42
|
||||
self.forty_two_mag_dia_odi_parameters()
|
||||
self.progress("Zeroing Mags orientations")
|
||||
for count in range(1, compass_count + 1):
|
||||
self.set_parameter("COMPASS%d_ORIENT" % count, 0)
|
||||
self.set_parameter("COMPASS_ORIENT", 0)
|
||||
for count in range(2, compass_count + 1):
|
||||
self.set_parameter("COMPASS_ORIENT%d" % count, 0)
|
||||
|
||||
# Only care about compass prearm
|
||||
self.set_parameter("ARMING_CHECK", 4)
|
||||
|
@ -7368,9 +7381,9 @@ Also, ignores heartbeats not from our target system'''
|
|||
timeout=20,
|
||||
)
|
||||
self.check_mag_parameters(params, compass_tnumber)
|
||||
self.verify_parameter_values({"COMPASS1_ORIENT": self.get_parameter("SIM_MAG_ORIENT")})
|
||||
self.verify_parameter_values({"COMPASS_ORIENT": self.get_parameter("SIM_MAG_ORIENT")})
|
||||
for count in range(2, compass_tnumber + 1):
|
||||
self.verify_parameter_values({"COMPASS%d_ORIENT" % count: self.get_parameter("SIM_MAG%d_ORIENT" % count)})
|
||||
self.verify_parameter_values({"COMPASS_ORIENT%d" % count: self.get_parameter("SIM_MAG%d_ORIENT" % count)})
|
||||
self.try_arm(False, "Compass calibrated requires reboot")
|
||||
|
||||
# test buzzer/notify ?
|
||||
|
@ -7385,7 +7398,7 @@ Also, ignores heartbeats not from our target system'''
|
|||
(_in, _out, value) = param
|
||||
self.set_parameter(_out, value)
|
||||
for count in range(compass_tnumber + 1, compass_count + 1):
|
||||
self.set_parameter("COMPASS%d_ORIENT" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))
|
||||
self.set_parameter("COMPASS_ORIENT%d" % count, self.get_parameter("SIM_MAG%d_ORIENT" % count))
|
||||
self.arm_vehicle()
|
||||
self.progress("Test calibration rejection when armed")
|
||||
self.run_cmd(mavutil.mavlink.MAV_CMD_DO_START_MAG_CAL,
|
||||
|
@ -7454,25 +7467,35 @@ Also, ignores heartbeats not from our target system'''
|
|||
parameter_mappings[key] = key
|
||||
for (old_compass_num, new_compass_num) in transforms:
|
||||
old_key_compass_bit = str(old_compass_num)
|
||||
if old_key_compass_bit == "1":
|
||||
old_key_compass_bit = ""
|
||||
new_key_compass_bit = str(new_compass_num)
|
||||
if new_key_compass_bit == "1":
|
||||
new_key_compass_bit = ""
|
||||
# vectors first:
|
||||
for key_vector_bit in ["OFS", "DIA", "ODI", "MOT"]:
|
||||
for axis in "X", "Y", "Z":
|
||||
old_key = "COMPASS%s_%s_%s" % (old_key_compass_bit,
|
||||
key_vector_bit,
|
||||
old_key = "COMPASS_%s%s_%s" % (key_vector_bit,
|
||||
old_key_compass_bit,
|
||||
axis)
|
||||
new_key = "COMPASS%s_%s_%s" % (new_key_compass_bit,
|
||||
key_vector_bit,
|
||||
new_key = "COMPASS_%s%s_%s" % (key_vector_bit,
|
||||
new_key_compass_bit,
|
||||
axis)
|
||||
parameter_mappings[old_key] = new_key
|
||||
# then non-vectorey bits:
|
||||
for key_bit in "SCALE", "ORIENT":
|
||||
old_key = "COMPASS%s_%s" % (old_key_compass_bit, key_bit)
|
||||
new_key = "COMPASS%s_%s" % (new_key_compass_bit, key_bit)
|
||||
old_key = "COMPASS_%s%s" % (key_bit, old_key_compass_bit)
|
||||
new_key = "COMPASS_%s%s" % (key_bit, new_key_compass_bit)
|
||||
parameter_mappings[old_key] = new_key
|
||||
# then a sore thumb:
|
||||
old_key = "COMPASS%s_EXTERN" % old_key_compass_bit
|
||||
new_key = "COMPASS%s_EXTERN" % new_key_compass_bit
|
||||
if old_key_compass_bit == "":
|
||||
old_key = "COMPASS_EXTERNAL"
|
||||
else:
|
||||
old_key = "COMPASS_EXTERN%s" % old_key_compass_bit
|
||||
if new_key_compass_bit == "":
|
||||
new_key = "COMPASS_EXTERNAL"
|
||||
else:
|
||||
new_key = "COMPASS_EXTERN%s" % new_key_compass_bit
|
||||
parameter_mappings[old_key] = new_key
|
||||
|
||||
for key in values.keys():
|
||||
|
@ -7488,53 +7511,53 @@ Also, ignores heartbeats not from our target system'''
|
|||
ex = None
|
||||
try:
|
||||
originals = {
|
||||
"COMPASS1_OFS_X": 1.1,
|
||||
"COMPASS1_OFS_Y": 1.2,
|
||||
"COMPASS1_OFS_Z": 1.3,
|
||||
"COMPASS1_DIA_X": 1.4,
|
||||
"COMPASS1_DIA_Y": 1.5,
|
||||
"COMPASS1_DIA_Z": 1.6,
|
||||
"COMPASS1_ODI_X": 1.7,
|
||||
"COMPASS1_ODI_Y": 1.8,
|
||||
"COMPASS1_ODI_Z": 1.9,
|
||||
"COMPASS1_MOT_X": 1.91,
|
||||
"COMPASS1_MOT_Y": 1.92,
|
||||
"COMPASS1_MOT_Z": 1.93,
|
||||
"COMPASS1_SCALE": 1.94,
|
||||
"COMPASS1_ORIENT": 1,
|
||||
"COMPASS1_EXTERN": 2,
|
||||
"COMPASS_OFS_X": 1.1,
|
||||
"COMPASS_OFS_Y": 1.2,
|
||||
"COMPASS_OFS_Z": 1.3,
|
||||
"COMPASS_DIA_X": 1.4,
|
||||
"COMPASS_DIA_Y": 1.5,
|
||||
"COMPASS_DIA_Z": 1.6,
|
||||
"COMPASS_ODI_X": 1.7,
|
||||
"COMPASS_ODI_Y": 1.8,
|
||||
"COMPASS_ODI_Z": 1.9,
|
||||
"COMPASS_MOT_X": 1.91,
|
||||
"COMPASS_MOT_Y": 1.92,
|
||||
"COMPASS_MOT_Z": 1.93,
|
||||
"COMPASS_SCALE": 1.94,
|
||||
"COMPASS_ORIENT": 1,
|
||||
"COMPASS_EXTERNAL": 2,
|
||||
|
||||
"COMPASS2_OFS_X": 2.1,
|
||||
"COMPASS2_OFS_Y": 2.2,
|
||||
"COMPASS2_OFS_Z": 2.3,
|
||||
"COMPASS2_DIA_X": 2.4,
|
||||
"COMPASS2_DIA_Y": 2.5,
|
||||
"COMPASS2_DIA_Z": 2.6,
|
||||
"COMPASS2_ODI_X": 2.7,
|
||||
"COMPASS2_ODI_Y": 2.8,
|
||||
"COMPASS2_ODI_Z": 2.9,
|
||||
"COMPASS2_MOT_X": 2.91,
|
||||
"COMPASS2_MOT_Y": 2.92,
|
||||
"COMPASS2_MOT_Z": 2.93,
|
||||
"COMPASS2_SCALE": 2.94,
|
||||
"COMPASS2_ORIENT": 3,
|
||||
"COMPASS2_EXTERN": 4,
|
||||
"COMPASS_OFS2_X": 2.1,
|
||||
"COMPASS_OFS2_Y": 2.2,
|
||||
"COMPASS_OFS2_Z": 2.3,
|
||||
"COMPASS_DIA2_X": 2.4,
|
||||
"COMPASS_DIA2_Y": 2.5,
|
||||
"COMPASS_DIA2_Z": 2.6,
|
||||
"COMPASS_ODI2_X": 2.7,
|
||||
"COMPASS_ODI2_Y": 2.8,
|
||||
"COMPASS_ODI2_Z": 2.9,
|
||||
"COMPASS_MOT2_X": 2.91,
|
||||
"COMPASS_MOT2_Y": 2.92,
|
||||
"COMPASS_MOT2_Z": 2.93,
|
||||
"COMPASS_SCALE2": 2.94,
|
||||
"COMPASS_ORIENT2": 3,
|
||||
"COMPASS_EXTERN2": 4,
|
||||
|
||||
"COMPASS3_OFS_X": 3.1,
|
||||
"COMPASS3_OFS_Y": 3.2,
|
||||
"COMPASS3_OFS_Z": 3.3,
|
||||
"COMPASS3_DIA_X": 3.4,
|
||||
"COMPASS3_DIA_Y": 3.5,
|
||||
"COMPASS3_DIA_Z": 3.6,
|
||||
"COMPASS3_ODI_X": 3.7,
|
||||
"COMPASS3_ODI_Y": 3.8,
|
||||
"COMPASS3_ODI_Z": 3.9,
|
||||
"COMPASS3_MOT_X": 3.91,
|
||||
"COMPASS3_MOT_Y": 3.92,
|
||||
"COMPASS3_MOT_Z": 3.93,
|
||||
"COMPASS3_SCALE": 3.94,
|
||||
"COMPASS3_ORIENT": 5,
|
||||
"COMPASS3_EXTERN": 6,
|
||||
"COMPASS_OFS3_X": 3.1,
|
||||
"COMPASS_OFS3_Y": 3.2,
|
||||
"COMPASS_OFS3_Z": 3.3,
|
||||
"COMPASS_DIA3_X": 3.4,
|
||||
"COMPASS_DIA3_Y": 3.5,
|
||||
"COMPASS_DIA3_Z": 3.6,
|
||||
"COMPASS_ODI3_X": 3.7,
|
||||
"COMPASS_ODI3_Y": 3.8,
|
||||
"COMPASS_ODI3_Z": 3.9,
|
||||
"COMPASS_MOT3_X": 3.91,
|
||||
"COMPASS_MOT3_Y": 3.92,
|
||||
"COMPASS_MOT3_Z": 3.93,
|
||||
"COMPASS_SCALE3": 3.94,
|
||||
"COMPASS_ORIENT3": 5,
|
||||
"COMPASS_EXTERN3": 6,
|
||||
}
|
||||
|
||||
# quick sanity check to ensure all values are unique:
|
||||
|
@ -7593,35 +7616,35 @@ Also, ignores heartbeats not from our target system'''
|
|||
MAG_OFS_Y = 200
|
||||
MAG_OFS_Z = 300
|
||||
wanted = {
|
||||
"COMPASS1_OFS_X": (MAG_OFS_X, 3.0),
|
||||
"COMPASS1_OFS_Y": (MAG_OFS_Y, 3.0),
|
||||
"COMPASS1_OFS_Z": (MAG_OFS_Z, 3.0),
|
||||
"COMPASS1_DIA_X": 1,
|
||||
"COMPASS1_DIA_Y": 1,
|
||||
"COMPASS1_DIA_Z": 1,
|
||||
"COMPASS1_ODI_X": 0,
|
||||
"COMPASS1_ODI_Y": 0,
|
||||
"COMPASS1_ODI_Z": 0,
|
||||
"COMPASS_OFS_X": (MAG_OFS_X, 3.0),
|
||||
"COMPASS_OFS_Y": (MAG_OFS_Y, 3.0),
|
||||
"COMPASS_OFS_Z": (MAG_OFS_Z, 3.0),
|
||||
"COMPASS_DIA_X": 1,
|
||||
"COMPASS_DIA_Y": 1,
|
||||
"COMPASS_DIA_Z": 1,
|
||||
"COMPASS_ODI_X": 0,
|
||||
"COMPASS_ODI_Y": 0,
|
||||
"COMPASS_ODI_Z": 0,
|
||||
|
||||
"COMPASS2_OFS_X": (MAG_OFS_X, 3.0),
|
||||
"COMPASS2_OFS_Y": (MAG_OFS_Y, 3.0),
|
||||
"COMPASS2_OFS_Z": (MAG_OFS_Z, 3.0),
|
||||
"COMPASS2_DIA_X": 1,
|
||||
"COMPASS2_DIA_Y": 1,
|
||||
"COMPASS2_DIA_Z": 1,
|
||||
"COMPASS2_ODI_X": 0,
|
||||
"COMPASS2_ODI_Y": 0,
|
||||
"COMPASS2_ODI_Z": 0,
|
||||
"COMPASS_OFS2_X": (MAG_OFS_X, 3.0),
|
||||
"COMPASS_OFS2_Y": (MAG_OFS_Y, 3.0),
|
||||
"COMPASS_OFS2_Z": (MAG_OFS_Z, 3.0),
|
||||
"COMPASS_DIA2_X": 1,
|
||||
"COMPASS_DIA2_Y": 1,
|
||||
"COMPASS_DIA2_Z": 1,
|
||||
"COMPASS_ODI2_X": 0,
|
||||
"COMPASS_ODI2_Y": 0,
|
||||
"COMPASS_ODI2_Z": 0,
|
||||
|
||||
"COMPASS3_OFS_X": (MAG_OFS_X, 3.0),
|
||||
"COMPASS3_OFS_Y": (MAG_OFS_Y, 3.0),
|
||||
"COMPASS3_OFS_Z": (MAG_OFS_Z, 3.0),
|
||||
"COMPASS3_DIA_X": 1,
|
||||
"COMPASS3_DIA_Y": 1,
|
||||
"COMPASS3_DIA_Z": 1,
|
||||
"COMPASS3_ODI_X": 0,
|
||||
"COMPASS3_ODI_Y": 0,
|
||||
"COMPASS3_ODI_Z": 0,
|
||||
"COMPASS_OFS3_X": (MAG_OFS_X, 3.0),
|
||||
"COMPASS_OFS3_Y": (MAG_OFS_Y, 3.0),
|
||||
"COMPASS_OFS3_Z": (MAG_OFS_Z, 3.0),
|
||||
"COMPASS_DIA3_X": 1,
|
||||
"COMPASS_DIA3_Y": 1,
|
||||
"COMPASS_DIA3_Z": 1,
|
||||
"COMPASS_ODI3_X": 0,
|
||||
"COMPASS_ODI3_Y": 0,
|
||||
"COMPASS_ODI3_Z": 0,
|
||||
}
|
||||
self.set_parameters({
|
||||
"SIM_MAG_OFS_X": MAG_OFS_X,
|
||||
|
|
|
@ -2,15 +2,15 @@ EK2_ENABLE 1
|
|||
FRAME_TYPE 0
|
||||
FS_THR_ENABLE 1
|
||||
BATT_MONITOR 4
|
||||
COMPASS1_OFS_X 5
|
||||
COMPASS1_OFS_Y 13
|
||||
COMPASS1_OFS_Z -18
|
||||
COMPASS2_OFS_X 5
|
||||
COMPASS2_OFS_Y 13
|
||||
COMPASS2_OFS_Z -18
|
||||
COMPASS3_OFS_X 5
|
||||
COMPASS3_OFS_Y 13
|
||||
COMPASS3_OFS_Z -18
|
||||
COMPASS_OFS_X 5
|
||||
COMPASS_OFS_Y 13
|
||||
COMPASS_OFS_Z -18
|
||||
COMPASS_OFS2_X 5
|
||||
COMPASS_OFS2_Y 13
|
||||
COMPASS_OFS2_Z -18
|
||||
COMPASS_OFS3_X 5
|
||||
COMPASS_OFS3_Y 13
|
||||
COMPASS_OFS3_Z -18
|
||||
FRAME_CLASS 1
|
||||
RC1_MAX 2000
|
||||
RC1_MIN 1000
|
||||
|
|
|
@ -6,15 +6,15 @@ FRAME_TYPE 0
|
|||
BATT_MONITOR 4
|
||||
FS_THR_ENABLE 1
|
||||
COMPASS_LEARN 0
|
||||
COMPASS1_OFS_X 5
|
||||
COMPASS1_OFS_Y 13
|
||||
COMPASS1_OFS_Z -18
|
||||
COMPASS2_OFS_X 5
|
||||
COMPASS2_OFS_Y 13
|
||||
COMPASS2_OFS_Z -18
|
||||
COMPASS3_OFS_X 5
|
||||
COMPASS3_OFS_Y 13
|
||||
COMPASS3_OFS_Z -18
|
||||
COMPASS_OFS_X 5
|
||||
COMPASS_OFS_Y 13
|
||||
COMPASS_OFS_Z -18
|
||||
COMPASS_OFS2_X 5
|
||||
COMPASS_OFS2_Y 13
|
||||
COMPASS_OFS2_Z -18
|
||||
COMPASS_OFS3_X 5
|
||||
COMPASS_OFS3_Y 13
|
||||
COMPASS_OFS3_Z -18
|
||||
RC1_MAX 2000.000000
|
||||
RC1_MIN 1000.000000
|
||||
RC1_TRIM 1500.000000
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
BATT_MONITOR 4.0000
|
||||
COMPASS2_OFS_X 5.0000
|
||||
COMPASS2_OFS_Y 13.0000
|
||||
COMPASS2_OFS_Z -18.0000
|
||||
COMPASS3_OFS_X 1.0000
|
||||
COMPASS3_OFS_Y 1.0000
|
||||
COMPASS3_OFS_Z 1.0000
|
||||
COMPASS1_OFS_X 2.8749
|
||||
COMPASS1_OFS_Y -21.8262
|
||||
COMPASS1_OFS_Z -21.8422
|
||||
COMPASS_OFS2_X 5.0000
|
||||
COMPASS_OFS2_Y 13.0000
|
||||
COMPASS_OFS2_Z -18.0000
|
||||
COMPASS_OFS3_X 1.0000
|
||||
COMPASS_OFS3_Y 1.0000
|
||||
COMPASS_OFS3_Z 1.0000
|
||||
COMPASS_OFS_X 2.8749
|
||||
COMPASS_OFS_Y -21.8262
|
||||
COMPASS_OFS_Z -21.8422
|
||||
FLTMODE1 7.0000
|
||||
FLTMODE2 9.0000
|
||||
FLTMODE3 6.0000
|
||||
|
|
|
@ -1,13 +1,13 @@
|
|||
BATT_MONITOR 4.0000
|
||||
COMPASS2_OFS_X 5.0000
|
||||
COMPASS2_OFS_Y 13.0000
|
||||
COMPASS2_OFS_Z -18.0000
|
||||
COMPASS3_OFS_X 1.0000
|
||||
COMPASS3_OFS_Y 1.0000
|
||||
COMPASS3_OFS_Z 1.0000
|
||||
COMPASS1_OFS_X 2.8749
|
||||
COMPASS1_OFS_Y -21.8262
|
||||
COMPASS1_OFS_Z -21.8422
|
||||
COMPASS_OFS2_X 5.0000
|
||||
COMPASS_OFS2_Y 13.0000
|
||||
COMPASS_OFS2_Z -18.0000
|
||||
COMPASS_OFS3_X 1.0000
|
||||
COMPASS_OFS3_Y 1.0000
|
||||
COMPASS_OFS3_Z 1.0000
|
||||
COMPASS_OFS_X 2.8749
|
||||
COMPASS_OFS_Y -21.8262
|
||||
COMPASS_OFS_Z -21.8422
|
||||
FLTMODE1 7.0000
|
||||
FLTMODE2 9.0000
|
||||
FLTMODE3 6.0000
|
||||
|
|
|
@ -3,15 +3,15 @@ FS_THR_ENABLE 1
|
|||
ATC_RAT_YAW_P 0.09
|
||||
ATC_RAT_YAW_I 0.009
|
||||
BATT_MONITOR 4
|
||||
COMPASS1_OFS_X 5
|
||||
COMPASS1_OFS_Y 13
|
||||
COMPASS1_OFS_Z -18
|
||||
COMPASS2_OFS_X 5
|
||||
COMPASS2_OFS_Y 13
|
||||
COMPASS2_OFS_Z -18
|
||||
COMPASS3_OFS_X 5
|
||||
COMPASS3_OFS_Y 13
|
||||
COMPASS3_OFS_Z -18
|
||||
COMPASS_OFS_X 5
|
||||
COMPASS_OFS_Y 13
|
||||
COMPASS_OFS_Z -18
|
||||
COMPASS_OFS2_X 5
|
||||
COMPASS_OFS2_Y 13
|
||||
COMPASS_OFS2_Z -18
|
||||
COMPASS_OFS3_X 5
|
||||
COMPASS_OFS3_Y 13
|
||||
COMPASS_OFS3_Z -18
|
||||
FENCE_RADIUS 150
|
||||
FRAME_CLASS 1
|
||||
RC1_MAX 2000.000000
|
||||
|
|
|
@ -12,15 +12,15 @@ ARSPD_FBW_MAX 35
|
|||
ARSPD_FBW_MIN 6
|
||||
ARSPD_USE 1
|
||||
AUTOTUNE_LEVEL 8
|
||||
COMPASS2_OFS_X -0.420265
|
||||
COMPASS2_OFS_Y -0.726942
|
||||
COMPASS2_OFS_Z 6.665476
|
||||
COMPASS3_OFS_X -0.420265
|
||||
COMPASS3_OFS_Y -0.726942
|
||||
COMPASS3_OFS_Z 6.665476
|
||||
COMPASS1_OFS_X -0.453570
|
||||
COMPASS1_OFS_Y -0.585846
|
||||
COMPASS1_OFS_Z 6.815743
|
||||
COMPASS_OFS2_X -0.420265
|
||||
COMPASS_OFS2_Y -0.726942
|
||||
COMPASS_OFS2_Z 6.665476
|
||||
COMPASS_OFS3_X -0.420265
|
||||
COMPASS_OFS3_Y -0.726942
|
||||
COMPASS_OFS3_Z 6.665476
|
||||
COMPASS_OFS_X -0.453570
|
||||
COMPASS_OFS_Y -0.585846
|
||||
COMPASS_OFS_Z 6.815743
|
||||
EK2_ENABLE 1
|
||||
EK2_IMU_MASK 3
|
||||
FBWB_CLIMB_RATE 10
|
||||
|
|
|
@ -3,15 +3,15 @@ ARSPD_TYPE 0
|
|||
ARSPD_FBW_MAX 35
|
||||
ARSPD_FBW_MIN 6
|
||||
AUTOTUNE_LEVEL 8
|
||||
COMPASS2_OFS_X -0.420265
|
||||
COMPASS2_OFS_Y -0.726942
|
||||
COMPASS2_OFS_Z 6.665476
|
||||
COMPASS3_OFS_X -0.420265
|
||||
COMPASS3_OFS_Y -0.726942
|
||||
COMPASS3_OFS_Z 6.665476
|
||||
COMPASS1_OFS_X -0.453570
|
||||
COMPASS1_OFS_Y -0.585846
|
||||
COMPASS1_OFS_Z 6.815743
|
||||
COMPASS_OFS2_X -0.420265
|
||||
COMPASS_OFS2_Y -0.726942
|
||||
COMPASS_OFS2_Z 6.665476
|
||||
COMPASS_OFS3_X -0.420265
|
||||
COMPASS_OFS3_Y -0.726942
|
||||
COMPASS_OFS3_Z 6.665476
|
||||
COMPASS_OFS_X -0.453570
|
||||
COMPASS_OFS_Y -0.585846
|
||||
COMPASS_OFS_Z 6.815743
|
||||
FBWB_CLIMB_RATE 10
|
||||
FLTMODE1 10
|
||||
FLTMODE2 11
|
||||
|
|
|
@ -4,15 +4,15 @@ ARSPD_FBW_MAX 35
|
|||
ARSPD_FBW_MIN 6
|
||||
ARSPD_USE 1
|
||||
AUTOTUNE_LEVEL 8
|
||||
COMPASS2_OFS_X -0.420265
|
||||
COMPASS2_OFS_Y -0.726942
|
||||
COMPASS2_OFS_Z 6.665476
|
||||
COMPASS3_OFS_X -0.420265
|
||||
COMPASS3_OFS_Y -0.726942
|
||||
COMPASS3_OFS_Z 6.665476
|
||||
COMPASS1_OFS_X -0.453570
|
||||
COMPASS1_OFS_Y -0.585846
|
||||
COMPASS1_OFS_Z 6.815743
|
||||
COMPASS_OFS2_X -0.420265
|
||||
COMPASS_OFS2_Y -0.726942
|
||||
COMPASS_OFS2_Z 6.665476
|
||||
COMPASS_OFS3_X -0.420265
|
||||
COMPASS_OFS3_Y -0.726942
|
||||
COMPASS_OFS3_Z 6.665476
|
||||
COMPASS_OFS_X -0.453570
|
||||
COMPASS_OFS_Y -0.585846
|
||||
COMPASS_OFS_Z 6.815743
|
||||
EK2_ENABLE 1
|
||||
EK2_IMU_MASK 3
|
||||
FBWB_CLIMB_RATE 10
|
||||
|
|
|
@ -4,15 +4,15 @@ ARSPD_FBW_MAX 35
|
|||
ARSPD_FBW_MIN 6
|
||||
ARSPD_USE 1
|
||||
AUTOTUNE_LEVEL 8
|
||||
COMPASS2_OFS_X -0.420265
|
||||
COMPASS2_OFS_Y -0.726942
|
||||
COMPASS2_OFS_Z 6.665476
|
||||
COMPASS3_OFS_X -0.420265
|
||||
COMPASS3_OFS_Y -0.726942
|
||||
COMPASS3_OFS_Z 6.665476
|
||||
COMPASS1_OFS_X -0.453570
|
||||
COMPASS1_OFS_Y -0.585846
|
||||
COMPASS1_OFS_Z 6.815743
|
||||
COMPASS_OFS2_X -0.420265
|
||||
COMPASS_OFS2_Y -0.726942
|
||||
COMPASS_OFS2_Z 6.665476
|
||||
COMPASS_OFS3_X -0.420265
|
||||
COMPASS_OFS3_Y -0.726942
|
||||
COMPASS_OFS3_Z 6.665476
|
||||
COMPASS_OFS_X -0.453570
|
||||
COMPASS_OFS_Y -0.585846
|
||||
COMPASS_OFS_Z 6.815743
|
||||
EK2_ENABLE 1
|
||||
EK2_IMU_MASK 3
|
||||
FBWB_CLIMB_RATE 10
|
||||
|
|
|
@ -4,15 +4,15 @@ ARSPD_FBW_MAX 35
|
|||
ARSPD_FBW_MIN 13
|
||||
ARSPD_USE 1
|
||||
AUTOTUNE_LEVEL 8
|
||||
COMPASS2_OFS_X -0.420265
|
||||
COMPASS2_OFS_Y -0.726942
|
||||
COMPASS2_OFS_Z 6.665476
|
||||
COMPASS3_OFS_X -0.420265
|
||||
COMPASS3_OFS_Y -0.726942
|
||||
COMPASS3_OFS_Z 6.665476
|
||||
COMPASS1_OFS_X -0.453570
|
||||
COMPASS1_OFS_Y -0.585846
|
||||
COMPASS1_OFS_Z 6.815743
|
||||
COMPASS_OFS2_X -0.420265
|
||||
COMPASS_OFS2_Y -0.726942
|
||||
COMPASS_OFS2_Z 6.665476
|
||||
COMPASS_OFS3_X -0.420265
|
||||
COMPASS_OFS3_Y -0.726942
|
||||
COMPASS_OFS3_Z 6.665476
|
||||
COMPASS_OFS_X -0.453570
|
||||
COMPASS_OFS_Y -0.585846
|
||||
COMPASS_OFS_Z 6.815743
|
||||
EK2_ENABLE 1
|
||||
EK2_IMU_MASK 3
|
||||
FBWB_CLIMB_RATE 10
|
||||
|
|
|
@ -4,15 +4,15 @@ ARSPD_FBW_MAX 35
|
|||
ARSPD_FBW_MIN 13
|
||||
ARSPD_USE 1
|
||||
AUTOTUNE_LEVEL 8
|
||||
COMPASS2_OFS_X -0.420265
|
||||
COMPASS2_OFS_Y -0.726942
|
||||
COMPASS2_OFS_Z 6.665476
|
||||
COMPASS3_OFS_X -0.420265
|
||||
COMPASS3_OFS_Y -0.726942
|
||||
COMPASS3_OFS3_Z 6.665476
|
||||
COMPASS1_OFS_X -0.453570
|
||||
COMPASS1_OFS_Y -0.585846
|
||||
COMPASS1_OFS_Z 6.815743
|
||||
COMPASS_OFS2_X -0.420265
|
||||
COMPASS_OFS2_Y -0.726942
|
||||
COMPASS_OFS2_Z 6.665476
|
||||
COMPASS_OFS3_X -0.420265
|
||||
COMPASS_OFS3_Y -0.726942
|
||||
COMPASS_OFS3_Z 6.665476
|
||||
COMPASS_OFS_X -0.453570
|
||||
COMPASS_OFS_Y -0.585846
|
||||
COMPASS_OFS_Z 6.815743
|
||||
EK2_ENABLE 1
|
||||
EK2_IMU_MASK 3
|
||||
EK3_ENABLE 1
|
||||
|
|
|
@ -32,15 +32,15 @@ BTN8_FUNCTION 48
|
|||
BTN8_SFUNCTION 0
|
||||
BTN9_FUNCTION 23
|
||||
BTN9_SFUNCTION 0
|
||||
COMPASS1_OFS_X 5
|
||||
COMPASS1_OFS_Y 13
|
||||
COMPASS1_OFS_Z -18
|
||||
COMPASS2_OFS_X 5
|
||||
COMPASS2_OFS_Y 13
|
||||
COMPASS2_OFS_Z -18
|
||||
COMPASS3_OFS_X 5
|
||||
COMPASS3_OFS_Y 13
|
||||
COMPASS3_OFS_Z -18
|
||||
COMPASS_OFS_X 5
|
||||
COMPASS_OFS_Y 13
|
||||
COMPASS_OFS_Z -18
|
||||
COMPASS_OFS2_X 5
|
||||
COMPASS_OFS2_Y 13
|
||||
COMPASS_OFS2_Z -18
|
||||
COMPASS_OFS3_X 5
|
||||
COMPASS_OFS3_Y 13
|
||||
COMPASS_OFS3_Z -18
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
|
|
|
@ -31,15 +31,15 @@ BTN8_FUNCTION 48
|
|||
BTN8_SFUNCTION 0
|
||||
BTN9_FUNCTION 23
|
||||
BTN9_SFUNCTION 0
|
||||
COMPASS1_OFS_X 5
|
||||
COMPASS1_OFS_Y 13
|
||||
COMPASS1_OFS_Z -18
|
||||
COMPASS2_OFS_X 5
|
||||
COMPASS2_OFS_Y 13
|
||||
COMPASS2_OFS_Z -18
|
||||
COMPASS3_OFS_X 5
|
||||
COMPASS3_OFS_Y 13
|
||||
COMPASS3_OFS_Z -18
|
||||
COMPASS_OFS_X 5
|
||||
COMPASS_OFS_Y 13
|
||||
COMPASS_OFS_Z -18
|
||||
COMPASS_OFS2_X 5
|
||||
COMPASS_OFS2_Y 13
|
||||
COMPASS_OFS2_Z -18
|
||||
COMPASS_OFS3_X 5
|
||||
COMPASS_OFS3_Y 13
|
||||
COMPASS_OFS3_Z -18
|
||||
INS_ACCOFFS_X 0.001
|
||||
INS_ACCOFFS_Y 0.001
|
||||
INS_ACCOFFS_Z 0.001
|
||||
|
|
|
@ -70,17 +70,58 @@ CHUTE_ENABLED,0
|
|||
CLI_ENABLED,0
|
||||
COMPASS_AUTODEC,1
|
||||
COMPASS_CAL_FIT,16
|
||||
COMPASS_DEC,0.2784546
|
||||
COMPASS_DEV_ID,0
|
||||
COMPASS_DEV_ID2,0
|
||||
COMPASS_DEV_ID3,0
|
||||
COMPASS_DIA_X,1
|
||||
COMPASS_DIA_Y,1
|
||||
COMPASS_DIA_Z,1
|
||||
COMPASS_DIA2_X,1
|
||||
COMPASS_DIA2_Y,1
|
||||
COMPASS_DIA2_Z,1
|
||||
COMPASS_DIA3_X,0
|
||||
COMPASS_DIA3_Y,0
|
||||
COMPASS_DIA3_Z,0
|
||||
COMPASS_EXTERN2,0
|
||||
COMPASS_EXTERN3,0
|
||||
COMPASS_EXTERNAL,0
|
||||
COMPASS_LEARN,1
|
||||
COMPASS1_OFS_X,16.29132
|
||||
COMPASS1_OFS_Y,4.398034
|
||||
COMPASS1_OFS_Z,-36.21775
|
||||
COMPASS2_OFS_X,16.29132
|
||||
COMPASS2_OFS_Y,4.398034
|
||||
COMPASS2_OFS_Z,-36.21775
|
||||
COMPASS_MOT_X,0
|
||||
COMPASS_MOT_Y,0
|
||||
COMPASS_MOT_Z,0
|
||||
COMPASS_MOT2_X,0
|
||||
COMPASS_MOT2_Y,0
|
||||
COMPASS_MOT2_Z,0
|
||||
COMPASS_MOT3_X,0
|
||||
COMPASS_MOT3_Y,0
|
||||
COMPASS_MOT3_Z,0
|
||||
COMPASS_MOTCT,0
|
||||
COMPASS_ODI_X,0
|
||||
COMPASS_ODI_Y,0
|
||||
COMPASS_ODI_Z,0
|
||||
COMPASS_ODI2_X,0
|
||||
COMPASS_ODI2_Y,0
|
||||
COMPASS_ODI2_Z,0
|
||||
COMPASS_ODI3_X,0
|
||||
COMPASS_ODI3_Y,0
|
||||
COMPASS_ODI3_Z,0
|
||||
COMPASS_OFS_X,16.29132
|
||||
COMPASS_OFS_Y,4.398034
|
||||
COMPASS_OFS_Z,-36.21775
|
||||
COMPASS_OFS2_X,16.29132
|
||||
COMPASS_OFS2_Y,4.398034
|
||||
COMPASS_OFS2_Z,-36.21775
|
||||
COMPASS_OFS3_X,0
|
||||
COMPASS_OFS3_Y,0
|
||||
COMPASS_OFS3_Z,0
|
||||
COMPASS_ORIENT,0
|
||||
COMPASS_ORIENT2,0
|
||||
COMPASS_ORIENT3,0
|
||||
COMPASS_PRIMARY,0
|
||||
COMPASS1_USE,1
|
||||
COMPASS2_USE,1
|
||||
COMPASS3_USE,1
|
||||
COMPASS_USE,1
|
||||
COMPASS_USE2,1
|
||||
COMPASS_USE3,1
|
||||
CRASH_ACC_THRESH,0
|
||||
CRASH_DETECT,0
|
||||
DSPOILR_RUD_RATE,100
|
||||
|
|
Loading…
Reference in New Issue