mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Tools: vehicleinfo: factor out a default_frame method
This commit is contained in:
parent
3a9ac2ef40
commit
96cfba971c
@ -206,9 +206,12 @@ class VehicleInfo(object):
|
||||
}
|
||||
|
||||
|
||||
def default_frame(self, vehicle):
|
||||
return self.options[vehicle]["default_frame"]
|
||||
|
||||
def default_waf_target(self, vehicle):
|
||||
"""Returns a waf target based on vehicle type, which is often determined by which directory the user is in"""
|
||||
default_frame = self.options[vehicle]["default_frame"]
|
||||
default_frame = self.default_frame(vehicle)
|
||||
return self.options[vehicle]["frames"][default_frame]["waf_target"]
|
||||
|
||||
def options_for_frame(self, frame, vehicle, opts):
|
||||
|
Loading…
Reference in New Issue
Block a user