mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Tools: remove trailling semilocons
This commit is contained in:
parent
0aaa029f9b
commit
6c43ab27c1
@ -1165,7 +1165,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
old_pos.lon,
|
old_pos.lon,
|
||||||
old_pos.alt)
|
old_pos.alt)
|
||||||
self.progress("Waiting for non-zero-lat")
|
self.progress("Waiting for non-zero-lat")
|
||||||
tstart = self.get_sim_time();
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
gpi = self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
gpi = self.mav.recv_match(type='GLOBAL_POSITION_INT',
|
||||||
blocking=True)
|
blocking=True)
|
||||||
@ -1178,7 +1178,7 @@ class AutoTestCopter(AutoTest):
|
|||||||
|
|
||||||
self.takeoff(arm=True)
|
self.takeoff(arm=True)
|
||||||
self.set_rc(1, 1600)
|
self.set_rc(1, 1600)
|
||||||
tstart = self.get_sim_time();
|
tstart = self.get_sim_time()
|
||||||
while True:
|
while True:
|
||||||
vicon_pos = self.mav.recv_match(type='VICON_POSITION_ESTIMATE',
|
vicon_pos = self.mav.recv_match(type='VICON_POSITION_ESTIMATE',
|
||||||
blocking=True)
|
blocking=True)
|
||||||
|
@ -189,7 +189,7 @@ class AutoTest(ABC):
|
|||||||
timeout=1)
|
timeout=1)
|
||||||
if m is not None:
|
if m is not None:
|
||||||
print("Received (%s)" % str(m))
|
print("Received (%s)" % str(m))
|
||||||
break;
|
break
|
||||||
self.mavproxy.send("set streamrate %u\n" % self.sitl_streamrate())
|
self.mavproxy.send("set streamrate %u\n" % self.sitl_streamrate())
|
||||||
self.progress("Reboot complete")
|
self.progress("Reboot complete")
|
||||||
|
|
||||||
@ -346,7 +346,7 @@ class AutoTest(ABC):
|
|||||||
|
|
||||||
def armed(self):
|
def armed(self):
|
||||||
'''Return true if vehicle is armed and safetyoff'''
|
'''Return true if vehicle is armed and safetyoff'''
|
||||||
return self.mav.motors_armed();
|
return self.mav.motors_armed()
|
||||||
|
|
||||||
def arm_vehicle(self):
|
def arm_vehicle(self):
|
||||||
"""Arm vehicle with mavlink arm message."""
|
"""Arm vehicle with mavlink arm message."""
|
||||||
|
@ -170,7 +170,7 @@ def process_library(vehicle, library, pathprefix=None):
|
|||||||
error("Unknown vehicles (%s)" % delta)
|
error("Unknown vehicles (%s)" % delta)
|
||||||
debug("field[0]=%s vehicle=%s truename=%s field[1]=%s only_for_vehicles=%s\n" % (field[0], vehicle.name,vehicle.truename,field[1], str(only_for_vehicles)))
|
debug("field[0]=%s vehicle=%s truename=%s field[1]=%s only_for_vehicles=%s\n" % (field[0], vehicle.name,vehicle.truename,field[1], str(only_for_vehicles)))
|
||||||
if vehicle.truename not in only_for_vehicles:
|
if vehicle.truename not in only_for_vehicles:
|
||||||
continue;
|
continue
|
||||||
if field[0] in known_param_fields:
|
if field[0] in known_param_fields:
|
||||||
value = re.sub('@PREFIX@', library.name, field[2])
|
value = re.sub('@PREFIX@', library.name, field[2])
|
||||||
setattr(p, field[0], value)
|
setattr(p, field[0], value)
|
||||||
|
Loading…
Reference in New Issue
Block a user