mirror of https://github.com/ArduPilot/ardupilot
autotest: add test for DroneCAN battery handling
This commit is contained in:
parent
dd56f2465b
commit
364452ffc8
|
@ -944,6 +944,19 @@ class sitl_periph_gps(sitl_periph):
|
|||
HAL_PERIPH_ENABLE_GPS = 1,
|
||||
)
|
||||
|
||||
class sitl_periph_battmon(sitl_periph):
|
||||
def configure_env(self, cfg, env):
|
||||
cfg.env.AP_PERIPH = 1
|
||||
super(sitl_periph_battmon, self).configure_env(cfg, env)
|
||||
env.DEFINES.update(
|
||||
HAL_BUILD_AP_PERIPH = 1,
|
||||
PERIPH_FW = 1,
|
||||
CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_battmon"',
|
||||
APJ_BOARD_ID = 101,
|
||||
|
||||
HAL_PERIPH_ENABLE_BATTERY = 1,
|
||||
)
|
||||
|
||||
class esp32(Board):
|
||||
abstract = True
|
||||
toolchain = 'xtensa-esp32-elf'
|
||||
|
|
|
@ -11574,6 +11574,57 @@ class AutoTestCopter(vehicle_test_suite.TestSuite):
|
|||
])
|
||||
return ret
|
||||
|
||||
def BattCANSplitAuxInfo(self):
|
||||
'''test CAN battery periphs'''
|
||||
self.start_subtest("Swap UAVCAN backend at runtime")
|
||||
self.set_parameters({
|
||||
"CAN_P1_DRIVER": 1,
|
||||
"BATT_MONITOR": 4, # 4 is ananlog volt+curr
|
||||
"BATT2_MONITOR": 8, # 8 is UAVCAN_BatteryInfo
|
||||
"BATT_SERIAL_NUM": 0,
|
||||
"BATT2_SERIAL_NUM": 0,
|
||||
"BATT_OPTIONS": 128, # allow split auxinfo
|
||||
"BATT2_OPTIONS": 128, # allow split auxinfo
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.delay_sim_time(2)
|
||||
self.set_parameters({
|
||||
"BATT_MONITOR": 8, # 8 is UAVCAN_BatteryInfo
|
||||
"BATT2_MONITOR": 4, # 8 is UAVCAN_BatteryInfo
|
||||
})
|
||||
self.delay_sim_time(2)
|
||||
self.set_parameters({
|
||||
"BATT_MONITOR": 4, # 8 is UAVCAN_BatteryInfo
|
||||
"BATT2_MONITOR": 8, # 8 is UAVCAN_BatteryInfo
|
||||
})
|
||||
self.delay_sim_time(2)
|
||||
self.set_parameters({
|
||||
"BATT_MONITOR": 8, # 8 is UAVCAN_BatteryInfo
|
||||
"BATT2_MONITOR": 4, # 8 is UAVCAN_BatteryInfo
|
||||
})
|
||||
self.delay_sim_time(2)
|
||||
|
||||
def BattCANReplaceRuntime(self):
|
||||
'''test CAN battery periphs'''
|
||||
self.start_subtest("Replace UAVCAN backend at runtime")
|
||||
self.set_parameters({
|
||||
"CAN_P1_DRIVER": 1,
|
||||
"BATT_MONITOR": 11, # 4 is ananlog volt+curr
|
||||
})
|
||||
self.reboot_sitl()
|
||||
self.delay_sim_time(2)
|
||||
self.set_parameters({
|
||||
"BATT_MONITOR": 8, # 4 is UAVCAN batterinfo
|
||||
})
|
||||
self.delay_sim_time(2)
|
||||
|
||||
def testcanbatt(self):
|
||||
ret = ([
|
||||
self.BattCANReplaceRuntime,
|
||||
self.BattCANSplitAuxInfo,
|
||||
])
|
||||
return ret
|
||||
|
||||
def tests(self):
|
||||
ret = []
|
||||
ret.extend(self.tests1a())
|
||||
|
@ -11637,3 +11688,9 @@ class AutoTestCAN(AutoTestCopter):
|
|||
|
||||
def tests(self):
|
||||
return self.testcan()
|
||||
|
||||
|
||||
class AutoTestBattCAN(AutoTestCopter):
|
||||
|
||||
def tests(self):
|
||||
return self.testcanbatt()
|
||||
|
|
|
@ -287,7 +287,9 @@ __bin_names = {
|
|||
"BalanceBot": "ardurover",
|
||||
"Sailboat": "ardurover",
|
||||
"SITLPeriphUniversal": ("sitl_periph_universal", "AP_Periph"),
|
||||
"SITLPeriphBattMon": ("sitl_periph_battmon", "AP_Periph"),
|
||||
"CAN": "arducopter",
|
||||
"BattCAN": "arducopter",
|
||||
}
|
||||
|
||||
|
||||
|
@ -358,11 +360,15 @@ tester_class_map = {
|
|||
"test.Sub": ardusub.AutoTestSub,
|
||||
"test.Tracker": antennatracker.AutoTestTracker,
|
||||
"test.CAN": arducopter.AutoTestCAN,
|
||||
"test.BattCAN": arducopter.AutoTestBattCAN,
|
||||
}
|
||||
|
||||
supplementary_test_binary_map = {
|
||||
"test.CAN": ["sitl_periph_universal:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501
|
||||
"sitl_periph_universal:AP_Periph:1:Tools/autotest/default_params/periph.parm"],
|
||||
"test.BattCAN": [
|
||||
"sitl_periph_battmon:AP_Periph:0:Tools/autotest/default_params/periph-battmon.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501
|
||||
],
|
||||
}
|
||||
|
||||
|
||||
|
@ -445,6 +451,10 @@ def run_step(step):
|
|||
vehicle_binary = 'bin/AP_Periph'
|
||||
board = 'sitl_periph_universal'
|
||||
|
||||
if step == 'build.SITLPeriphBattMon':
|
||||
vehicle_binary = 'bin/AP_Periph'
|
||||
board = 'sitl_periph_battmon'
|
||||
|
||||
if step == 'build.Replay':
|
||||
return util.build_replay(board='SITL')
|
||||
|
||||
|
@ -1081,6 +1091,9 @@ if __name__ == "__main__":
|
|||
'build.SITLPeriphUniversal',
|
||||
'test.CAN',
|
||||
|
||||
'build.SITLPeriphBattMon',
|
||||
'test.BattCAN',
|
||||
|
||||
# convertgps disabled as it takes 5 hours
|
||||
# 'convertgpx',
|
||||
]
|
||||
|
|
Loading…
Reference in New Issue