mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
Tools: autotest: refactor setting of rc defaults
This commit is contained in:
parent
9b540a6380
commit
fa37ad344b
@ -1014,10 +1014,11 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm)
|
|||||||
])
|
])
|
||||||
return ret
|
return ret
|
||||||
|
|
||||||
def set_rc_default(self):
|
def rc_defaults(self):
|
||||||
super(AutoTestRover, self).set_rc_default()
|
ret = super(AutoTestRover, self).rc_defaults()
|
||||||
self.set_rc(3, 1000)
|
ret[3] = 1000
|
||||||
self.set_rc(8, 1800)
|
ret[8] = 1800
|
||||||
|
return ret;
|
||||||
|
|
||||||
def default_mode(self):
|
def default_mode(self):
|
||||||
return 'MANUAL'
|
return 'MANUAL'
|
||||||
|
@ -2574,9 +2574,10 @@ class AutoTestCopter(AutoTest):
|
|||||||
def default_mode(self):
|
def default_mode(self):
|
||||||
return "STABILIZE"
|
return "STABILIZE"
|
||||||
|
|
||||||
def set_rc_default(self):
|
def rc_defaults(self):
|
||||||
super(AutoTestCopter, self).set_rc_default()
|
ret = super(AutoTestCopter, self).rc_defaults()
|
||||||
self.set_rc(3, 1000)
|
ret[3] = 1000
|
||||||
|
return ret
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
@ -2742,11 +2743,11 @@ class AutoTestHeli(AutoTestCopter):
|
|||||||
AVCHOME.heading)
|
AVCHOME.heading)
|
||||||
self.frame = 'heli'
|
self.frame = 'heli'
|
||||||
|
|
||||||
def set_rc_default(self):
|
def rc_defaults(self):
|
||||||
super(AutoTestCopter, self).set_rc_default()
|
ret = super(AutoTestHeli, self).rc_defaults()
|
||||||
self.progress("Lowering rotor speed")
|
ret[8] = 1000
|
||||||
self.set_rc(8, 1000)
|
ret[3] = 1000 # collective
|
||||||
self.set_rc(3, 1000) # collective
|
return ret
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
|
@ -730,10 +730,11 @@ class AutoTestPlane(AutoTest):
|
|||||||
lambda: self.fly_mission(
|
lambda: self.fly_mission(
|
||||||
os.path.join(testdir, "ap1.txt")))
|
os.path.join(testdir, "ap1.txt")))
|
||||||
|
|
||||||
def set_rc_default(self):
|
def rc_defaults(self):
|
||||||
super(AutoTestPlane, self).set_rc_default()
|
ret = super(AutoTestPlane, self).rc_defaults()
|
||||||
self.set_rc(3, 1000)
|
ret[3] = 1000
|
||||||
self.set_rc(8, 1800)
|
ret[8] = 1800
|
||||||
|
return ret
|
||||||
|
|
||||||
def default_mode(self):
|
def default_mode(self):
|
||||||
return "MANUAL"
|
return "MANUAL"
|
||||||
|
@ -53,9 +53,10 @@ class AutoTestBalanceBot(AutoTestRover):
|
|||||||
self.do_set_mode_via_command_long("HOLD")
|
self.do_set_mode_via_command_long("HOLD")
|
||||||
self.do_set_mode_via_command_long("MANUAL")
|
self.do_set_mode_via_command_long("MANUAL")
|
||||||
|
|
||||||
def set_rc_default(self):
|
def rc_defaults(self):
|
||||||
super(AutoTestBalanceBot, self).set_rc_default()
|
ret = super(AutoTestBalanceBot, self).rc_defaults()
|
||||||
self.set_rc(3, 1500)
|
ret[3] = 1500
|
||||||
|
return ret
|
||||||
|
|
||||||
def tests(self):
|
def tests(self):
|
||||||
'''return list of all tests'''
|
'''return list of all tests'''
|
||||||
|
@ -602,10 +602,36 @@ class AutoTest(ABC):
|
|||||||
self.progress("num_wp: %d" % num_wp)
|
self.progress("num_wp: %d" % num_wp)
|
||||||
return num_wp
|
return num_wp
|
||||||
|
|
||||||
|
def rc_defaults(self):
|
||||||
|
return {
|
||||||
|
1: 1500,
|
||||||
|
2: 1500,
|
||||||
|
3: 1500,
|
||||||
|
4: 1500,
|
||||||
|
5: 1500,
|
||||||
|
6: 1500,
|
||||||
|
7: 1500,
|
||||||
|
8: 1500,
|
||||||
|
9: 1500,
|
||||||
|
10: 1500,
|
||||||
|
11: 1500,
|
||||||
|
12: 1500,
|
||||||
|
13: 1500,
|
||||||
|
14: 1500,
|
||||||
|
15: 1500,
|
||||||
|
16: 1500,
|
||||||
|
}
|
||||||
|
|
||||||
|
def set_rc_from_map(self, _map):
|
||||||
|
for chan in _map:
|
||||||
|
value = _map[chan]
|
||||||
|
self.set_rc(chan, value)
|
||||||
|
# self.mavproxy.send('rc %u value\n' % (chan, value))
|
||||||
|
|
||||||
def set_rc_default(self):
|
def set_rc_default(self):
|
||||||
"""Setup all simulated RC control to 1500."""
|
"""Setup all simulated RC control to 1500."""
|
||||||
for chan in range(1, 16):
|
_defaults = self.rc_defaults()
|
||||||
self.mavproxy.send('rc %u 1500\n' % chan)
|
self.set_rc_from_map(_defaults)
|
||||||
|
|
||||||
def set_rc(self, chan, pwm, timeout=2000):
|
def set_rc(self, chan, pwm, timeout=2000):
|
||||||
"""Setup a simulated RC control to a PWM value"""
|
"""Setup a simulated RC control to a PWM value"""
|
||||||
|
Loading…
Reference in New Issue
Block a user