|
|
|
@ -410,6 +410,7 @@ class px4(Board):
@@ -410,6 +410,7 @@ class px4(Board):
|
|
|
|
|
def __init__(self): |
|
|
|
|
self.version = None |
|
|
|
|
self.use_px4io = True |
|
|
|
|
self.ROMFS_EXCLUDE = [] |
|
|
|
|
|
|
|
|
|
def configure(self, cfg): |
|
|
|
|
if not self.version: |
|
|
|
@ -444,6 +445,7 @@ class px4(Board):
@@ -444,6 +445,7 @@ class px4(Board):
|
|
|
|
|
'PX4NuttX', |
|
|
|
|
'uavcan', |
|
|
|
|
] |
|
|
|
|
env.ROMFS_EXCLUDE = self.ROMFS_EXCLUDE |
|
|
|
|
|
|
|
|
|
env.PX4_VERSION = self.version |
|
|
|
|
env.PX4_USE_PX4IO = True if self.use_px4io else False |
|
|
|
@ -456,17 +458,22 @@ class px4(Board):
@@ -456,17 +458,22 @@ class px4(Board):
|
|
|
|
|
bld.ap_version_append_str('PX4_GIT_VERSION', bld.git_submodule_head_hash('PX4Firmware', short=True)) |
|
|
|
|
bld.load('px4') |
|
|
|
|
|
|
|
|
|
def romfs_exclude(self, exclude): |
|
|
|
|
self.ROMFS_EXCLUDE += exclude |
|
|
|
|
|
|
|
|
|
class px4_v1(px4): |
|
|
|
|
name = 'px4-v1' |
|
|
|
|
def __init__(self): |
|
|
|
|
super(px4_v1, self).__init__() |
|
|
|
|
self.version = '1' |
|
|
|
|
self.romfs_exclude(['oreoled.bin']) |
|
|
|
|
|
|
|
|
|
class px4_v2(px4): |
|
|
|
|
name = 'px4-v2' |
|
|
|
|
def __init__(self): |
|
|
|
|
super(px4_v2, self).__init__() |
|
|
|
|
self.version = '2' |
|
|
|
|
self.romfs_exclude(['oreoled.bin']) |
|
|
|
|
|
|
|
|
|
class px4_v3(px4): |
|
|
|
|
name = 'px4-v3' |
|
|
|
@ -480,3 +487,4 @@ class px4_v4(px4):
@@ -480,3 +487,4 @@ class px4_v4(px4):
|
|
|
|
|
super(px4_v4, self).__init__() |
|
|
|
|
self.version = '4' |
|
|
|
|
self.use_px4io = False |
|
|
|
|
self.romfs_exclude(['oreoled.bin', 'px4io.bin']) |
|
|
|
|