diff --git a/donkeycar/benchmarks/tub.py b/donkeycar/benchmarks/tub.py index c22ce0d24..4f2501767 100644 --- a/donkeycar/benchmarks/tub.py +++ b/donkeycar/benchmarks/tub.py @@ -34,11 +34,11 @@ def benchmark(): contents = record_file.read_text() if contents: contents = json.loads(contents) - print('Record %s' % contents) + print(f'Record {contents}') if __name__ == "__main__": timer = timeit.Timer(benchmark) time_taken = timer.timeit(number=1) - print('Time taken %s seconds' % time_taken) + print(f'Time taken {time_taken} seconds') print('\nDone.') diff --git a/donkeycar/benchmarks/tub_v2.py b/donkeycar/benchmarks/tub_v2.py index 48087096a..800625faa 100644 --- a/donkeycar/benchmarks/tub_v2.py +++ b/donkeycar/benchmarks/tub_v2.py @@ -26,9 +26,9 @@ def benchmark(): deletions = np.random.randint(0, write_count, 100) tub.delete_records(deletions) - + for record in tub: - print('Record %s' % record) + print(f'Record {record}') tub.close() @@ -36,5 +36,5 @@ def benchmark(): if __name__ == "__main__": timer = timeit.Timer(benchmark) time_taken = timer.timeit(number=1) - print('Time taken %s seconds' % time_taken) + print(f'Time taken {time_taken} seconds') print('\nDone.') diff --git a/donkeycar/config.py b/donkeycar/config.py index 607fd35f9..b740c6e0f 100644 --- a/donkeycar/config.py +++ b/donkeycar/config.py @@ -12,7 +12,7 @@ class Config: - + def from_pyfile(self, filename): d = types.ModuleType('config') d.__file__ = filename @@ -20,16 +20,16 @@ def from_pyfile(self, filename): with open(filename, mode='rb') as config_file: exec(compile(config_file.read(), filename, 'exec'), d.__dict__) except IOError as e: - e.strerror = 'Unable to load configuration file (%s)' % e.strerror + e.strerror = f'Unable to load configuration file ({e.strerror})' raise self.from_object(d) return True - + def from_object(self, obj): for key in dir(obj): if key.isupper(): setattr(self, key, getattr(obj, key)) - + def __str__(self): result = [] for key in dir(self): @@ -44,7 +44,7 @@ def show(self): def load_config(config_path=None, myconfig="myconfig.py"): - + if config_path is None: import __main__ as main main_path = os.path.dirname(os.path.realpath(main.__file__)) @@ -53,7 +53,7 @@ def load_config(config_path=None, myconfig="myconfig.py"): local_config = os.path.join(os.path.curdir, 'config.py') if os.path.exists(local_config): config_path = local_config - + logger.info(f'loading config file: {config_path}') cfg = Config() cfg.from_pyfile(config_path) diff --git a/donkeycar/contrib/robohat/code-robocarstore.py b/donkeycar/contrib/robohat/code-robocarstore.py index 247680ab4..5208a3ba1 100644 --- a/donkeycar/contrib/robohat/code-robocarstore.py +++ b/donkeycar/contrib/robohat/code-robocarstore.py @@ -141,7 +141,7 @@ def main(): break last_input = time.monotonic() - logger.debug("Read from UART: %s" % (byte)) + logger.debug(f"Read from UART: {byte}") # if data is recieved, check if it is the end of a stream if(byte == b'\r'): diff --git a/donkeycar/contrib/robohat/code.py b/donkeycar/contrib/robohat/code.py index 35e8be106..c6ce070ba 100644 --- a/donkeycar/contrib/robohat/code.py +++ b/donkeycar/contrib/robohat/code.py @@ -128,7 +128,7 @@ def main(): if DEBUG: logger.info("Get: steering=%i, throttle=%i" % (int(steering.value), int(throttle.value))) - + if(USB_SERIAL): # simulator USB print("%i, %i" % (int(steering.value), int(throttle.value))) @@ -146,7 +146,7 @@ def main(): last_input = time.monotonic() if (DEBUG): - logger.debug("Read from UART: %s" % (byte)) + logger.debug(f"Read from UART: {byte}") # if data is recieved, check if it is the end of a stream if(byte == b'\r'): diff --git a/donkeycar/geom.py b/donkeycar/geom.py index 601b91027..175b0917f 100755 --- a/donkeycar/geom.py +++ b/donkeycar/geom.py @@ -5,7 +5,7 @@ ''' from .la import Vec2 -class LineSeg2d(object): +class LineSeg2d(): def __init__(self, x1, y1, x2, y2): a = Vec2(x1, y1) @@ -34,4 +34,3 @@ def cross_track_error(self, vec2_pt): if err_vec.cross(self.ray) < 0.0: sign = -1. return mag * sign - diff --git a/donkeycar/gym/gym_real.py b/donkeycar/gym/gym_real.py index eaf66904d..cf1508229 100755 --- a/donkeycar/gym/gym_real.py +++ b/donkeycar/gym/gym_real.py @@ -33,22 +33,22 @@ class DonkeyRealEnv(gym.Env): def __init__(self, time_step=0.05, frame_skip=2): print("starting DonkeyGym env") - + try: donkey_name = str(os.environ['DONKEY_NAME']) - except: + except Exception: donkey_name = 'my_robot1234' print("No DONKEY_NAME environment var. Using default:", donkey_name) try: mqtt_broker = str(os.environ['DONKEY_MQTT_BROKER']) - except: + except Exception: mqtt_broker = "iot.eclipse.org" print("No DONKEY_MQTT_BROKER environment var. Using default:", mqtt_broker) - + # start controller self.controller = DonkeyRemoteContoller(donkey_name=donkey_name, mqtt_broker=mqtt_broker) - + # steering and throttle self.action_space = spaces.Box(low=np.array([self.STEER_LIMIT_LEFT, self.THROTTLE_MIN]), high=np.array([self.STEER_LIMIT_RIGHT, self.THROTTLE_MAX]), dtype=np.float32 ) @@ -61,10 +61,10 @@ def __init__(self, time_step=0.05, frame_skip=2): # wait until loaded self.controller.wait_until_connected() - + def close(self): - self.controller.quit() + self.controller.quit() def step(self, action): for i in range(self.frame_skip): diff --git a/donkeycar/gym/remote_controller.py b/donkeycar/gym/remote_controller.py index 8954d823f..f1d31eddc 100755 --- a/donkeycar/gym/remote_controller.py +++ b/donkeycar/gym/remote_controller.py @@ -12,8 +12,8 @@ class DonkeyRemoteContoller: def __init__(self, donkey_name, mqtt_broker, sensor_size=(120, 160, 3)): - self.camera_sub = MQTTValueSub("donkey/%s/camera" % donkey_name, broker=mqtt_broker) - self.controller_pub = MQTTValuePub("donkey/%s/controls" % donkey_name, broker=mqtt_broker) + self.camera_sub = MQTTValueSub(f"donkey/{donkey_name}/camera", broker=mqtt_broker) + self.controller_pub = MQTTValuePub(f"donkey/{donkey_name}/controls", broker=mqtt_broker) self.jpgToImg = JpgToImgArr() self.sensor_size = sensor_size @@ -37,6 +37,3 @@ def observe(self): jpg = self.camera_sub.run() self.img = self.jpgToImg.run(jpg) return self.img - - - diff --git a/donkeycar/la.py b/donkeycar/la.py index 25096bfa3..08a3ec998 100755 --- a/donkeycar/la.py +++ b/donkeycar/la.py @@ -5,7 +5,7 @@ ''' import math -class Vec2(object): +class Vec2(): def __init__(self, x=0.0, y=0.0): self.x = x self.y = y @@ -34,7 +34,7 @@ def mag_squared(self): def mag(self): return math.sqrt(self.x * self.x + self.y * self.y) - + def scale(self, s): self.x *= s self.y *= s @@ -45,36 +45,36 @@ def scaled(self, s): r.x = self.x * s r.y = self.y * s return r - + def normalize(self): m = self.mag() self.scale(1.0 / m) return self - + def subtract(self, v): r = Vec2() r.x = self.x - v.x r.y = self.y - v.y return r - + def add(self, v): r = Vec2() r.x = self.x + v.x r.y = self.y + v.y return r - + def multiply(self, v): r = Vec2() r.x = self.x * v.x r.y = self.y * v.y return r - + def dot(self, v): return self.x * v.x + self.y * v.y - + def cross(self, v): #the sign tells you which side the other vector lies - return self.x * v.y - self.y * v.x + return self.x * v.y - self.y * v.x def dist(self, v): r = self.subtract(v) @@ -87,14 +87,14 @@ def reciprocal(self): if(self.y != 0.0): r.y = 1.0 / self.y return r - + def unit_angle(self, v): #note! requires normalized vectors as input #returns radian angle return math.acos(self.dot(v)) -class Vec3(object): +class Vec3(): def __init__(self, x=0.0, y=0.0, z=0.0): self.x = x self.y = y @@ -121,7 +121,7 @@ def __iadd__(self, other): #+= other def mag(self): return math.sqrt(self.x * self.x + self.y * self.y + self.z * self.z) - + def scale(self, s): self.x *= s self.y *= s @@ -134,7 +134,7 @@ def scaled(self, s): r.y = self.y * s r.z = self.z * s return r - + def normalize(self): m = self.mag() self.scale(1.0 / m) @@ -153,31 +153,31 @@ def subtract(self, v): r.y = self.y - v.y r.z = self.z - v.z return r - + def add(self, v): r = Vec3() r.x = self.x + v.x r.y = self.y + v.y r.z = self.z + v.z return r - + def multiply(self, v): r = Vec3() r.x = self.x * v.x r.y = self.y * v.y r.z = self.z * v.z return r - + def dot(self, v): return (self.x * v.x + self.y * v.y + self.z * v.z) - + def cross(self, v): r = Vec3() r.x = (self.y * v.z) - (self.z * v.y) r.y = (self.z * v.x) - (self.x * v.z) r.z = (self.x * v.y) - (self.y * v.x) return r - + def dist(self, v): r = self.subtract(v) return r.mag() @@ -191,18 +191,18 @@ def reciprocal(self): if(self.z != 0.0): r.z = 1.0 / self.z return r - + def unit_angle(self, v): #note! requires normalized vectors as input return math.acos(self.dot(v)) - + def Quat_RotY( radians ): halfAngle = radians * 0.5 sinHalf = math.sin(halfAngle) cosHalf = math.cos(halfAngle) return Quat(0.0, sinHalf, 0.0, cosHalf) -class Quat(object): +class Quat(): def __init__(self, x=0.0, y=0.0, z=0.0, w=1.0): self.x = x self.y = y @@ -248,8 +248,8 @@ def normalize(self): return self def normalized(self): - return self.scaled(1.0 / self.mag()) - + return self.scaled(1.0 / self.mag()) + def scale(self, s): self.x *= s self.y *= s @@ -271,13 +271,13 @@ def conjugate(self): def inverse(self): q0 = self.normalized() return q0.scale(-1.0) - + def multiply(self, q1, q2): self.x = q2.w * q1.x + q2.x * q1.w + q2.y * q1.z - q2.z * q1.y self.y = q2.w * q1.y + q2.y * q1.w + q2.z * q1.x - q2.x * q1.z self.z = q2.w * q1.z + q2.z * q1.w + q2.x * q1.y - q2.y * q1.x self.w = q2.w * q1.w - q2.x * q1.x - q2.y * q1.y - q2.z * q1.z - + def vector_transform(self, v): qxyz = Vec3(self.x, self.y, self.z) cross_v = qxyz.cross(v) @@ -302,7 +302,7 @@ def to_axis_angle(self): ''' halfa = math.acos(self.w) sinha = math.sin(halfa) - axis = Vec3() + axis = Vec3() if sinha != 0.0: axis.x = self.x / sinha axis.y = self.y / sinha @@ -312,7 +312,7 @@ def to_axis_angle(self): angle = 2.0 * halfa return axis, angle - + def getYAxisRot(self): c = Vec3() x2 = self.x + self.x @@ -322,27 +322,27 @@ def getYAxisRot(self): xz = self.x * z2 yy = self.y * y2 wy = self.w * y2 - + c.x = xz + wy c.y = 0.0 c.z = 1.0 - (xx + yy) cx2cz2 = c.x * c.x + c.z * c.z - + if cx2cz2 > 0.0: factor = 1.0 / math.sqrt(cx2cz2) c.x = c.x * factor c.z = c.z * factor else: return 0.0 - + if c.z <= -0.9999999: return math.pi - + if c.z >= 0.9999999: return 0.0 - + return math.atan2(c.x, c.z) - + def slerp(self, tval, low, high): lHigh = Quat() cosom = low.x*high.x + low.y*high.y + low.z*high.z + low.w*high.w @@ -357,7 +357,7 @@ def slerp(self, tval, low, high): lHigh.y = high.y lHigh.z = high.z lHigh.w = high.w - + FLOAT_EPSILON = 0.0000001 if ( (1.0 - cosom) > FLOAT_EPSILON ): #standard case (slerp) @@ -367,19 +367,19 @@ def slerp(self, tval, low, high): scalar0 = math.sin( ((1.0 - tval) * omega) ) * fOneOverSinom scalar1 = math.sin( (tval * omega) ) * fOneOverSinom else: - # "from" and "to" Quaternions are very close + # "from" and "to" Quaternions are very close # ... so we can do a linear interpolation scalar0 = 1.0 - tval scalar1 = tval - + # calculate final values self.x = scalar0 * low.x + scalar1 * lHigh.x self.y = scalar0 * low.y + scalar1 * lHigh.y self.z = scalar0 * low.z + scalar1 * lHigh.z - self.w = scalar0 * low.w + scalar1 * lHigh.w - + self.w = scalar0 * low.w + scalar1 * lHigh.w + -class Vec4(object): +class Vec4(): def __init__(self, x=0.0, y=0.0, z=0.0, w=0.0): self.x = x self.y = y @@ -407,7 +407,7 @@ def __iadd__(self, other): #+= other def mag(self): return math.sqrt(self.x * self.x + self.y * self.y + self.z * self.z + self.w * self.w) - + def scale(self, s): self.x *= s self.y *= s @@ -422,7 +422,7 @@ def scaled(self, s): r.z = self.z * s r.w = self.w * s return r - + def normalize(self): m = self.mag() self.scale(1.0 / m) @@ -430,8 +430,8 @@ def normalize(self): def normalized(self): m = self.mag() - return self.scaled(1.0 / m) - + return self.scaled(1.0 / m) + def subtract(self, v): r = Vec4() r.x = self.x - v.x @@ -439,7 +439,7 @@ def subtract(self, v): r.z = self.z - v.z r.w = self.w - v.w return r - + def add(self, v): r = Vec4() r.x = self.x + v.x @@ -447,17 +447,17 @@ def add(self, v): r.z = self.z + v.z r.w = self.w + v.w return r - + def multiply(self, v): r = Vec4() r.x = self.x * v.x r.y = self.y * v.y r.z = self.z * v.z return r - + def dot(self, v): return (self.x * v.x + self.y * v.y + self.z * v.z + self.w * v.w) - + def dist(self, v): r = self.subtract(v) return r.mag() @@ -483,7 +483,7 @@ def Det3x3(a1, a2, a3, b1, b2, b3, c1, c2, c3): b1 * Det2x2(a2, a3, c2, c3) + c1 * Det2x2(a2, a3, b2, b3)) -class Mat44(object): +class Mat44(): def __init__(self, a=Vec4(), b=Vec4(), c=Vec4(), d=Vec4()): self.a = a self.b = b @@ -495,7 +495,7 @@ def indentity(self): self.b = Vec4(0.0, 1.0, 0.0, 0.0) self.c = Vec4(0.0, 0.0, 1.0, 0.0) self.d = Vec4(0.0, 0.0, 0.0, 1.0) - + def fromQuat(self, q): #calculate coefficients x2 = q.x + q.x @@ -510,32 +510,32 @@ def fromQuat(self, q): wx = q.w * x2 wy = q.w * y2 wz = q.w * z2 - + self.a.x = 1.0 - (yy + zz) self.a.y = xy + wz self.a.z = xz - wy self.a.w = 0.0 - + self.b.x = xy - wz self.b.y = 1.0 - (xx + zz) self.b.z = yz + wx self.b.w = 0.0 - + self.c.x = xz + wy self.c.y = yz - wx self.c.z = 1.0 - (xx + yy) self.c.w = 0.0 - - self.d.x = 0.0 + + self.d.x = 0.0 self.d.y = 0.0 self.d.z = 0.0 self.d.w = 1.0 - + def setTranslation(self, trans): self.d.x = trans.x self.d.y = trans.y self.d.z = trans.z - + def affineTransform(self, v): x = self.a.x*v.x + self.b.x*v.y + self.c.x*v.z + self.d.x y = self.a.y*v.x + self.b.y*v.y + self.c.y*v.z + self.d.y @@ -558,25 +558,25 @@ def multiply_vec4(self, v): def multiply_mat44(self, src2): mtxOut = Mat44() - mtxOut.a.x = self.a.x*src2.a.x + self.a.y*src2.b.x + self.a.z*src2.c.x + self.a.w*src2.d.x; - mtxOut.a.y = self.a.x*src2.a.y + self.a.y*src2.b.y + self.a.z*src2.c.y + self.a.w*src2.d.y; - mtxOut.a.z = self.a.x*src2.a.z + self.a.y*src2.b.z + self.a.z*src2.c.z + self.a.w*src2.d.z; - mtxOut.a.w = self.a.x*src2.a.w + self.a.y*src2.b.w + self.a.z*src2.c.w + self.a.w*src2.d.w; - - mtxOut.b.x = self.b.x*src2.a.x + self.b.y*src2.b.x + self.b.z*src2.c.x + self.b.w*src2.d.x; - mtxOut.b.y = self.b.x*src2.a.y + self.b.y*src2.b.y + self.b.z*src2.c.y + self.b.w*src2.d.y; - mtxOut.b.z = self.b.x*src2.a.z + self.b.y*src2.b.z + self.b.z*src2.c.z + self.b.w*src2.d.z; - mtxOut.b.w = self.b.x*src2.a.w + self.b.y*src2.b.w + self.b.z*src2.c.w + self.b.w*src2.d.w; - - mtxOut.c.x = self.c.x*src2.a.x + self.c.y*src2.b.x + self.c.z*src2.c.x + self.c.w*src2.d.x; - mtxOut.c.y = self.c.x*src2.a.y + self.c.y*src2.b.y + self.c.z*src2.c.y + self.c.w*src2.d.y; - mtxOut.c.z = self.c.x*src2.a.z + self.c.y*src2.b.z + self.c.z*src2.c.z + self.c.w*src2.d.z; - mtxOut.c.w = self.c.x*src2.a.w + self.c.y*src2.b.w + self.c.z*src2.c.w + self.c.w*src2.d.w; - - mtxOut.d.x = self.d.x*src2.a.x + self.d.y*src2.b.x + self.d.z*src2.c.x + self.d.w*src2.d.x; - mtxOut.d.y = self.d.x*src2.a.y + self.d.y*src2.b.y + self.d.z*src2.c.y + self.d.w*src2.d.y; - mtxOut.d.z = self.d.x*src2.a.z + self.d.y*src2.b.z + self.d.z*src2.c.z + self.d.w*src2.d.z; - mtxOut.d.w = self.d.x*src2.a.w + self.d.y*src2.b.w + self.d.z*src2.c.w + self.d.w*src2.d.w; + mtxOut.a.x = self.a.x*src2.a.x + self.a.y*src2.b.x + self.a.z*src2.c.x + self.a.w*src2.d.x + mtxOut.a.y = self.a.x*src2.a.y + self.a.y*src2.b.y + self.a.z*src2.c.y + self.a.w*src2.d.y + mtxOut.a.z = self.a.x*src2.a.z + self.a.y*src2.b.z + self.a.z*src2.c.z + self.a.w*src2.d.z + mtxOut.a.w = self.a.x*src2.a.w + self.a.y*src2.b.w + self.a.z*src2.c.w + self.a.w*src2.d.w + + mtxOut.b.x = self.b.x*src2.a.x + self.b.y*src2.b.x + self.b.z*src2.c.x + self.b.w*src2.d.x + mtxOut.b.y = self.b.x*src2.a.y + self.b.y*src2.b.y + self.b.z*src2.c.y + self.b.w*src2.d.y + mtxOut.b.z = self.b.x*src2.a.z + self.b.y*src2.b.z + self.b.z*src2.c.z + self.b.w*src2.d.z + mtxOut.b.w = self.b.x*src2.a.w + self.b.y*src2.b.w + self.b.z*src2.c.w + self.b.w*src2.d.w + + mtxOut.c.x = self.c.x*src2.a.x + self.c.y*src2.b.x + self.c.z*src2.c.x + self.c.w*src2.d.x + mtxOut.c.y = self.c.x*src2.a.y + self.c.y*src2.b.y + self.c.z*src2.c.y + self.c.w*src2.d.y + mtxOut.c.z = self.c.x*src2.a.z + self.c.y*src2.b.z + self.c.z*src2.c.z + self.c.w*src2.d.z + mtxOut.c.w = self.c.x*src2.a.w + self.c.y*src2.b.w + self.c.z*src2.c.w + self.c.w*src2.d.w + + mtxOut.d.x = self.d.x*src2.a.x + self.d.y*src2.b.x + self.d.z*src2.c.x + self.d.w*src2.d.x + mtxOut.d.y = self.d.x*src2.a.y + self.d.y*src2.b.y + self.d.z*src2.c.y + self.d.w*src2.d.y + mtxOut.d.z = self.d.x*src2.a.z + self.d.y*src2.b.z + self.d.z*src2.c.z + self.d.w*src2.d.z + mtxOut.d.w = self.d.x*src2.a.w + self.d.y*src2.b.w + self.d.z*src2.c.w + self.d.w*src2.d.w return mtxOut @@ -593,11 +593,11 @@ def inverse(self): inv.a.x = Det2x2(self.b.y, self.b.z, self.c.y, self.c.z) * oodet inv.b.x = -Det2x2(self.b.x, self.b.z, self.c.x, self.c.z) * oodet inv.c.x = Det2x2(self.b.x, self.b.y, self.c.x, self.c.y) * oodet - + inv.a.y = -Det2x2(self.a.y, self.a.z, self.c.y, self.c.z) * oodet inv.b.y = Det2x2(self.a.x, self.a.z, self.c.x, self.c.z) * oodet inv.c.y = -Det2x2(self.a.x, self.a.y, self.c.x, self.c.y) * oodet - + inv.a.z = Det2x2(self.a.y, self.a.z, self.b.y, self.b.z) * oodet inv.b.z = -Det2x2(self.a.x, self.a.z, self.b.x, self.b.z) * oodet inv.c.z = Det2x2(self.a.x, self.a.y, self.b.x, self.b.y) * oodet @@ -610,7 +610,7 @@ def inverse(self): return(inv) -class Line3D(object): +class Line3D(): def __init__(self, a, b): self.origin = a diff --git a/donkeycar/management/base.py b/donkeycar/management/base.py index da5e649f5..9e148d049 100644 --- a/donkeycar/management/base.py +++ b/donkeycar/management/base.py @@ -46,7 +46,7 @@ def load_config(config_path, myconfig='myconfig.py'): return cfg -class BaseCommand(object): +class BaseCommand(): pass @@ -167,7 +167,7 @@ def run(self, args): s = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) s.connect(("8.8.8.8", 80)) ip = s.getsockname()[0] - print('Your IP address: %s ' % s.getsockname()[0]) + print(f'Your IP address: {s.getsockname()[0]} ') s.close() print("Finding your car's IP address...") @@ -225,7 +225,7 @@ def run(self, args): except ValueError as e: print(e) print("See pins.py for a description of pin specification strings.") - exit(-1) + sys.exit(-1) print(f'init pin {args.pwm_pin}') freq = int(args.pwmFreq) print(f"Using PWM freq: {freq}") diff --git a/donkeycar/management/joystick_creator.py b/donkeycar/management/joystick_creator.py index ee9b3e80c..626d572b0 100644 --- a/donkeycar/management/joystick_creator.py +++ b/donkeycar/management/joystick_creator.py @@ -10,10 +10,10 @@ try: from prettytable import PrettyTable -except: +except Exception: print("need: pip install PrettyTable") -class CreateJoystick(object): +class CreateJoystick(): def __init__(self): self.last_button = None @@ -61,14 +61,14 @@ def get_axis_move(self, duration=2.0): if self.last_axis in axis_samples: try: axis_samples[self.last_axis] = axis_samples[self.last_axis] + math.fabs(self.axis_val) - except: + except Exception: try: axis_samples[self.last_axis] = math.fabs(self.axis_val) - except: + except Exception: pass else: axis_samples[self.last_axis] = math.fabs(self.axis_val) - + most_movement = None most_val = 0 for key, value in axis_samples.items(): @@ -82,7 +82,7 @@ def clear_scr(self): print(chr(27) + "[2J") def create_joystick(self, args): - + self.clear_scr() print("##~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~##") print("## Welcome to Joystick Creator Wizard. ##") @@ -100,10 +100,10 @@ def create_joystick(self, args): print("Please plug-in your controller via USB or bluetooth. Make sure status lights are on and device is mapped.") input('Enter to continue ') self.clear_scr() - + self.init_js_device() print() - + self.init_polling_js() self.clear_scr() @@ -162,7 +162,7 @@ def init_js_device(self): if js_cr is None: ret = input("Failed to open device. try again? [Y/n] : ") if ret.upper() == "N": - exit(0) + sys.exit(0) self.js = js_cr.js input("Hit Enter to continue") @@ -184,10 +184,10 @@ def find_gyro(self): print() if len(self.gyro_axis) > 0: - print("Ok, we found %d axes that stream gyroscope data. We will ignore those during labelling and mapping." % len(self.gyro_axis)) + print(f"Ok, we found {len(self.gyro_axis)} axes that stream gyroscope data. We will ignore those during labelling and mapping.") else: print("Ok, we didn't see any events. So perhaps your controller doesn't emit gyroscope data. No problem.") - + input("Hit Enter to continue ") def get_code_from_button(self, button): @@ -220,7 +220,7 @@ def name_buttons(self): while not done: print('Tap a button to name it.') - + self.get_button_press() if self.last_button is None: @@ -233,7 +233,7 @@ def name_buttons(self): if code is not None: if code in self.js.button_names: - ret = input("This button has a name: %s. Are you done naming? (y/N) " % self.js.button_names[code]) + ret = input(f"This button has a name: {self.js.button_names[code]}. Are you done naming? (y/N) ") if ret.upper() == "Y": done = True break @@ -249,7 +249,7 @@ def name_buttons(self): self.clear_scr() self.print_config() - + def print_config(self): pt = PrettyTable() @@ -288,7 +288,7 @@ def name_axes(self): ret = input("Hit Enter to begin. D when done. ") if ret.upper() == 'D': break - + most_movement = self.get_axis_move() if most_movement is None: @@ -335,54 +335,55 @@ def write_python_class_file(self): print() try: outfile = open(pyth_filename, "wt") - except: + except Exception: ret = input("failed to open filename. Enter another filename? [Y,n]") if ret == "n": break pyth_filename = None print() - + if outfile is not None: classname = input("What is the name of joystick class? [default: MyJoystick] ") if len(classname) == 0: classname = "MyJoystick" file_header = \ - ''' + f''' from donkeycar.parts.controller import Joystick, JoystickController -class %s(Joystick): +class {classname}(Joystick): #An interface to a physical joystick available at /dev/input/js0 def __init__(self, *args, **kwargs): - super(%s, self).__init__(*args, **kwargs) + super({classname}, self).__init__(*args, **kwargs) + - \n''' % (classname, classname ) +''' outfile.write(file_header) outfile.write(' self.button_names = {\n') for key, value in self.js.button_names.items(): - outfile.write(" %s : '%s',\n" % (str(hex(key)), str(value))) + outfile.write(f" {str(hex(key))} : '{str(value)}',\n") outfile.write(' }\n\n\n') - + outfile.write(' self.axis_names = {\n') for key, value in self.js.axis_names.items(): - outfile.write(" %s : '%s',\n" % (str(hex(key)), str(value))) + outfile.write(f" {str(hex(key))} : '{str(value)}',\n") outfile.write(' }\n\n\n') js_controller = \ - ''' -class %sController(JoystickController): + f''' +class {classname}Controller(JoystickController): #A Controller object that maps inputs to actions def __init__(self, *args, **kwargs): - super(%sController, self).__init__(*args, **kwargs) + super({classname}Controller, self).__init__(*args, **kwargs) def init_js(self): #attempt to init joystick try: - self.js = %s(self.dev_fn) + self.js = {classname}(self.dev_fn) self.js.init() except FileNotFoundError: print(self.dev_fn, "not found.") @@ -392,18 +393,19 @@ def init_js(self): def init_trigger_maps(self): #init set of mapping from buttons to function calls - \n''' % (classname, classname, classname) + +''' outfile.write(js_controller) outfile.write(' self.button_down_trigger_map = {\n') for button, control in self.mapped_controls: - outfile.write(" '%s' : self.%s,\n" % (str(button), str(control))) + outfile.write(f" '{str(button)}' : self.{str(control)},\n") outfile.write(' }\n\n\n') - + outfile.write(' self.axis_trigger_map = {\n') for axis, control in self.axis_map: - outfile.write(" '%s' : self.%s,\n" % (str(axis), str(control))) + outfile.write(f" '{str(axis)}' : self.{str(control)},\n") outfile.write(' }\n\n\n') outfile.close() @@ -411,19 +413,19 @@ def init_trigger_maps(self): def map_control_axis(self, control_name, control_fn): while True: - axis = self.get_axis_action('Move the controller axis you wish to use for %s. Continue moving for 2 seconds.' % control_name) - + axis = self.get_axis_action(f'Move the controller axis you wish to use for {control_name}. Continue moving for 2 seconds.') + mapped = False if axis is None: - print("No mapping for %s." % control_name) + print(f"No mapping for {control_name}.") else: #print("axis", axis) code = self.get_code_from_button(axis) for key, value in self.js.axis_names.items(): #print('key', key, 'value', value) if key == code or value == code: - print('Mapping %s to %s.\n' % (value, control_name)) + print(f'Mapping {value} to {control_name}.\n') mapped = value break if mapped: @@ -465,7 +467,7 @@ def map_button_controls(self): ('toggle_constant_throttle', 'toggle the mode of supplying constant throttle'), ('toggle_manual_recording','toggles recording records on and off') ] - + self.mapped_controls = [] self.print_config() print() @@ -486,16 +488,16 @@ def map_button_controls(self): try: ret = " " while (not ret.isdigit() and ret.upper() != 'D') or (ret.isdigit() and (int(ret) < 1 or int(ret) > len(unmapped_controls))): - ret = input("Press the number of control to map (1-%d). D when done. " % len(unmapped_controls)) + ret = input(f"Press the number of control to map (1-{len(unmapped_controls)}). D when done. ") if ret.upper() == 'D': break iControl = int(ret) - 1 - except: + except Exception: continue - + print('Press the button to map to control:', unmapped_controls[iControl][0]) self.get_button_press() @@ -506,7 +508,7 @@ def map_button_controls(self): break else: code = self.get_code_from_button(self.last_button) - if code in self.js.button_names: + if code in self.js.button_names: button_name = self.js.button_names[code] else: button_name = self.last_button @@ -530,7 +532,7 @@ def revisit_topic(self): print("A)xes need renaming.") print("T)hrottle and steering need remap.") print("R)emap buttons to controls.") - + ret = input("Select option ").upper() if ret == 'H': done = True @@ -541,11 +543,11 @@ def revisit_topic(self): elif ret == 'T': self.map_steering_throttle() elif ret == 'R': - self.map_button_controls() + self.map_button_controls() def get_axis_action(self, prompt): - done = False + done = False while not done: print(prompt) ret = input("Hit Enter to begin. D when done. ") @@ -581,4 +583,3 @@ def run(self, args): self.create_joystick(args) except KeyboardInterrupt: self.shutdown() - diff --git a/donkeycar/management/kivy_ui.py b/donkeycar/management/kivy_ui.py index 4930a9b42..f842600bc 100644 --- a/donkeycar/management/kivy_ui.py +++ b/donkeycar/management/kivy_ui.py @@ -549,13 +549,13 @@ def update_filter(self): rc_handler.data['record_filter'] = self.record_filter if hasattr(config, 'TRAIN_FILTER'): delattr(config, 'TRAIN_FILTER') - tub_screen().status(f'Filter cleared') + tub_screen().status('Filter cleared') return filter_expression = self.create_filter_string(filter_text) try: record = tub_screen().current_record - filter_func_text = f"""def filter_func(record): - return {filter_expression} + filter_func_text = """def filter_func(record): + return {filter_expression} """ # creates the function 'filter_func' ldict = {} @@ -994,20 +994,20 @@ def train_call(self, model_type, *args): model_type=model_type, transfer=transfer, comment=self.ids.comment.text) - self.ids.status.text = f'Training completed.' + self.ids.status.text = 'Training completed.' self.ids.comment.text = 'Comment' self.ids.transfer_spinner.text = 'Choose transfer model' self.reload_database() except Exception as e: Logger.error(e) - self.ids.status.text = f'Train failed see console' + self.ids.status.text = 'Train failed see console' finally: self.ids.train_button.state = 'normal' def train(self, model_type): self.config.SHOW_PLOT = False Thread(target=self.train_call, args=(model_type,)).start() - self.ids.status.text = f'Training started.' + self.ids.status.text = 'Training started.' def set_config_attribute(self, input): try: diff --git a/donkeycar/management/makemovie.py b/donkeycar/management/makemovie.py index bcc68ef66..49d18fec2 100755 --- a/donkeycar/management/makemovie.py +++ b/donkeycar/management/makemovie.py @@ -6,7 +6,7 @@ from matplotlib import cm try: from vis.utils import utils -except: +except Exception: raise Exception("Please install keras-vis: pip install git+https://github.com/autorope/keras-vis.git") import donkeycar as dk @@ -17,7 +17,7 @@ DEG_TO_RAD = math.pi / 180.0 -class MakeMovie(object): +class MakeMovie(): def run(self, args, parser): ''' @@ -48,7 +48,7 @@ def run(self, args, parser): parser.print_help() if args.type not in ['linear', 'categorical']: - print("Model type {} is not supported. Only linear or categorical is supported for salient visualization".format(args.type)) + print(f"Model type {args.type} is not supported. Only linear or categorical is supported for salient visualization") parser.print_help() return @@ -141,7 +141,7 @@ def draw_steering_distribution(self, img, img_drawon): from donkeycar.parts.keras import KerasCategorical if self.keras_part is None or type(self.keras_part) is not KerasCategorical: - return + return pred_img = normalize_image(img) angle_binned, _ = self.keras_part.interpreter.predict(pred_img, other_arr=None) @@ -159,7 +159,7 @@ def draw_steering_distribution(self, img, img_drawon): x += dx def init_salient(self, model): - # Utility to search for layer index by name. + # Utility to search for layer index by name. # Alternatively we can specify this as -1 since it corresponds to the last layer. output_name = [] layer_idx = [] @@ -175,7 +175,7 @@ def init_salient(self, model): print("####################") print("Visualizing activations on layer:", output_name) print("####################") - + # ensure we have linear activation for li in layer_idx: model.layers[li].activation = activations.linear @@ -200,7 +200,7 @@ def compute_visualisation_mask(self, img): for p in pred: maxindex = tf.math.argmax(p[0]) pred_list.append(p[0][maxindex]) - + grads = 0 for p in pred_list: grad = tape.gradient(p, images) @@ -246,12 +246,13 @@ def make_frame(self, t): img_path = os.path.join(self.tub.images_base_path, rec['cam/image_array']) image_input = img_to_arr(Image.open(img_path)) image = image_input - + if self.do_salient: image = self.draw_salient(image_input) image = cv2.normalize(src=image, dst=None, alpha=0, beta=255, norm_type=cv2.NORM_MINMAX, dtype=cv2.CV_8U) - - if self.user: self.draw_user_input(rec, image_input, image) + + if self.user: + self.draw_user_input(rec, image_input, image) if self.keras_part is not None: self.draw_model_prediction(image_input, image) self.draw_steering_distribution(image_input, image) diff --git a/donkeycar/management/tub.py b/donkeycar/management/tub.py index 7e60ab27f..70b3a7aa9 100644 --- a/donkeycar/management/tub.py +++ b/donkeycar/management/tub.py @@ -26,7 +26,7 @@ class WebServer(tornado.web.Application): def __init__(self, data_path): if not os.path.exists(data_path): - raise ValueError('The path {} does not exist.'.format(data_path)) + raise ValueError(f'The path {data_path} does not exist.') this_dir = os.path.dirname(os.path.realpath(__file__)) static_file_path = os.path.join(this_dir, 'tub_web', 'static') @@ -47,7 +47,7 @@ def __init__(self, data_path): def start(self, port=8886): self.port = int(port) self.listen(self.port) - print('Listening on {}...'.format(port)) + print(f'Listening on {port}...') tornado.ioloop.IOLoop.instance().start() diff --git a/donkeycar/memory.py b/donkeycar/memory.py index 2fecd94a4..1ebdead7e 100755 --- a/donkeycar/memory.py +++ b/donkeycar/memory.py @@ -12,7 +12,7 @@ class Memory: """ def __init__(self, *args, **kw): self.d = {} - + def __setitem__(self, key, value): if type(key) is str: self.d[key] = value @@ -22,16 +22,16 @@ def __setitem__(self, key, value): value = tuple(key) for i, k in enumerate(key): self.d[k] = value[i] - + def __getitem__(self, key): if type(key) is tuple: return [self.d[k] for k in key] else: return self.d[key] - + def update(self, new_d): self.d.update(new_d) - + def put(self, keys, inputs): if len(keys) > 1: for i, key in enumerate(keys): @@ -40,22 +40,21 @@ def put(self, keys, inputs): except IndexError as e: error = str(e) + ' issue with keys: ' + str(key) raise IndexError(error) - + else: self.d[keys[0]] = inputs - - + + def get(self, keys): result = [self.d.get(k) for k in keys] return result - + def keys(self): return self.d.keys() - + def values(self): return self.d.values() - + def items(self): return self.d.items() - \ No newline at end of file diff --git a/donkeycar/parts/actuator.py b/donkeycar/parts/actuator.py index fdf761a74..cb2100c1e 100644 --- a/donkeycar/parts/actuator.py +++ b/donkeycar/parts/actuator.py @@ -16,9 +16,9 @@ logger = logging.getLogger(__name__) try: - import RPi.GPIO as GPIO + from RPi import GPIO except ImportError as e: - logger.warn(f"RPi.GPIO was not imported. {e}") + logger.warning(f"RPi.GPIO was not imported. {e}") globals()["GPIO"] = None from donkeycar.parts.pins import OutputPin, PwmPin, PinState @@ -158,7 +158,7 @@ def set_duty_cycle(self, duty_cycle): if duty_cycle < 0 or duty_cycle > 1: logging.error("duty_cycle must be in range 0 to 1") duty_cycle = clamp(duty_cycle, 0, 1) - + if duty_cycle == 1: self.set_high() elif duty_cycle == 0: @@ -168,13 +168,13 @@ def set_duty_cycle(self, duty_cycle): pulse = int(4096 * duty_cycle) try: self.pwm.set_pwm(self.channel, 0, pulse) - except: + except Exception: self.pwm.set_pwm(self.channel, 0, pulse) def set_pulse(self, pulse): try: self.pwm.set_pwm(self.channel, 0, int(pulse * self.pwm_scale)) - except: + except Exception: self.pwm.set_pwm(self.channel, 0, int(pulse * self.pwm_scale)) def run(self, pulse): @@ -185,27 +185,27 @@ class VESC: ''' VESC Motor controler using pyvesc This is used for most electric scateboards. - + inputs: serial_port---- port used communicate with vesc. for linux should be something like /dev/ttyACM1 has_sensor=False------- default value from pyvesc start_heartbeat=True----default value from pyvesc (I believe this sets up a heartbeat and kills speed if lost) baudrate=115200--------- baudrate used for communication with VESC timeout=0.05-------------time it will try before giving up on establishing connection - + percent=.2--------------max percentage of the dutycycle that the motor will be set to outputs: none - + uses the pyvesc library to open communication with the VESC and sets the servo to the angle (0-1) and the duty_cycle(speed of the car) to the throttle (mapped so that percentage will be max/min speed) - + Note that this depends on pyvesc, but using pip install pyvesc will create a pyvesc file that can only set the speed, but not set the servo angle. - + Instead please use: pip install git+https://github.com/LiamBindle/PyVESC.git@master to install the pyvesc library ''' def __init__(self, serial_port, percent=.2, has_sensor=False, start_heartbeat=True, baudrate=115200, timeout=0.05, steering_scale = 1.0, steering_offset = 0.0 ): - + try: import pyvesc except Exception as err: @@ -216,21 +216,21 @@ def __init__(self, serial_port, percent=.2, has_sensor=False, start_heartbeat=Tr print("\n\n\n") time.sleep(1) raise - + assert percent <= 1 and percent >= -1,'\n\nOnly percentages are allowed for MAX_VESC_SPEED (we recommend a value of about .2) (negative values flip direction of motor)' self.steering_scale = steering_scale self.steering_offset = steering_offset self.percent = percent - + try: self.v = pyvesc.VESC(serial_port, has_sensor, start_heartbeat, baudrate, timeout) except Exception as err: print("\n\n\n\n", err) print("\n\nto fix permission denied errors, try running the following command:") - print("sudo chmod a+rw {}".format(serial_port), "\n\n\n\n") + print(f"sudo chmod a+rw {serial_port}", "\n\n\n\n") time.sleep(1) raise - + def run(self, angle, throttle): self.v.set_servo((angle * self.steering_scale) + self.steering_offset) self.v.set_duty_cycle(throttle*self.percent) @@ -417,14 +417,14 @@ def get_bus(): # we install our own write that is more efficient use of interrupts self.pwm.set_pwm = self.set_pwm - + def set_pulse(self, pulse): - self.set_pwm(self.channel, 0, pulse) + self.set_pwm(self.channel, 0, pulse) def set_pwm(self, channel, on, off): # sets a single PWM channel self.pwm._device.writeList(self.register, [off & 0xFF, off >> 8]) - + def run(self, pulse): self.set_pulse(pulse) @@ -465,14 +465,14 @@ def read_pwm(self): while h1 != 100: logger.debug("skipping to start of header") h1 = self.pwm._device.readU8(self.register) - + h2 = self.pwm._device.readU8(self.register) # h2 ignored now val_a = self.pwm._device.readU8(self.register) val_b = self.pwm._device.readU8(self.register) self.steering = (val_b << 8) + val_a - + val_c = self.pwm._device.readU8(self.register) val_d = self.pwm._device.readU8(self.register) self.throttle = (val_d << 8) + val_c @@ -484,7 +484,7 @@ def read_pwm(self): def update(self): while(self.running): self.read_pwm() - + def run_threaded(self): return self.steering, self.throttle @@ -510,19 +510,19 @@ class Adafruit_DCMotor_Hat: def __init__(self, motor_num): from Adafruit_MotorHAT import Adafruit_MotorHAT, Adafruit_DCMotor import atexit - + self.FORWARD = Adafruit_MotorHAT.FORWARD self.BACKWARD = Adafruit_MotorHAT.BACKWARD - self.mh = Adafruit_MotorHAT(addr=0x60) - + self.mh = Adafruit_MotorHAT(addr=0x60) + self.motor = self.mh.getMotor(motor_num) self.motor_num = motor_num - + atexit.register(self.turn_off_motors) self.speed = 0 self.throttle = 0 - - + + def run(self, speed): ''' Update the speed of the motor where 1 is full forward and @@ -530,17 +530,17 @@ def run(self, speed): ''' if speed > 1 or speed < -1: raise ValueError( "Speed must be between 1(forward) and -1(reverse)") - + self.speed = speed self.throttle = int(dk.utils.map_range(abs(speed), -1, 1, -255, 255)) - - if speed > 0: + + if speed > 0: self.motor.run(self.FORWARD) else: self.motor.run(self.BACKWARD) - + self.motor.setSpeed(self.throttle) - + def shutdown(self): self.mh.getMotor(self.motor_num).run(Adafruit_MotorHAT.RELEASE) @@ -685,7 +685,7 @@ def set_pulse(self, pulse): w *= 1000 * 1000 # in microseconds with Teensy.teensy_lock: - Teensy.teensy_device.write(("%c %.1f\n" % (self.channel, w)).encode('ascii')) + Teensy.teensy_device.write(f"{self.channel:c} {w:.1f}\n".encode('ascii')) def set_turn_left(self, v): if self.lturn != v: @@ -742,7 +742,7 @@ def astar_readline(self): return ret -class MockController(object): +class MockController(): def __init__(self): pass @@ -753,7 +753,7 @@ def shutdown(self): pass -class L298N_HBridge_3pin(object): +class L298N_HBridge_3pin(): """ Motor controlled with an L298N hbridge, chosen with configuration DRIVETRAIN_TYPE=DC_TWO_WHEEL_L298N @@ -800,12 +800,12 @@ def run(self, throttle:float) -> None: where 1 is full forward and -1 is full backwards. """ if throttle is None: - logger.warn("TwoWheelSteeringThrottle throttle is None") + logger.warning("TwoWheelSteeringThrottle throttle is None") return if throttle > 1 or throttle < -1: - logger.warn( f"TwoWheelSteeringThrottle throttle is {throttle}, but it must be between 1(forward) and -1(reverse)") + logger.warning( f"TwoWheelSteeringThrottle throttle is {throttle}, but it must be between 1(forward) and -1(reverse)") throttle = clamp(throttle, -1, 1) - + self.speed = throttle self.throttle = dk.utils.map_range_float(throttle, -1, 1, -self.max_duty, self.max_duty) if self.throttle > self.zero_throttle: @@ -827,7 +827,7 @@ def shutdown(self): self.pin_backward.stop() -class TwoWheelSteeringThrottle(object): +class TwoWheelSteeringThrottle(): """ Modify individual differential drive wheel throttles in order to implemeht steering. @@ -843,16 +843,16 @@ def run(self, throttle:float, steering:float) -> Tuple[float, float]: where 1 is full forward and -1 is full backwards. """ if throttle is None: - logger.warn("TwoWheelSteeringThrottle throttle is None") + logger.warning("TwoWheelSteeringThrottle throttle is None") return if steering is None: - logger.warn("TwoWheelSteeringThrottle steering is None") + logger.warning("TwoWheelSteeringThrottle steering is None") return if throttle > 1 or throttle < -1: - logger.warn( f"TwoWheelSteeringThrottle throttle is {throttle}, but it must be between 1(forward) and -1(reverse)") + logger.warning( f"TwoWheelSteeringThrottle throttle is {throttle}, but it must be between 1(forward) and -1(reverse)") throttle = clamp(throttle, -1, 1) if steering > 1 or steering < -1: - logger.warn( f"TwoWheelSteeringThrottle steering is {steering}, but it must be between 1(right) and -1(left)") + logger.warning( f"TwoWheelSteeringThrottle steering is {steering}, but it must be between 1(right) and -1(left)") steering = clamp(steering, -1, 1) left_motor_speed = throttle @@ -869,7 +869,7 @@ def shutdown(self) -> None: pass -class L298N_HBridge_2pin(object): +class L298N_HBridge_2pin(): """ Motor controlled with an 'mini' L298N hbridge using 2 PwmPins, one for forward pwm and for reverse pwm. @@ -909,7 +909,7 @@ def __init__(self, pin_forward:PwmPin, pin_backward:PwmPin, zero_throttle:float= self.throttle=0 self.speed=0 - + self.pin_forward.start(0) self.pin_backward.start(0) @@ -920,15 +920,15 @@ def run(self, throttle:float) -> None: where 1 is full forward and -1 is full backwards. """ if throttle is None: - logger.warn("TwoWheelSteeringThrottle throttle is None") + logger.warning("TwoWheelSteeringThrottle throttle is None") return if throttle > 1 or throttle < -1: - logger.warn( f"TwoWheelSteeringThrottle throttle is {throttle}, but it must be between 1(forward) and -1(reverse)") + logger.warning( f"TwoWheelSteeringThrottle throttle is {throttle}, but it must be between 1(forward) and -1(reverse)") throttle = clamp(throttle, -1, 1) self.speed = throttle self.throttle = dk.utils.map_range_float(throttle, -1, 1, -self.max_duty, self.max_duty) - + if self.throttle > self.zero_throttle: self.pin_backward.duty_cycle(0) self.pin_forward.duty_cycle(self.throttle) @@ -943,14 +943,14 @@ def shutdown(self): self.pin_forward.stop() self.pin_backward.stop() - + # # This is being replaced by pins.py and PulseController. # GPIO pins can be configured using RPi.GPIO or PIGPIO, # so this is redundant # @deprecated("This will be removed in a future release in favor of PulseController") -class RPi_GPIO_Servo(object): +class RPi_GPIO_Servo(): ''' Servo controlled from the gpio pins on Rpi ''' @@ -987,7 +987,7 @@ def shutdown(self): # configured using RPi.GPIO or PIGPIO, so ServoBlaster is redundant # @deprecated("This will be removed in a future release in favor of PulseController") -class ServoBlaster(object): +class ServoBlaster(): ''' Servo controlled from the gpio pins on Rpi This uses a user space service to generate more efficient PWM via DMA control blocks. @@ -1066,7 +1066,7 @@ def __init__(self, servo_pin = 6, esc_pin = 5): def set_pulse(self, pin, angle): try: self.board.analog_write(pin, int(angle)) - except: + except Exception: self.board.analog_write(pin, int(angle)) def set_servo_pulse(self, angle): diff --git a/donkeycar/parts/behavior.py b/donkeycar/parts/behavior.py index 8907bbaad..dc3698563 100755 --- a/donkeycar/parts/behavior.py +++ b/donkeycar/parts/behavior.py @@ -1,4 +1,4 @@ -class BehaviorPart(object): +class BehaviorPart(): ''' Keep a list of states, and an active state. Keep track of switching. And return active state information. diff --git a/donkeycar/parts/camera.py b/donkeycar/parts/camera.py index 180cc5428..4cf8c060b 100644 --- a/donkeycar/parts/camera.py +++ b/donkeycar/parts/camera.py @@ -170,7 +170,7 @@ def run(self): return self.frame - def update(self): + def update(self): from datetime import datetime, timedelta while self.on: start = datetime.now() @@ -200,10 +200,10 @@ class CSICamera(BaseCamera): Credit: https://github.com/feicccccccc/donkeycar/blob/dev/donkeycar/parts/camera.py gstreamer init string from https://github.com/NVIDIA-AI-IOT/jetbot/blob/master/jetbot/camera.py ''' - def gstreamer_pipeline(self, capture_width=3280, capture_height=2464, output_width=224, output_height=224, framerate=21, flip_method=0) : + def gstreamer_pipeline(self, capture_width=3280, capture_height=2464, output_width=224, output_height=224, framerate=21, flip_method=0) : return 'nvarguscamerasrc ! video/x-raw(memory:NVMM), width=%d, height=%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv flip-method=%d ! nvvidconv ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! appsink' % ( capture_width, capture_height, framerate, flip_method, output_width, output_height) - + def __init__(self, image_w=160, image_h=120, image_d=3, capture_width=3280, capture_height=2464, framerate=60, gstreamer_flip=0): ''' gstreamer_flip = 0 - no flip @@ -265,7 +265,7 @@ def run(self): def run_threaded(self): return self.frame - + def shutdown(self): self.running = False logger.info('Stopping CSICamera') @@ -354,7 +354,7 @@ class ImageListCamera(BaseCamera): ''' def __init__(self, path_mask='~/mycar/data/**/images/*.jpg'): self.image_filenames = glob.glob(os.path.expanduser(path_mask), recursive=True) - + def get_image_index(fnm): sl = os.path.basename(fnm).split('_') return int(sl[0]) @@ -377,10 +377,10 @@ def get_image_index(fnm): def update(self): pass - def run_threaded(self): + def run_threaded(self): if self.num_images > 0: self.i_frame = (self.i_frame + 1) % self.num_images - self.frame = Image.open(self.image_filenames[self.i_frame]) + self.frame = Image.open(self.image_filenames[self.i_frame]) return np.asarray(self.frame) diff --git a/donkeycar/parts/controller.py b/donkeycar/parts/controller.py index 3c556525a..51b7961d2 100644 --- a/donkeycar/parts/controller.py +++ b/donkeycar/parts/controller.py @@ -14,7 +14,7 @@ logger = logging.getLogger(__name__) -class Joystick(object): +class Joystick(): ''' An interface to a physical joystick. The joystick holds available buttons @@ -42,11 +42,11 @@ def init(self): except ModuleNotFoundError: self.num_axes = 0 self.num_buttons = 0 - logger.warn("no support for fnctl module. joystick not enabled.") + logger.warning("no support for fnctl module. joystick not enabled.") return False if not os.path.exists(self.dev_fn): - logger.warn(f"{self.dev_fn} is missing") + logger.warning(f"{self.dev_fn} is missing") return False ''' @@ -60,7 +60,7 @@ def init(self): buf = array.array('B', [0] * 64) ioctl(self.jsdev, 0x80006a13 + (0x10000 * len(buf)), buf) # JSIOCGNAME(len) self.js_name = buf.tobytes().decode('utf-8') - logger.info('Device name: %s' % self.js_name) + logger.info(f'Device name: {self.js_name}') # Get number of axes and buttons. buf = array.array('B', [0]) @@ -76,7 +76,7 @@ def init(self): ioctl(self.jsdev, 0x80406a32, buf) # JSIOCGAXMAP for axis in buf[:self.num_axes]: - axis_name = self.axis_names.get(axis, 'unknown(0x%02x)' % axis) + axis_name = self.axis_names.get(axis, f'unknown(0x{axis:02x})') self.axis_map.append(axis_name) self.axis_states[axis_name] = 0.0 @@ -85,7 +85,7 @@ def init(self): ioctl(self.jsdev, 0x80406a34, buf) # JSIOCGBTNMAP for btn in buf[:self.num_buttons]: - btn_name = self.button_names.get(btn, 'unknown(0x%03x)' % btn) + btn_name = self.button_names.get(btn, f'unknown(0x{btn:03x})') self.button_map.append(btn_name) self.button_states[btn_name] = 0 #print('btn', '0x%03x' % btn, 'name', btn_name) @@ -140,12 +140,12 @@ def poll(self): fvalue = value / 32767.0 self.axis_states[axis] = fvalue axis_val = fvalue - logger.debug("axis: %s val: %f" % (axis, fvalue)) + logger.debug(f"axis: {axis} val: {fvalue:f}") return button, button_state, axis, axis_val -class PyGameJoystick(object): +class PyGameJoystick(): def __init__( self, poll_delay=0.0, throttle_scale=1.0, @@ -196,7 +196,7 @@ def poll(self): axis = self.axis_names[i] axis_val = val self.axis_states[i] = val - logging.debug("axis: %s val: %f" % (axis, val)) + logging.debug(f"axis: {axis} val: {val:f}") #print("axis: %s val: %f" % (axis, val)) @@ -232,7 +232,7 @@ def poll(self): iBtn += 1 return button, button_state, axis, axis_val - + def set_deadzone(self, val): self.dead_zone = val @@ -273,7 +273,7 @@ def __init__(self, cfg, debug=False): self.cbs.append(self.pi.callback(channel.pin, pigpio.EITHER_EDGE, self.cbf)) if self.debug: logger.info(f'RCReceiver gpio {channel.pin} created') - + def cbf(self, gpio, level, tick): import pigpio @@ -286,11 +286,11 @@ def cbf(self, gpio, level, tick): :param tick: # of mu s since boot, 32 bit int """ for channel in self.channels: - if gpio == channel.pin: - if level == 1: - channel.high_tick = tick - elif level == 0: - if channel.high_tick is not None: + if gpio == channel.pin: + if level == 1: + channel.high_tick = tick + elif level == 0: + if channel.high_tick is not None: channel.tick = pigpio.tickDiff(channel.high_tick, tick) def pulse_width(self, high): @@ -322,14 +322,14 @@ def run(self, mode=None, recording=None): logger.info(f'RC CH1 signal:{round(self.signals[0], 3)}, RC CH2 signal:{round(self.signals[1], 3)}, RC CH3 signal:{round(self.signals[2], 3)}') # check mode channel if present - if (self.signals[2] - self.jitter) > 0: + if (self.signals[2] - self.jitter) > 0: self.mode = 'local' else: # pass though value if provided self.mode = mode if mode is not None else 'user' # check throttle channel - if ((self.signals[1] - self.jitter) > 0) and self.RECORD: # is throttle above jitter level? If so, turn on auto-record + if ((self.signals[1] - self.jitter) > 0) and self.RECORD: # is throttle above jitter level? If so, turn on auto-record is_action = True else: # pass through default value @@ -350,14 +350,14 @@ class JoystickCreator(Joystick): A Helper class to create a new joystick mapping ''' def __init__(self, *args, **kwargs): - super(JoystickCreator, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = {} self.button_names = {} def poll(self): - button, button_state, axis, axis_val = super(JoystickCreator, self).poll() + button, button_state, axis, axis_val = super().poll() return button, button_state, axis, axis_val @@ -367,7 +367,7 @@ class PS3JoystickSixAd(Joystick): Contains mapping that worked for Jetson Nano using sixad for PS3 controller's connection ''' def __init__(self, *args, **kwargs): - super(PS3JoystickSixAd, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -388,7 +388,7 @@ def __init__(self, *args, **kwargs): 0x121 : 'L3', 0x122 : 'R3', - 0x12c : "triangle", + 0x12c : "triangle", 0x12d : "circle", 0x12e : "cross", 0x12f : 'square', @@ -406,7 +406,7 @@ class PS3JoystickOld(Joystick): Contains mapping that worked for Raspian Jessie drivers ''' def __init__(self, *args, **kwargs): - super(PS3JoystickOld, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -446,7 +446,7 @@ def __init__(self, *args, **kwargs): 0x121 : 'L3', 0x122 : 'R3', - 0x12c : "triangle", + 0x12c : "triangle", 0x12d : "circle", 0x12e : "cross", 0x12f : 'square', @@ -464,7 +464,7 @@ class PS3Joystick(Joystick): Contains mapping that work for Raspian Stretch drivers ''' def __init__(self, *args, **kwargs): - super(PS3Joystick, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -505,7 +505,7 @@ class PS4Joystick(Joystick): An interface to a physical PS4 joystick available at /dev/input/js0 ''' def __init__(self, *args, **kwargs): - super(PS4Joystick, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -558,7 +558,7 @@ class PS3JoystickPC(Joystick): It also wants /dev/input/js1 device filename, not js0 ''' def __init__(self, *args, **kwargs): - super(PS3JoystickPC, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -616,7 +616,7 @@ class PyGamePS4Joystick(PyGameJoystick): Windows setup: https://github.com/nefarius/ScpToolkit/releases/tag/v1.6.238.16010 ''' def __init__(self, *args, **kwargs): - super(PyGamePS4Joystick, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -668,7 +668,7 @@ class XboxOneJoystick(Joystick): https://github.com/Ezward/donkeypart_ps3_controller/blob/master/donkeypart_ps3_controller/part.py ''' def __init__(self, *args, **kwargs): - super(XboxOneJoystick, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00 : 'left_stick_horz', @@ -701,7 +701,7 @@ class LogitechJoystick(Joystick): https://github.com/kevkruemp/donkeypart_logitech_controller/blob/master/donkeypart_logitech_controller/part.py ''' def __init__(self, *args, **kwargs): - super(LogitechJoystick, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.axis_names = { 0x00: 'left_stick_horz', @@ -739,7 +739,7 @@ class Nimbus(Joystick): #contains mappings that work for the SteelNimbus joystick #on Jetson TX2, JetPack 4.2, Ubuntu 18.04 def __init__(self, *args, **kwargs): - super(Nimbus, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.button_names = { 0x130 : 'a', @@ -769,7 +769,7 @@ class WiiU(Joystick): #https://github.com/autorope/donkeypart_bluetooth_game_controller/blob/master/donkeypart_bluetooth_game_controller/wiiu_config.yml #and need testing! def __init__(self, *args, **kwargs): - super(WiiU, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.button_names = { 305: 'A', @@ -801,7 +801,7 @@ def __init__(self, *args, **kwargs): class RC3ChanJoystick(Joystick): #An interface to a physical joystick available at /dev/input/js0 def __init__(self, *args, **kwargs): - super(RC3ChanJoystick, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.button_names = { @@ -816,7 +816,7 @@ def __init__(self, *args, **kwargs): } -class JoystickController(object): +class JoystickController(): ''' Class to map joystick buttons and axes to functions. JoystickController is a base class. You will not use this class directly, @@ -945,7 +945,7 @@ def erase_last_N_records(self): try: self.tub.delete_last_n_records(self.num_records_to_erase) logger.info('deleted last %d records.' % self.num_records_to_erase) - except: + except Exception: logger.info('failed to erase') @@ -965,7 +965,7 @@ def emergency_stop(self): ''' initiate a series of steps to try to stop the vehicle as quickly as possible ''' - logger.warn('E-Stop!!!') + logger.warning('E-Stop!!!') self.mode = "user" self.recording = False self.constant_throttle = False @@ -1184,7 +1184,7 @@ class JoystickCreatorController(JoystickController): a custom joystick. ''' def __init__(self, *args, **kwargs): - super(JoystickCreatorController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1214,7 +1214,7 @@ class PS3JoystickController(JoystickController): A Controller object that maps inputs to actions ''' def __init__(self, *args, **kwargs): - super(PS3JoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1280,7 +1280,7 @@ def init_trigger_maps(self): ''' init set of mapping from buttons to function calls ''' - super(PS3JoystickSixAdController, self).init_trigger_maps() + super().init_trigger_maps() self.axis_trigger_map = { 'right_stick_horz' : self.set_steering, @@ -1292,7 +1292,7 @@ class PS4JoystickController(JoystickController): A Controller object that maps inputs to actions ''' def __init__(self, *args, **kwargs): - super(PS4JoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1335,7 +1335,7 @@ class PyGamePS4JoystickController(PS4JoystickController): A Controller object that maps inputs to actions ''' def __init__(self, which_js=0, *args, **kwargs): - super(PyGamePS4JoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.which_js=which_js @@ -1359,7 +1359,7 @@ class XboxOneJoystickController(JoystickController): https://github.com/Ezward/donkeypart_ps3_controller/blob/master/donkeypart_ps3_controller/part.py ''' def __init__(self, *args, **kwargs): - super(XboxOneJoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1419,13 +1419,13 @@ class XboxOneSwappedJoystickController(XboxOneJoystickController): Swap steering and throttle controls from std XBox one controller ''' def __init__(self, *args, **kwargs): - super(XboxOneSwappedJoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_trigger_maps(self): ''' init set of mapping from buttons to function calls ''' - super(XboxOneSwappedJoystickController, self).init_trigger_maps() + super().init_trigger_maps() # make the actual swap of the sticks self.set_axis_trigger('right_stick_horz', self.set_steering) @@ -1443,7 +1443,7 @@ class LogitechJoystickController(JoystickController): https://github.com/kevkruemp/donkeypart_logitech_controller/blob/master/donkeypart_logitech_controller/part.py ''' def __init__(self, *args, **kwargs): - super(LogitechJoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1514,7 +1514,7 @@ def on_dpad_right(self): class NimbusController(JoystickController): #A Controller object that maps inputs to actions def __init__(self, *args, **kwargs): - super(NimbusController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1546,7 +1546,7 @@ def init_trigger_maps(self): class WiiUController(JoystickController): #A Controller object that maps inputs to actions def __init__(self, *args, **kwargs): - super(WiiUController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1579,7 +1579,7 @@ def init_trigger_maps(self): class RC3ChanJoystickController(JoystickController): #A Controller object that maps inputs to actions def __init__(self, *args, **kwargs): - super(RC3ChanJoystickController, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def init_js(self): @@ -1626,7 +1626,7 @@ def init_trigger_maps(self): } -class JoyStickPub(object): +class JoyStickPub(): ''' Use Zero Message Queue (zmq) to publish the control messages from a local joystick ''' @@ -1655,7 +1655,7 @@ def run(self): logger.info(f"SENT {message_data}") -class JoyStickSub(object): +class JoyStickSub(): ''' Use Zero Message Queue (zmq) to subscribe to control messages from a remote joystick ''' diff --git a/donkeycar/parts/coral.py b/donkeycar/parts/coral.py index 1f57ce8bb..1a522b25f 100644 --- a/donkeycar/parts/coral.py +++ b/donkeycar/parts/coral.py @@ -6,88 +6,88 @@ class InferenceEngine(BasicEngine): - """Engine used for inference task.""" - - def __init__(self, model_path, device_path=None): - """Creates a BasicEngine with given model. - - Args: - model_path: String, path to TF-Lite Flatbuffer file. - device_path: String, if specified, bind engine with Edge TPU at device_path. - - Raises: - ValueError: An error occurred when the output format of model is invalid. - """ - if device_path: - super().__init__(model_path, device_path) - else: - super().__init__(model_path) - output_tensors_sizes = self.get_all_output_tensors_sizes() - if output_tensors_sizes.size > 2: - raise ValueError( - ('Inference model should have 2 output tensors or less!' - 'This model has {}.'.format(output_tensors_sizes.size))) - - def Inference(self, img): - """Inference image with np array image object. - - This interface assumes the loaded model is trained for image - classification. - - Args: - img: numpy.array image object. - - Returns: - List of (float) which represents inference results. - - Raises: - RuntimeError: when tensor not a single 3 channel image. - Asserts: when image incorrect size. - """ - input_tensor_shape = self.get_input_tensor_shape() - if (input_tensor_shape.size != 4 or input_tensor_shape[3] != 3 or - input_tensor_shape[0] != 1): - raise RuntimeError( - 'Invalid input tensor shape! Expected: [1, height, width, 3]') - _, height, width, _ = input_tensor_shape - assert(height == img.shape[0]) - assert(width == img.shape[1]) - input_tensor = img.flatten() - return self.RunInferenceWithInputTensor(input_tensor) - - def RunInferenceWithInputTensor(self, input_tensor): - """Run inference with raw input tensor. - - This interface requires user to process input data themselves and convert - it to formatted input tensor. - - Args: - input_tensor: numpy.array represents the input tensor. - - Returns: - List of (float) which represents inference. - - Raises: - ValueError: when input param is invalid. - """ - _, self._raw_result = self.RunInference( - input_tensor) - return [self._raw_result] - - - -class CoralLinearPilot(object): - ''' - Base class for TFlite models that will provide steering and throttle to guide a car. - ''' - def __init__(self): - self.model = None - self.engine = None - - def load(self, model_path): - # Load Coral edgetpu TFLite model and allocate tensors. - self.engine = InferenceEngine(model_path) - - def run(self, image): - steering, throttle = self.engine.Inference(image)[0] - return steering, throttle + """Engine used for inference task.""" + + def __init__(self, model_path, device_path=None): + """Creates a BasicEngine with given model. + + Args: + model_path: String, path to TF-Lite Flatbuffer file. + device_path: String, if specified, bind engine with Edge TPU at device_path. + + Raises: + ValueError: An error occurred when the output format of model is invalid. + """ + if device_path: + super().__init__(model_path, device_path) + else: + super().__init__(model_path) + output_tensors_sizes = self.get_all_output_tensors_sizes() + if output_tensors_sizes.size > 2: + raise ValueError( + ('Inference model should have 2 output tensors or less!' + 'This model has {}.'.format(output_tensors_sizes.size))) + + def Inference(self, img): + """Inference image with np array image object. + + This interface assumes the loaded model is trained for image + classification. + + Args: + img: numpy.array image object. + + Returns: + List of (float) which represents inference results. + + Raises: + RuntimeError: when tensor not a single 3 channel image. + Asserts: when image incorrect size. + """ + input_tensor_shape = self.get_input_tensor_shape() + if (input_tensor_shape.size != 4 or input_tensor_shape[3] != 3 or + input_tensor_shape[0] != 1): + raise RuntimeError( + 'Invalid input tensor shape! Expected: [1, height, width, 3]') + _, height, width, _ = input_tensor_shape + assert (height == img.shape[0]) + assert (width == img.shape[1]) + input_tensor = img.flatten() + return self.RunInferenceWithInputTensor(input_tensor) + + def RunInferenceWithInputTensor(self, input_tensor): + """Run inference with raw input tensor. + + This interface requires user to process input data themselves and convert + it to formatted input tensor. + + Args: + input_tensor: numpy.array represents the input tensor. + + Returns: + List of (float) which represents inference. + + Raises: + ValueError: when input param is invalid. + """ + _, self._raw_result = self.RunInference( + input_tensor) + return [self._raw_result] + + +class CoralLinearPilot(): + ''' + Base class for TFlite models that will provide steering and throttle to guide a car. + ''' + + def __init__(self): + self.model = None + self.engine = None + + def load(self, model_path): + # Load Coral edgetpu TFLite model and allocate tensors. + self.engine = InferenceEngine(model_path) + + def run(self, image): + steering, throttle = self.engine.Inference(image)[0] + return steering, throttle diff --git a/donkeycar/parts/cv.py b/donkeycar/parts/cv.py index 84f51e8be..9657179b4 100644 --- a/donkeycar/parts/cv.py +++ b/donkeycar/parts/cv.py @@ -1,4 +1,5 @@ import time +import sys import cv2 import numpy as np import logging @@ -26,7 +27,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_RGB2GRAY) return img_arr - except: + except Exception: logger.error("Unable to convert RGB image to greyscale") return None @@ -41,7 +42,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_GRAY2RGB) - except: + except Exception: logger.error(F"Unable to convert greyscale image of shape {img_arr.shape} to RGB") return None @@ -56,7 +57,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_GRAY2BGR) - except: + except Exception: logger.error(F"Unable to convert greyscale image of shape {img_arr.shape} to RGB") return None @@ -77,7 +78,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_BGR2GRAY) return img_arr - except: + except Exception: logger.error("Unable to convert BGR image to greyscale") return None @@ -94,7 +95,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_HSV2GRAY) return img_arr - except: + except Exception: logger.error("Unable to convert HSV image to greyscale") return None @@ -123,7 +124,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_BGR2RGB) return img_arr - except: + except Exception: logger.error("Unable to convert BGR image to RGB") return None @@ -140,7 +141,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_RGB2BGR) return img_arr - except: + except Exception: logger.error("Unable to convert RGB image to BRG") return None @@ -157,7 +158,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_HSV2RGB) return img_arr - except: + except Exception: logger.error("Unable to convert HSV image to RGB") return None @@ -174,7 +175,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_RGB2HSV) return img_arr - except: + except Exception: logger.error("Unable to convert RGB image to HSV") return None @@ -191,7 +192,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_HSV2BGR) return img_arr - except: + except Exception: logger.error("Unable to convert HSV image to BGR") return None @@ -208,7 +209,7 @@ def run(self, img_arr): try: img_arr = cv2.cvtColor(img_arr, cv2.COLOR_BGR2HSV) return img_arr - except: + except Exception: logger.error("Unable to convert BGR image to HSV") return None @@ -232,7 +233,7 @@ def run(self, img_arr): try: return cv2.resize(img_arr, (0,0), fx=self.scale, fy=self.scale_height) - except: + except Exception: logger.error("Unable to scale image") return None @@ -255,7 +256,7 @@ def run(self, img_arr): try: return cv2.resize(img_arr, (self.width, self.height)) - except: + except Exception: logger.error("Unable to resize image") return None @@ -280,22 +281,22 @@ def run(self, image): # center (h, w) = image.shape[:2] (cX, cY) = (w // 2, h // 2) - + # grab the rotation matrix (applying the negative of the # angle to rotate clockwise), then grab the sine and cosine # (i.e., the rotation components of the matrix) M = cv2.getRotationMatrix2D((cX, cY), -self.rot_deg, 1.0) cos = np.abs(M[0, 0]) sin = np.abs(M[0, 1]) - + # compute the new bounding dimensions of the image nW = int((h * sin) + (w * cos)) nH = int((h * cos) + (w * sin)) - + # adjust the rotation matrix to take into account translation M[0, 2] += (nW / 2) - cX M[1, 2] += (nH / 2) - cY - + # perform the actual rotation and return the image return cv2.warpAffine(image, M, (nW, nH)) @@ -321,7 +322,7 @@ def run(self, img_arr): self.high_threshold, apertureSize=self.aperture_size, L2gradient=self.l2gradient) - except: + except Exception: logger.error("Unable to apply canny edge detection to image.") return None @@ -333,16 +334,16 @@ class ImgGaussianBlur: def __init__(self, kernel_size=5, kernel_y=None): self.kernel_size = (kernel_size, kernel_y if kernel_y is not None else kernel_size) - + def run(self, img_arr): if img_arr is None: return None try: return cv2.GaussianBlur(img_arr, - self.kernel_size, + self.kernel_size, 0) - except: + except Exception: logger.error("Unable to apply gaussian blur to image.") return None @@ -354,14 +355,14 @@ class ImgSimpleBlur: def __init__(self, kernel_size=5, kernel_y=None): self.kernel_size = (kernel_size, kernel_y if kernel_y is not None else kernel_size) - + def run(self, img_arr): if img_arr is None: return None try: return cv2.blur(img_arr, self.kernel_size) - except: + except Exception: logger.error("Unable to apply simple blur to image.") return None @@ -417,7 +418,7 @@ def run(self, image): transformed = np.multiply(image, mask) return transformed - + def shutdown(self): self.masks = {} # free cached masks @@ -505,18 +506,18 @@ def run(self): class Pipeline: def __init__(self, steps): self.steps = steps - + def run(self, val): for step in self.steps: f = step['f'] args = step['args'] kwargs = step['kwargs'] - + val = f(val, *args, **kwargs) return val -class CvImgFromFile(object): +class CvImgFromFile(): def __init__(self, file_path, image_w=None, image_h=None, image_d=None, copy=False): """ Part to load image from file and output as RGB image @@ -527,7 +528,7 @@ def __init__(self, file_path, image_w=None, image_h=None, image_d=None, copy=Fal image = cv2.imread(file_path) if image is None: raise ValueError(f"CvImage file_path did not resolve to a readable image file: {file_path}") - + # # resize if there are overrides # @@ -561,7 +562,7 @@ def run(self): return self.image -class CvCam(object): +class CvCam(): def __init__(self, image_w=160, image_h=120, image_d=3, iCam=0, warming_secs=5): self.width = image_w self.height = image_h @@ -619,7 +620,7 @@ def shutdown(self): self.cap.release() -class CvImageView(object): +class CvImageView(): def run(self, image): if image is None: @@ -628,7 +629,7 @@ def run(self, image): try: cv2.imshow('frame', image) cv2.waitKey(1) - except: + except Exception: logger.error("Unable to open image window.") def shutdown(self): @@ -638,7 +639,7 @@ def shutdown(self): if __name__ == "__main__": import argparse import sys - + # parse arguments parser = argparse.ArgumentParser() parser.add_argument("-c", "--camera", type=int, default=0, @@ -649,7 +650,7 @@ def shutdown(self): help = "height of image to capture") parser.add_argument("-f", "--file", type=str, help = "path to image file to user rather that a camera") - parser.add_argument("-a", "--aug", required=True, type=str.upper, + parser.add_argument("-a", "--aug", required=True, type=str.upper, choices=['CROP', 'TRAPEZE', "RGB2HSV", "HSV2RGB", "RGB2BGR", "BGR2RGB", "BGR2HSV", "HSV2BRG", "RGB2GREY", "BGR2GREY", "HSV2GREY", @@ -685,7 +686,7 @@ def shutdown(self): help="Simple blur kernel y size in pixels, defaults to a square kernel") parser.add_argument("-sw", "--scale", type=float, help = "scale factor for image width") - parser.add_argument("-sh", "--scale-height", type=float, + parser.add_argument("-sh", "--scale-height", type=float, help = "scale factor for image height. Defaults to scale") # @@ -695,7 +696,7 @@ def shutdown(self): # Read arguments from command line args = parser.parse_args() - + image_source = None help = [] if args.file is None: @@ -746,7 +747,7 @@ def shutdown(self): # # masking tranformations # - if "TRAPEZE" == transformation or "CROP" == transformation: + if "TRAPEZE" == transformation or "CROP" == transformation: # # masking transformations # @@ -761,9 +762,9 @@ def shutdown(self): ) else: transformer = ImgCropMask( - args.left if args.left is not None else 0, - args.top if args.top is not None else 0, - args.right if args.right is not None else 0, + args.left if args.left is not None else 0, + args.top if args.top is not None else 0, + args.right if args.right is not None else 0, args.bottom if args.bottom is not None else 0) # # color space transformations @@ -789,14 +790,14 @@ def shutdown(self): elif "CANNY" == transformation: # canny edge detection transformer = ImgCanny(args.canny_low, args.canny_high, args.canny_aperture) - # + # # blur transformations # elif "GBLUR" == transformation: transformer = ImgGaussianBlur(args.guassian_kernel, args.guassian_kernel_y) elif "BLUR" == transformation: transformer = ImgSimpleBlur(args.blur_kernel, args.blur_kernel_y) - # + # # resize transformations # elif "RESIZE" == transformation: @@ -805,7 +806,7 @@ def shutdown(self): transformer = ImageScale(args.scale, args.scale_height) else: print("-a/--aug is not a valid augmentation") - exit() + sys.exit() # Creating a window for later use window_name = 'hsv_range_picker' @@ -828,7 +829,7 @@ def shutdown(self): k = cv2.waitKey(5) & 0xFF if k == ord('q') or k == ord('Q'): # 'Q' or 'q' break - + if cap is not None: cap.release() diff --git a/donkeycar/parts/datastore.py b/donkeycar/parts/datastore.py index 87d455c41..3170697b6 100644 --- a/donkeycar/parts/datastore.py +++ b/donkeycar/parts/datastore.py @@ -19,7 +19,7 @@ from PIL import Image -class Tub(object): +class Tub(): """ A datastore to store sensor data in a key, value format. @@ -87,7 +87,7 @@ def __init__(self, path, inputs=None, types=None, user_meta=[]): json.dump(self.meta, f) self.current_ix = 0 self.exclude = set() - print('New tub created at: {}'.format(self.path)) + print(f'New tub created at: {self.path}') else: msg = "The tub path you provided doesn't exist and you didnt pass any meta info (inputs & types)" + \ "to create a new tub. Please check your tub path or provide meta info to create a new tub." @@ -95,7 +95,7 @@ def __init__(self, path, inputs=None, types=None, user_meta=[]): raise AttributeError(msg) def get_last_ix(self): - index = self.get_index() + index = self.get_index() return max(index) def update_df(self): @@ -117,18 +117,18 @@ def get_file_ix(file_name): try: name = file_name.split('.')[0] num = int(name.split('_')[1]) - except: + except Exception: num = 0 return num nums = [get_file_ix(f) for f in record_files] - + if shuffled: random.shuffle(nums) else: nums = sorted(nums) - - return nums + + return nums @property def inputs(self): @@ -152,7 +152,7 @@ def write_json_record(self, json_data): print('troubles with record:', json_data) except FileNotFoundError: raise - except: + except Exception: print("Unexpected error:", sys.exc_info()[0]) raise @@ -177,13 +177,13 @@ def check(self, fix=False): Iterate over all records and make sure we can load them. Optionally remove records that cause a problem. """ - print('Checking tub:%s.' % self.path) + print(f'Checking tub:{self.path}.') print('Found: %d records.' % self.get_num_records()) problems = False for ix in self.get_index(shuffled=False): try: self.get_record(ix) - except: + except Exception: problems = True if fix == False: print('problems with record:', self.path, ix) @@ -208,7 +208,7 @@ def put_record(self, data): """ json_data = {} self.current_ix += 1 - + for key, val in data.items(): typ = self.get_input_type(key) @@ -236,13 +236,13 @@ def put_record(self, data): name = self.make_file_name(key, ext='.png') img.save(os.path.join(self.path, name)) json_data[key]=name - + elif typ == 'nparray': # convert np array to python so it is jsonable json_data[key] = val.tolist() else: - msg = 'Tub does not know what to do with this type {}'.format(typ) + msg = f'Tub does not know what to do with this type {typ}' raise TypeError(msg) json_data['milliseconds'] = int((time.time() - self.start_time) * 1000) @@ -286,7 +286,7 @@ def get_json_record(self, ix): raise Exception('bad record: %d. You may want to run `python manage.py check --fix`' % ix) except FileNotFoundError: raise - except: + except Exception: print("Unexpected error:", sys.exc_info()[0]) raise @@ -342,7 +342,7 @@ def exclude_index(self, index): def include_index(self, index): try: self.exclude.remove(index) - except: + except Exception: pass def write_exclude(self): @@ -357,7 +357,7 @@ def write_exclude(self): class TubWriter(Tub): def __init__(self, *args, **kwargs): - super(TubWriter, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def run(self, *args): """ @@ -372,7 +372,7 @@ def run(self, *args): class TubReader(Tub): def __init__(self, path, *args, **kwargs): - super(TubReader, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) def run(self, *args): """ @@ -396,7 +396,7 @@ def next_tub_number(self, path): def get_tub_num(tub_name): try: num = int(tub_name.split('_')[1]) - except: + except Exception: num = 0 return num @@ -426,7 +426,7 @@ class TubImageStacker(Tub): If you drive with the ImageFIFO part, then you don't need this. Just make sure your inference pass uses the ImageFIFO that the NN will now expect. ''' - + def rgb2gray(self, rgb): ''' take a numpy rgb image return a new single channel image converted to greyscale @@ -443,7 +443,7 @@ def stack3Images(self, img_a, img_b, img_c): gray_a = self.rgb2gray(img_a) gray_b = self.rgb2gray(img_b) gray_c = self.rgb2gray(img_c) - + img_arr = np.zeros([width, height, 3], dtype=np.dtype('B')) img_arr[...,0] = np.reshape(gray_a, (width, height)) @@ -457,11 +457,11 @@ def get_record(self, ix): get the current record and two previous. stack the 3 images into a single image. ''' - data = super(TubImageStacker, self).get_record(ix) + data = super().get_record(ix) if ix > 1: - data_ch1 = super(TubImageStacker, self).get_record(ix - 1) - data_ch0 = super(TubImageStacker, self).get_record(ix - 2) + data_ch1 = super().get_record(ix - 1) + data_ch0 = super().get_record(ix - 2) json_data = self.get_json_record(ix) for key, val in json_data.items(): @@ -492,9 +492,9 @@ def __init__(self, frame_list, *args, **kwargs): [5, 90, 200] would return 3 frames of records, ofset 5, 90, and 200 frames in the future. ''' - super(TubTimeStacker, self).__init__(*args, **kwargs) + super().__init__(*args, **kwargs) self.frame_list = frame_list - + def get_record(self, ix): ''' stack the N records into a single record. @@ -504,12 +504,12 @@ def get_record(self, ix): data = {} for i, iOffset in enumerate(self.frame_list): iRec = ix + iOffset - + try: json_data = self.get_json_record(iRec) except FileNotFoundError: pass - except: + except Exception: pass for key, val in json_data.items(): @@ -518,9 +518,9 @@ def get_record(self, ix): # load only the first image saved as separate files if typ == 'image' and i == 0: val = Image.open(os.path.join(self.path, val)) - data[key] = val + data[key] = val elif typ == 'image_array' and i == 0: - d = super(TubTimeStacker, self).get_record(ix) + d = super().get_record(ix) data[key] = d[key] else: ''' diff --git a/donkeycar/parts/datastore_v2.py b/donkeycar/parts/datastore_v2.py index 8bc359d35..e77835abe 100644 --- a/donkeycar/parts/datastore_v2.py +++ b/donkeycar/parts/datastore_v2.py @@ -12,7 +12,7 @@ NEWLINE_STRIP = '\r\n' -class Seekable(object): +class Seekable(): """ A seekable file reader, writer which deals with newline delimited records. \n @@ -103,7 +103,7 @@ def truncate_until_end(self, line_number): if len(self.cumulative_lengths) > 0 else 0 self.seek_end_of_file() self.file.truncate() - + def read_from(self, line_number): current_offset = self.file.tell() self.seek_line_start(line_number) @@ -112,10 +112,10 @@ def read_from(self, line_number): while len(contents) > 0: lines.append(contents) contents = self.readline() - + self.file.seek(current_offset) return lines - + def update_line(self, line_number, contents): lines = self.read_from(line_number) length = len(lines) @@ -138,7 +138,7 @@ def __exit__(self, type, value, traceback): self.close() -class Catalog(object): +class Catalog(): ''' A new line delimited file that has records delimited by newlines. \n @@ -170,7 +170,7 @@ def close(self): self.seekable.close() -class CatalogMetadata(object): +class CatalogMetadata(): ''' Manifest for a Catalog ''' @@ -217,7 +217,7 @@ def close(self): self.seekeable.close() -class Manifest(object): +class Manifest(): ''' A newline delimited file, with the following format. @@ -396,7 +396,7 @@ def __len__(self): return self.current_index - len(self.deleted_indexes) -class ManifestIterator(object): +class ManifestIterator(): """ An iterator for the Manifest type. \n diff --git a/donkeycar/parts/dgym.py b/donkeycar/parts/dgym.py index fb067d60a..cdebe00e6 100644 --- a/donkeycar/parts/dgym.py +++ b/donkeycar/parts/dgym.py @@ -8,7 +8,7 @@ def is_exe(fpath): return os.path.isfile(fpath) and os.access(fpath, os.X_OK) -class DonkeyGymEnv(object): +class DonkeyGymEnv(): def __init__(self, sim_path, host="127.0.0.1", port=9091, headless=0, env_name="donkey-generated-track-v0", sync="asynchronous", conf={}, record_location=False, record_gyroaccel=False, record_velocity=False, record_lidar=False, delay=0): diff --git a/donkeycar/parts/encoder.py b/donkeycar/parts/encoder.py index 7919f0e4a..bf6cc0802 100644 --- a/donkeycar/parts/encoder.py +++ b/donkeycar/parts/encoder.py @@ -11,18 +11,18 @@ # The Arduino class is for a quadrature wheel or motor encoder that is being read by an offboard microcontroller -# such as an Arduino or Teensy that is feeding serial data to the RaspberryPy or Nano via USB serial. +# such as an Arduino or Teensy that is feeding serial data to the RaspberryPy or Nano via USB serial. # The microcontroller should be flashed with this sketch (use the Arduino IDE to do that): https://github.com/zlite/donkeycar/tree/master/donkeycar/parts/encoder/encoder -# Make sure you check the sketch using the "test_encoder.py code in the Donkeycar tests folder to make sure you've got your +# Make sure you check the sketch using the "test_encoder.py code in the Donkeycar tests folder to make sure you've got your # encoder plugged into the right pins, or edit it to reflect the pins you are using. # You will need to calibrate the mm_per_tick line below to reflect your own car. Just measure out a meter and roll your car -# along it. Change the number below until it the distance reads out almost exactly 1.0 +# along it. Change the number below until it the distance reads out almost exactly 1.0 # This samples the odometer at 10HZ and does a moving average over the past ten readings to derive a velocity @deprecated("Deprecated in favor donkeycar.parts.tachometer.Tachometer(SerialEncoder)") -class ArduinoEncoder(object): +class ArduinoEncoder(): def __init__(self, mm_per_tick=0.0000599, debug=False): import serial import serial.tools.list_ports @@ -54,8 +54,8 @@ def update(self): self.speed, self.distance = self.OdomDist(self.ticks, self.mm_per_tick) def run_threaded(self): - self.speed - return self.speed + self.speed + return self.speed def shutdown(self): @@ -153,21 +153,21 @@ def _cb(self, pin, level, tick): def update(self): # keep looping infinitely until the thread is stopped while(self.on): - + #save the ticks and reset the counter ticks = self.counter self.counter = 0 - + #save off the last time interval and reset the timer start_time = self.last_time end_time = time.time() self.last_time = end_time - + #calculate elapsed time and distance traveled seconds = end_time - start_time distance = ticks * self.m_per_tick velocity = distance / seconds - + #update the odometer values self.meters += distance self.meters_per_second = velocity @@ -193,9 +193,9 @@ def shutdown(self): # indicate that the thread should be stopped self.on = False print('Stopping Rotary Encoder') - print("\tDistance Travelled: {} meters".format(round(self.meters, 4))) - print("\tTop Speed: {} meters/second".format(round(self.top_speed, 4))) + print(f"\tDistance Travelled: {round(self.meters, 4)} meters") + print(f"\tTop Speed: {round(self.top_speed, 4)} meters/second") if self.cb != None: self.cb.cancel() self.cb = None - self.pi.stop() \ No newline at end of file + self.pi.stop() diff --git a/donkeycar/parts/fast_stretch.py b/donkeycar/parts/fast_stretch.py index 2fbc16c25..a3bc287c5 100644 --- a/donkeycar/parts/fast_stretch.py +++ b/donkeycar/parts/fast_stretch.py @@ -39,7 +39,7 @@ def fast_stretch(image, debug=False): if debug: time_taken = (time.time() - start) * 1000 - print('Preprocessing time %s' % time_taken) + print(f'Preprocessing time {time_taken}') start = time.time() histogram = cv2.calcHist([input], [0], None, [256], [0, 256]) @@ -61,7 +61,7 @@ def fast_stretch(image, debug=False): if debug: time_taken = (time.time() - start) * 1000 - print('Histogram Binning %s' % time_taken) + print(f'Histogram Binning {time_taken}') start = time.time() # Vectorized ops @@ -77,7 +77,7 @@ def fast_stretch(image, debug=False): if debug: time_taken = (time.time() - start) * 1000 - print('Vector Ops %s' % time_taken) + print(f'Vector Ops {time_taken}') start = time.time() return output diff --git a/donkeycar/parts/fastai.py b/donkeycar/parts/fastai.py index ead252eef..c3f5b0a60 100644 --- a/donkeycar/parts/fastai.py +++ b/donkeycar/parts/fastai.py @@ -242,7 +242,7 @@ def output_shapes(self): class Linear(nn.Module): def __init__(self): - super(Linear, self).__init__() + super().__init__() self.dropout = 0.1 # init the layers self.conv24 = nn.Conv2d(3, 24, kernel_size=(5, 5), stride=(2, 2)) diff --git a/donkeycar/parts/file_watcher.py b/donkeycar/parts/file_watcher.py index ee5193e99..ae401be46 100755 --- a/donkeycar/parts/file_watcher.py +++ b/donkeycar/parts/file_watcher.py @@ -1,6 +1,6 @@ import os -class FileWatcher(object): +class FileWatcher(): ''' Watch a specific file and give a signal when it's modified ''' @@ -22,7 +22,5 @@ def run(self): if self.verbose: print(self.filename, "changed.") return True - - return False - + return False diff --git a/donkeycar/parts/fps.py b/donkeycar/parts/fps.py index 4d27ad1a5..02b1a5772 100644 --- a/donkeycar/parts/fps.py +++ b/donkeycar/parts/fps.py @@ -4,7 +4,7 @@ logger = logging.getLogger(__name__) -class FrequencyLogger(object): +class FrequencyLogger(): """ Log current, min and max of frequency value """ diff --git a/donkeycar/parts/gps.py b/donkeycar/parts/gps.py index 6afca446c..19c3a59c8 100644 --- a/donkeycar/parts/gps.py +++ b/donkeycar/parts/gps.py @@ -184,7 +184,7 @@ def parseGpsPosition(line, debug=False): Given a line emitted by a GPS module, Parse out the position and return as a return: tuple of float (longitude, latitude) as meters. - If it cannot be parsed or is not a position message, + If it cannot be parsed or is not a position message, then return None. """ if not line: @@ -192,24 +192,24 @@ def parseGpsPosition(line, debug=False): line = line.strip() if not line: return None - + # # must start with $ and end with checksum # if '$' != line[0]: logger.info("NMEA Missing line start") return None - + if '*' != line[-3]: logger.info("NMEA Missing checksum") return None - + nmea_checksum = parse_nmea_checksum(line) # ## checksum hex digits as int nmea_msg = line[1:-3] # msg without $ and *## checksum nmea_parts = nmea_msg.split(",") message = nmea_parts[0] - if (message == "GPRMC") or (message == "GNRMC"): - # + if (message == "GPRMC") or (message == "GNRMC"): + # # like '$GPRMC,003918.00,A,3806.92281,N,12235.64362,W,0.090,,060322,,,D*67' # GPRMC = Recommended minimum specific GPS/Transit data # @@ -231,7 +231,7 @@ def parseGpsPosition(line, debug=False): try: msg = pynmea2.parse(line) except pynmea2.ParseError as e: - logger.error('NMEA parse error detected: {}'.format(e)) + logger.error(f'NMEA parse error detected: {e}') return None # Reading the GPS fix data is an alternative approach that also works @@ -257,7 +257,7 @@ def parseGpsPosition(line, debug=False): utm_position = utm.from_latlon(latitude, longitude) if debug: logger.info(f"UTM easting = {utm_position[0]}, UTM northing = {utm_position[1]}") - + # return (longitude, latitude) as float degrees return float(utm_position[0]), float(utm_position[1]) else: @@ -276,8 +276,8 @@ def parse_nmea_checksum(nmea_line): calling this function. """ return int(nmea_line[-2:], 16) # checksum hex digits as int - - + + def calculate_nmea_checksum(nmea_line): """ Given the complete nmea line (including starting '$' and ending checksum '*##') @@ -286,7 +286,7 @@ def calculate_nmea_checksum(nmea_line): should check that '$' and '*##' checksum are present and that the checksum matches before calling this function. """ - # + # # xor all characters in the message to get a one byte checksum. # don't include starting '$' or trailing checksum '*##' # @@ -302,7 +302,7 @@ def nmea_to_degrees(gps_str, direction): """ if not gps_str or gps_str == "0": return 0 - + # # pull out the degrees and minutes # and then combine the minutes @@ -312,26 +312,26 @@ def nmea_to_degrees(gps_str, direction): minutes_str = parts[0][-2:] # always results in 2 digits if 2 == len(parts): minutes_str += "." + parts[1] # combine whole and fractional minutes - + # # convert degrees to a float # degrees = 0.0 if len(degrees_str) > 0: degrees = float(degrees_str) - + # # convert minutes a float in degrees # minutes = 0.0 if len(minutes_str) > 0: minutes = float(minutes_str) / 60 - + # # sum up the degrees and apply the direction as a sign # return (degrees + minutes) * (-1 if direction in ['W', 'S'] else 1) - + # # The __main__ self test can log position or optionally record a set of waypoints @@ -395,20 +395,20 @@ def __init__(self, samples, nstd = 1.0): Fit an ellipsoid to the given samples at the given multiple of the standard deviation of the samples. """ - + # separate out the points by axis self.x = [w[1] for w in samples] self.y = [w[2] for w in samples] - + # calculate the stats for each axis self.x_stats = stats(self.x) self.y_stats = stats(self.y) # # calculate a rotated ellipse that best fits the samples. - # We use a rotated ellipse because the x and y values - # of each point are not independent. - # + # We use a rotated ellipse because the x and y values + # of each point are not independent. + # def eigsorted(cov): """ Calculate eigenvalues and eigenvectors @@ -463,7 +463,7 @@ def is_in_range(self, x, y): (x <= self.x_stats.max) and \ (y >= self.y_stats.min) and \ (y <= self.y_stats.max) - + def is_in_std(self, x, y, std_multiple=1.0): """ Determine if the given (x, y) point is within a given @@ -486,7 +486,7 @@ def show(self): ax = plt.subplot(111, aspect='equal') self.plot() plt.show() - + def plot(self): """ Draw the waypoint ellipsoid @@ -495,17 +495,17 @@ def plot(self): import matplotlib.pyplot as plt #define Matplotlib figure and axis ax = plt.subplot(111, aspect='equal') - + # plot the collected readings plt.scatter(self.x, self.y) - + # plot the centroid plt.plot(self.x_stats.mean, self.y_stats.mean, marker="+", markeredgecolor="green", markerfacecolor="green") - + # plot the range bounds = Rectangle( - (self.x_stats.min, self.y_stats.min), - self.x_stats.max - self.x_stats.min, + (self.x_stats.min, self.y_stats.min), + self.x_stats.max - self.x_stats.min, self.y_stats.max - self.y_stats.min, alpha=0.5, edgecolor='red', @@ -513,7 +513,7 @@ def plot(self): visible=True) ax.add_artist(bounds) - # plot the ellipsoid + # plot the ellipsoid ellipse = Ellipse(xy=(self.x_stats.mean, self.y_stats.mean), width=self.width, height=self.height, angle=self.theta) @@ -641,7 +641,7 @@ def read_gps(): print(f"...done. Collected {count} samples for waypoint #{len(waypoints)+1}") # # model a waypoint as a rotated ellipsoid - # that represents a 95% confidence interval + # that represents a 95% confidence interval # around the points measured at the waypoint. # waypoint = Waypoint(waypoint_samples, nstd=args.nstd) @@ -682,4 +682,3 @@ def read_gps(): line_reader.shutdown() if update_thread is not None: update_thread.join() # wait for thread to end - diff --git a/donkeycar/parts/graph.py b/donkeycar/parts/graph.py index 03a6f2eee..875b7da50 100644 --- a/donkeycar/parts/graph.py +++ b/donkeycar/parts/graph.py @@ -2,7 +2,7 @@ import cv2 -class Graph(object): +class Graph(): ''' Take input values and plot them on an image. Takes a list of (x, y) (b, g, r) pairs and @@ -36,7 +36,7 @@ def run(self, values): self.img = np.zeros_like(self.img) self.prev = x - + return self.img def shutdown(self): diff --git a/donkeycar/parts/image.py b/donkeycar/parts/image.py index 942127d55..cf4a981b1 100644 --- a/donkeycar/parts/image.py +++ b/donkeycar/parts/image.py @@ -14,7 +14,7 @@ def run(self, img_arr): image = arr_to_img(img_arr) jpg = img_to_binary(image) return jpg - except: + except Exception: return None @@ -42,7 +42,7 @@ def run(self, image_a, image_b): grey_a = dk.utils.rgb2gray(image_a) grey_b = dk.utils.rgb2gray(image_b) grey_c = grey_a - grey_b - + stereo_image = np.zeros([width, height, 3], dtype=np.dtype('B')) stereo_image[...,0] = np.reshape(grey_a, (width, height)) stereo_image[...,1] = np.reshape(grey_b, (width, height)) @@ -62,12 +62,12 @@ def __init__(self, top=0, bottom=0, left=0, right=0): self.bottom = bottom self.left = left self.right = right - + def run(self, img_arr): if img_arr is None: return None width, height, _ = img_arr.shape - img_arr = img_arr[self.top:height-self.bottom, + img_arr = img_arr[self.top:height-self.bottom, self.left: width-self.right] return img_arr @@ -91,11 +91,11 @@ def rgb2gray(self, rgb): greyscale ''' return np.dot(rgb[...,:3], [0.299, 0.587, 0.114]) - + def run(self, img_arr): - width, height, _ = img_arr.shape + width, height, _ = img_arr.shape gray = self.rgb2gray(img_arr) - + if self.img_arr is None: self.img_arr = np.zeros([width, height, self.num_channels], dtype=np.dtype('B')) diff --git a/donkeycar/parts/image_transformations.py b/donkeycar/parts/image_transformations.py index e0b07d780..3c8c4524c 100644 --- a/donkeycar/parts/image_transformations.py +++ b/donkeycar/parts/image_transformations.py @@ -20,7 +20,7 @@ def __init__(self, config: Config, transformation: str, self.transformations = [image_transformer(name, config) for name in transformations] logger.info(f'Creating ImageTransformations {transformations}') - + def run(self, image): """ Run the list of tranformers on the image @@ -88,7 +88,7 @@ def image_transformer(name: str, config): return cv_parts.ImgCanny(config.CANNY_LOW_THRESHOLD, config.CANNY_HIGH_THRESHOLD, config.CANNY_APERTURE) - # + # # blur transformations # elif "BLUR" == name: @@ -98,7 +98,7 @@ def image_transformer(name: str, config): else: return cv_parts.ImgSimpleBlur(config.BLUR_KERNEL, config.BLUR_KERNEL_Y) - # + # # resize transformations # elif "RESIZE" == name: @@ -162,7 +162,7 @@ def run(self, image): class_name = getattr(config, name + "_CLASS", None) if class_name is None: raise ValueError(f"No class declared for custom image transformer: {name}") - + import os import sys import importlib.util @@ -212,4 +212,3 @@ def run(self, image): return my_class(config) else: raise ValueError(f"Unable to load custom tranformation module at {file_path}") - diff --git a/donkeycar/parts/imu.py b/donkeycar/parts/imu.py index 4690fc5e4..0525c6de6 100755 --- a/donkeycar/parts/imu.py +++ b/donkeycar/parts/imu.py @@ -20,10 +20,10 @@ class IMU: sudo python setup.py install pip install mpu6050-raspberrypi - + - MPU9250 pip install mpu9250-jmdev - + ''' def __init__(self, addr=0x68, poll_delay=0.0166, sensor=SENSOR_MPU6050, dlp_setting=DLP_SETTING_DISABLED): @@ -31,10 +31,10 @@ def __init__(self, addr=0x68, poll_delay=0.0166, sensor=SENSOR_MPU6050, dlp_sett if self.sensortype == SENSOR_MPU6050: from mpu6050 import mpu6050 as MPU6050 self.sensor = MPU6050(addr) - + if(dlp_setting > 0): self.sensor.bus.write_byte_data(self.sensor.address, CONFIG_REGISTER, dlp_setting) - + else: from mpu9250_jmdev.registers import AK8963_ADDRESS, GFS_1000, AFS_4G, AK8963_BIT_16, AK8963_MODE_C100HZ from mpu9250_jmdev.mpu_9250 import MPU9250 @@ -48,13 +48,13 @@ def __init__(self, addr=0x68, poll_delay=0.0166, sensor=SENSOR_MPU6050, dlp_sett afs=AFS_4G, mfs=AK8963_BIT_16, mode=AK8963_MODE_C100HZ) - + if(dlp_setting > 0): self.sensor.writeSlave(CONFIG_REGISTER, dlp_setting) self.sensor.calibrateMPU6500() self.sensor.configure() - + self.accel = { 'x' : 0., 'y' : 0., 'z' : 0. } self.gyro = { 'x' : 0., 'y' : 0., 'z' : 0. } self.mag = {'x': 0., 'y': 0., 'z': 0.} @@ -66,7 +66,7 @@ def update(self): while self.on: self.poll() time.sleep(self.poll_delay) - + def poll(self): try: if self.sensortype == SENSOR_MPU6050: @@ -78,9 +78,9 @@ def poll(self): self.gyro = { 'x' : ret[4], 'y' : ret[5], 'z' : ret[6] } self.mag = { 'x' : ret[13], 'y' : ret[14], 'z' : ret[15] } self.temp = ret[16] - except: + except Exception: print('failed to read imu!!') - + def run_threaded(self): return self.accel['x'], self.accel['y'], self.accel['z'], self.gyro['x'], self.gyro['y'], self.gyro['z'], self.temp @@ -95,7 +95,7 @@ def shutdown(self): if __name__ == "__main__": iter = 0 import sys - sensor_type = SENSOR_MPU6050 + sensor_type = SENSOR_MPU6050 dlp_setting = DLP_SETTING_DISABLED if len(sys.argv) > 1: sensor_type = sys.argv[1] @@ -108,4 +108,3 @@ def shutdown(self): print(data) time.sleep(0.1) iter += 1 - diff --git a/donkeycar/parts/interpreter.py b/donkeycar/parts/interpreter.py index d2912e190..a5a7ddeef 100755 --- a/donkeycar/parts/interpreter.py +++ b/donkeycar/parts/interpreter.py @@ -34,12 +34,12 @@ def keras_to_tflite(model, out_filename, data_gen=None): converter.representative_dataset = data_gen try: converter.target_ops = [tf.lite.OpsSet.TFLITE_BUILTINS_INT8] - except: + except Exception: pass try: converter.target_spec.supported_ops \ = [tf.lite.OpsSet.TFLITE_BUILTINS_INT8] - except: + except Exception: pass converter.inference_input_type = tf.uint8 converter.inference_output_type = tf.uint8 @@ -67,7 +67,7 @@ def saved_model_to_tensor_rt(saved_path: str, tensor_rt_path: str): conversion_params=params) converter.convert() converter.save(tensor_rt_path) - logger.info(f'TensorRT conversion done.') + logger.info('TensorRT conversion done.') except Exception as e: logger.error(f'TensorRT conversion failed because: {e}') @@ -241,7 +241,7 @@ def __init__(self): self.input_shapes = None self.input_details = None self.output_details = None - + def load(self, model_path): assert os.path.splitext(model_path)[1] == '.tflite', \ 'TFlitePilot should load only .tflite files' diff --git a/donkeycar/parts/keras.py b/donkeycar/parts/keras.py index 7e8ffe487..0e0329bfa 100644 --- a/donkeycar/parts/keras.py +++ b/donkeycar/parts/keras.py @@ -181,7 +181,7 @@ def train(self, verbose=verbose, workers=1, use_multiprocessing=False) - + if show_plot: try: import matplotlib.pyplot as plt @@ -215,7 +215,7 @@ def train(self, except Exception as ex: print(f"problems with loss graph: {ex}") - + return history.history def x_transform( @@ -578,7 +578,7 @@ def create_model(self): def compile(self): self.interpreter.compile(optimizer=self.optimizer, metrics=['acc'], loss='mse') - + def interpreter_to_output(self, interpreter_out) \ -> Tuple[Union[float, np.ndarray], ...]: angle, throttle, track_loc = interpreter_out @@ -895,12 +895,12 @@ def default_imu(num_outputs, num_imu_inputs, input_shape): x = core_cnn_layers(img_in, drop) x = Dense(100, activation='relu')(x) x = Dropout(.1)(x) - + y = imu_in y = Dense(14, activation='relu')(y) y = Dense(14, activation='relu')(y) y = Dense(14, activation='relu')(y) - + z = concatenate([x, y]) z = Dense(50, activation='relu')(z) z = Dropout(.1)(z) @@ -910,7 +910,7 @@ def default_imu(num_outputs, num_imu_inputs, input_shape): outputs = [] for i in range(num_outputs): outputs.append(Dense(1, activation='linear', name='out_' + str(i))(z)) - + model = Model(inputs=[img_in, imu_in], outputs=outputs, name='imu') return model @@ -925,23 +925,23 @@ def default_bhv(num_bvh_inputs, input_shape): x = core_cnn_layers(img_in, drop) x = Dense(100, activation='relu')(x) x = Dropout(.1)(x) - + y = bvh_in y = Dense(num_bvh_inputs * 2, activation='relu')(y) y = Dense(num_bvh_inputs * 2, activation='relu')(y) y = Dense(num_bvh_inputs * 2, activation='relu')(y) - + z = concatenate([x, y]) z = Dense(100, activation='relu')(z) z = Dropout(.1)(z) z = Dense(50, activation='relu')(z) z = Dropout(.1)(z) - + # Categorical output of the angle into 15 bins angle_out = Dense(15, activation='softmax', name='angle_out')(z) # Categorical output of throttle into 20 bins throttle_out = Dense(20, activation='softmax', name='throttle_out')(z) - + model = Model(inputs=[img_in, bvh_in], outputs=[angle_out, throttle_out], name='behavioral') return model @@ -954,7 +954,7 @@ def default_loc(num_locations, input_shape): x = core_cnn_layers(img_in, drop) x = Dense(100, activation='relu')(x) x = Dropout(drop)(x) - + z = Dense(50, activation='relu')(x) z = Dropout(drop)(z) @@ -1088,7 +1088,7 @@ def default_latent(num_outputs, input_shape): x = Convolution2D(64, 3, strides=2, activation='relu', name="conv2d_7")(x) x = Dropout(drop)(x) x = Convolution2D(64, 1, strides=2, activation='relu', name="latent")(x) - + y = Conv2DTranspose(filters=64, kernel_size=3, strides=2, name="deconv2d_1")(x) y = Conv2DTranspose(filters=64, kernel_size=3, strides=2, @@ -1100,7 +1100,7 @@ def default_latent(num_outputs, input_shape): y = Conv2DTranspose(filters=32, kernel_size=3, strides=2, name="deconv2d_5")(y) y = Conv2DTranspose(filters=1, kernel_size=3, strides=2, name="img_out")(y) - + x = Flatten(name='flattened')(x) x = Dense(256, activation='relu')(x) x = Dropout(drop)(x) @@ -1112,6 +1112,6 @@ def default_latent(num_outputs, input_shape): outputs = [y] for i in range(num_outputs): outputs.append(Dense(1, activation='linear', name='n_outputs' + str(i))(x)) - + model = Model(inputs=[img_in], outputs=outputs, name='latent') return model diff --git a/donkeycar/parts/kinematics.py b/donkeycar/parts/kinematics.py index 360c740de..88f8d9dfe 100644 --- a/donkeycar/parts/kinematics.py +++ b/donkeycar/parts/kinematics.py @@ -202,7 +202,7 @@ def run(self, forward_velocity:float, angular_velocity:float, timestamp:float=No math.tan(steering_angle) = angular_velocity * self.wheel_base / forward_velocity steering_angle = math.atan(angular_velocity * self.wheel_base / forward_velocity) """ - steering_angle = bicycle_steering_angle(self.wheel_base, forward_velocity, angular_velocity) + steering_angle = bicycle_steering_angle(self.wheel_base, forward_velocity, angular_velocity) self.timestamp = timestamp return forward_velocity, steering_angle, timestamp @@ -531,7 +531,7 @@ def __init__(self, max_steering_angle:float, steering_zero:float=0.0) -> None: """ self.max_steering_angle = max_steering_angle self.steering_zero = steering_zero - + def run(self, steering_angle) -> float: """ @param steering angle in radians where @@ -567,7 +567,7 @@ def __init__(self, max_steering_angle:float, steering_zero:float=0.0) -> None: """ self.max_steering_angle = max_steering_angle self.steering_zero = steering_zero - + def run(self, steering) -> float: """ @param a normalized steering value in range -1 to 1, where @@ -582,10 +582,10 @@ def run(self, steering) -> float: return 0 if steering > 1 or steering < -1: - logger.warn(f"steering = {steering}, but must be between 1(right) and -1(left)") + logger.warning(f"steering = {steering}, but must be between 1(right) and -1(left)") steering = clamp(steering, -1, 1) - + s = sign(steering) steering = abs(steering) if steering <= self.steering_zero: @@ -611,46 +611,48 @@ def wheel_rotational_velocity(wheel_radius:float, speed:float) -> float: def differential_steering(throttle: float, steering: float, steering_zero: float = 0) -> Tuple[float, float]: - """ - Turn steering angle and speed/throttle into - left and right wheel speeds/throttle. - This basically slows down one wheel by the steering value - while leaving the other wheel at the desired throttle. - So, except for the case where the steering is zero (going straight forward), - the effective throttle is low than the requested throttle. - This is different than car-like vehicles, where the effective - forward throttle is not affected by the steering angle. - This is is NOT inverse kinematics; it is appropriate for managing throttle - when a user is driving the car (so the user is the controller) - This is the algorithm used by TwoWheelSteeringThrottle. + """ + Turn steering angle and speed/throttle into + left and right wheel speeds/throttle. + This basically slows down one wheel by the steering value + while leaving the other wheel at the desired throttle. + So, except for the case where the steering is zero (going straight forward), + the effective throttle is low than the requested throttle. + This is different than car-like vehicles, where the effective + forward throttle is not affected by the steering angle. + This is is NOT inverse kinematics; it is appropriate for managing throttle + when a user is driving the car (so the user is the controller) + This is the algorithm used by TwoWheelSteeringThrottle. + + @Param throttle:float throttle or real speed; reverse < 0, 0 is stopped, forward > 0 + @Param steering:float -1 to 1, -1 full left, 0 straight, 1 is full right + @Param steering_zero:float values abs(steering) <= steering_zero are considered zero. + """ + if not is_number_type(throttle): + logger.error("throttle must be a number") + return 0, 0 + if throttle > 1 or throttle < -1: + logger.warning( + f"throttle = {throttle}, but must be between 1(right) and -1(left)") + throttle = clamp(throttle, -1, 1) - @Param throttle:float throttle or real speed; reverse < 0, 0 is stopped, forward > 0 - @Param steering:float -1 to 1, -1 full left, 0 straight, 1 is full right - @Param steering_zero:float values abs(steering) <= steering_zero are considered zero. - """ - if not is_number_type(throttle): - logger.error("throttle must be a number") - return 0, 0 - if throttle > 1 or throttle < -1: - logger.warn(f"throttle = {throttle}, but must be between 1(right) and -1(left)") - throttle = clamp(throttle, -1, 1) + if not is_number_type(steering): + logger.error("steering must be a number") + return 0, 0 + if steering > 1 or steering < -1: + logger.warning( + f"steering = {steering}, but must be between 1(right) and -1(left)") + steering = clamp(steering, -1, 1) - if not is_number_type(steering): - logger.error("steering must be a number") - return 0, 0 - if steering > 1 or steering < -1: - logger.warn(f"steering = {steering}, but must be between 1(right) and -1(left)") - steering = clamp(steering, -1, 1) + left_throttle = throttle + right_throttle = throttle - left_throttle = throttle - right_throttle = throttle - - if steering < -steering_zero: - left_throttle *= (1.0 + steering) - elif steering > steering_zero: - right_throttle *= (1.0 - steering) + if steering < -steering_zero: + left_throttle *= (1.0 + steering) + elif steering > steering_zero: + right_throttle *= (1.0 - steering) - return left_throttle, right_throttle + return left_throttle, right_throttle class TwoWheelSteeringThrottle: @@ -672,6 +674,6 @@ def run(self, throttle, steering): @Param steering:float -1 to 1, -1 full left, 0 straight, 1 is full right """ return differential_steering(throttle, steering, self.steering_zero) - + def shutdown(self): pass diff --git a/donkeycar/parts/launch.py b/donkeycar/parts/launch.py index 7882d9a61..c4eb3a773 100644 --- a/donkeycar/parts/launch.py +++ b/donkeycar/parts/launch.py @@ -15,7 +15,7 @@ def __init__(self, launch_duration=1.0, launch_throttle=1.0, keep_enabled=False) self.launch_throttle = launch_throttle self.prev_mode = None self.trigger_on_switch = keep_enabled - + def enable_ai_launch(self): self.enabled = True print('AiLauncher is enabled.') @@ -45,4 +45,3 @@ def run(self, mode, ai_throttle): new_throttle = self.launch_throttle return new_throttle - diff --git a/donkeycar/parts/led_status.py b/donkeycar/parts/led_status.py index de39e5f06..fa66ab43d 100644 --- a/donkeycar/parts/led_status.py +++ b/donkeycar/parts/led_status.py @@ -19,7 +19,7 @@ def toggle(self, condition): self.on = True else: GPIO.output(self.pin, GPIO.LOW) - self.on = False + self.on = False def blink(self, rate): if time.time() - self.blink_changed > rate: @@ -35,7 +35,7 @@ def run(self, blink_rate): self.toggle(True) def shutdown(self): - self.toggle(False) + self.toggle(False) GPIO.cleanup() @@ -120,13 +120,13 @@ def shutdown(self): print('output pin', pin_r, pin_g, pin_b, 'rate', rate) p = RGB_LED(pin_r, pin_g, pin_b) - + iter = 0 while iter < 50: p.run(rate) time.sleep(0.1) iter += 1 - + delay = 0.1 iter = 0 @@ -134,7 +134,7 @@ def shutdown(self): p.set_rgb(iter, 100-iter, 0) time.sleep(delay) iter += 1 - + iter = 0 while iter < 100: p.set_rgb(100 - iter, 0, iter) @@ -142,4 +142,3 @@ def shutdown(self): iter += 1 p.shutdown() - diff --git a/donkeycar/parts/leopard_imaging.py b/donkeycar/parts/leopard_imaging.py index 9a7e7d521..1f176a488 100644 --- a/donkeycar/parts/leopard_imaging.py +++ b/donkeycar/parts/leopard_imaging.py @@ -9,7 +9,7 @@ class LICamera(BaseCamera): The Leopard Imaging Camera with Fast-Stretch built in. ''' def __init__(self, width=224, height=224, capture_width=1280, capture_height=720, fps=60): - super(LICamera, self).__init__() + super().__init__() self.width = width self.height = height self.capture_width = capture_width @@ -54,4 +54,4 @@ def shutdown(self): @classmethod def camera_id(cls, capture_width, capture_height, width, height, fps): return 'nvarguscamerasrc ! video/x-raw(memory:NVMM), width=%d, height=%d, format=(string)NV12, framerate=(fraction)%d/1 ! nvvidconv ! video/x-raw, width=(int)%d, height=(int)%d, format=(string)BGRx ! videoconvert ! appsink' % ( - capture_width, capture_height, fps, width, height) \ No newline at end of file + capture_width, capture_height, fps, width, height) diff --git a/donkeycar/parts/lidar.py b/donkeycar/parts/lidar.py index 4eaf8d977..2f77fde4d 100644 --- a/donkeycar/parts/lidar.py +++ b/donkeycar/parts/lidar.py @@ -46,7 +46,7 @@ def angle_in_bounds(angle, min_angle, max_angle): return (min_angle <= angle <= 360) or (max_angle >= angle >= 0) -class RPLidar2(object): +class RPLidar2(): ''' Adapted from https://github.com/Ezward/rplidar NOTES @@ -62,7 +62,7 @@ def __init__(self, angle_direction=CLOCKWISE, batch_ms=50, # how long to loop in run() debug=False): - + self.lidar = None self.port = None self.on = False @@ -73,16 +73,16 @@ def __init__(self, if max_distance <= 0: help.append("max_distance must be > 0") - + if min_angle < 0 or min_angle > 360: help.append("min_angle must be 0 <= min_angle <= 360") if max_angle <= 0 or max_angle > 360: help.append("max_angle must be 0 < max_angle <= 360") - + if forward_angle < 0 or forward_angle > 360: help.append("forward_angle must be 0 <= forward_angle <= 360") - + if angle_direction != CLOCKWISE and \ angle_direction != COUNTER_CLOCKWISE: help.append("angle-direction must be 1 (clockwise) or -1 (counter-clockwise)") # noqa @@ -97,11 +97,11 @@ def __init__(self, self.max_distance = max_distance self.forward_angle = forward_angle self.spin_reverse = (args.angle_direction != CLOCKWISE) - self.measurements = [] # list of (distance, angle, time, scan, index) + self.measurements = [] # list of (distance, angle, time, scan, index) from adafruit_rplidar import RPLidar import glob - + # # find the serial port where the lidar is connected # @@ -142,7 +142,7 @@ def poll(self): # read one measurement # new_scan, quality, angle, distance = next(self.iter_measurements) # noqa - + now = time.time() self.total_measurements += 1 @@ -152,17 +152,17 @@ def poll(self): self.full_scan_index = 0 self.measurement_count = self.measurement_index # this full scan self.measurement_index = 0 # start filling in next scan - + # # rplidar spins clockwise, # but we want angles to increase counter-clockwise # if self.spin_reverse: angle = (360.0 - (angle % 360.0)) % 360.0 - + # adjust so zero degrees is 'forward' angle = (angle - self.forward_angle + 360.0) % 360.0 - + # filter the measurement by angle and distance if angle_in_bounds(angle, self.min_angle, self.max_angle): if distance >= self.min_distance and distance <= self.max_distance: @@ -207,7 +207,7 @@ def poll(self): # measurement = (distance, angle, now, self.full_scan_count, self.full_scan_index) - + # grow buffer if necessary, otherwise overwrite if self.measurement_index >= len(self.measurements): self.measurements.append(measurement) @@ -216,7 +216,7 @@ def poll(self): self.measurements[self.measurement_index] = measurement # noqa self.measurement_index += 1 self.full_scan_index += 1 - + except serial.serialutil.SerialException: logger.error('SerialException from RPLidar.') @@ -228,17 +228,17 @@ def update(self): total_time = time.time() - start_time scan_rate = self.full_scan_count / total_time measurement_rate = self.total_measurements / total_time - logger.info("RPLidar total scan time = {time} seconds".format(time=total_time)) - logger.info("RPLidar total scan count = {count} scans".format(count=self.full_scan_count)) - logger.info("RPLidar total measurement count = {count} measurements".format(count=self.total_measurements)) - logger.info("RPLidar rate = {rate} scans per second".format(rate=scan_rate)) - logger.info("RPLidar rate = {rate} measurements per second".format(rate=measurement_rate)) + logger.info(f"RPLidar total scan time = {total_time} seconds") + logger.info(f"RPLidar total scan count = {self.full_scan_count} scans") + logger.info(f"RPLidar total measurement count = {self.total_measurements} measurements") + logger.info(f"RPLidar rate = {scan_rate} scans per second") + logger.info(f"RPLidar rate = {measurement_rate} measurements per second") def run_threaded(self): if self.running: return self.measurements return [] - + def run(self): if not self.running: return [] @@ -264,7 +264,7 @@ def shutdown(self): self.lidar = None -class RPLidar(object): +class RPLidar(): ''' https://github.com/adafruit/Adafruit_CircuitPython_RPLIDAR ''' @@ -332,7 +332,7 @@ def shutdown(self): self.lidar.disconnect() -class YDLidar(object): +class YDLidar(): ''' https://pypi.org/project/PyLidar3/ ''' @@ -390,7 +390,7 @@ def shutdown(self): self.lidar.Disconnect() -class LidarPlot(object): +class LidarPlot(): ''' takes the raw lidar measurements and plots it to an image ''' @@ -408,7 +408,7 @@ def __init__(self, resolution=(500,500), self.plot_fn = self.plot_circ else: self.plot_fn = self.plot_line - + def plot_line(self, img, dist, theta, max_dist, draw): ''' scale dist so that max_dist is edge of img (mm) @@ -428,7 +428,7 @@ def plot_line(self, img, dist, theta, max_dist, draw): ey = math.sin(theta) * (dist + self.rad) + center[1] fill = 128 draw.line((sx,sy, ex, ey), fill=(fill, fill, fill), width=1) - + def plot_circ(self, img, dist, theta, max_dist, draw): ''' scale dist so that max_dist is edge of img (mm) @@ -454,7 +454,7 @@ def plot_circ(self, img, dist, theta, max_dist, draw): def plot_scan(self, img, distances, angles, max_dist, draw): for dist, angle in zip(distances, angles): self.plot_fn(img, dist, angle, max_dist, draw) - + def run(self, distances, angles): ''' takes two lists of equal length, one of distance values, @@ -522,12 +522,12 @@ def plot_polar_point(draw_context, bounds, mark_fn, mark_color, mark_px, cy = (top + bottom) / 2 max_pixel = min(cx, cy) distance_px = distance / max_distance * max_pixel - + theta = (theta + rotate_plot) % 360.0 - + if angle_direction != COUNTER_CLOCKWISE: theta = (360.0 - (theta % 360.0)) % 360.0 - + mark_fn(draw_context, cx, cy, distance_px, theta, mark_color, mark_px) @@ -553,7 +553,7 @@ def plot_polar_points(draw_context, bounds, mark_fn, mark_color, mark_px, rotate_plot: angle in positive degrees to rotate the measurement mark. this can be used to match the direction of the robot when it is plotted in world coordinates. - """ + """ # plot each measurement for distance, angle in measurements: plot_polar_point(draw_context, bounds, mark_fn, mark_color, mark_px, @@ -584,7 +584,7 @@ def plot_polar_bounds(draw_context, bounds, color, cx = (left + right) / 2 cy = (top + bottom) / 2 max_pixel = min(cx, cy) - + # # draw the zero heading axis # @@ -608,7 +608,7 @@ def plot_polar_angle(draw_context, bounds, color, theta, assuming the polar origin is at the center of bounding box and the bounding distance is the minimum of the width and height of the bounding box - + draw_context: PIL draw context bounds: tuple (left, top, right, bottom) indicating bounds within which the plot should be drawn. @@ -624,7 +624,7 @@ def plot_polar_angle(draw_context, bounds, color, theta, cx = (left + right) / 2 cy = (top + bottom) / 2 max_pixel = min(cx, cy) - + # # draw the zero heading axis # @@ -632,7 +632,7 @@ def plot_polar_angle(draw_context, bounds, color, theta, theta += rotate_plot if angle_direction != COUNTER_CLOCKWISE: theta = (360.0 - (theta % 360.0)) % 360.0 - + # draw the angle line theta = np.radians(theta) sx = cx + math.cos(theta) * max_pixel @@ -640,11 +640,11 @@ def plot_polar_angle(draw_context, bounds, color, theta, draw_context.line((cx, cy, sx, sy), fill=color, width=1) -class LidarPlot2(object): +class LidarPlot2(): ''' takes the lidar measurements as a list of (distance, angle) tuples and plots them to a PIL image which it outputs - + resolution: dimensions of image in pixels as tuple (width, height) plot_type: PLOT_TYPE_CIRC or PLOT_TYPE_LINE mark_px: size of data measurement marks in pixels @@ -662,12 +662,12 @@ def __init__(self, plot_type=PLOT_TYPE_CIRCLE, mark_px=3, max_dist=4000, #mm - angle_direction=COUNTER_CLOCKWISE, + angle_direction=COUNTER_CLOCKWISE, rotate_plot=0, background_color=(224, 224, 224), border_color=(128, 128, 128), point_color=(255, 64, 64)): - + self.frame = Image.new('RGB', resolution) self.mark_px = mark_px self.max_distance = max_dist @@ -678,7 +678,7 @@ def __init__(self, self.mark_fn = mark_line self.angle_direction = angle_direction self.rotate_plot = rotate_plot - + self.background_color = background_color self.border_color = border_color self.point_color = point_color @@ -688,11 +688,11 @@ def run(self, measurements): draw measurements to a PIL image and output the pil image measurements: list of polar coordinates as (distance, angle) tuples ''' - + self.frame = Image.new('RGB', self.resolution, (255, 255, 255)) bounds = (0, 0, self.frame.width, self.frame.height) draw = ImageDraw.Draw(self.frame) - + # background draw.rectangle(bounds, fill=self.background_color) @@ -701,20 +701,20 @@ def run(self, measurements): self.angle_direction, self.rotate_plot) plot_polar_angle(draw, bounds, self.border_color, 0, self.angle_direction, self.rotate_plot) - + # data points plot_polar_points( draw, bounds, self.mark_fn, self.point_color, self.mark_px, [(distance, angle) for distance, angle, _, _, _ in measurements], self.max_distance, self.angle_direction, self.rotate_plot) - + return self.frame def shutdown(self): pass -class BreezySLAM(object): +class BreezySLAM(): ''' https://github.com/simondlevy/BreezySLAM ''' @@ -728,9 +728,9 @@ def __init__(self, MAP_SIZE_PIXELS=500, MAP_SIZE_METERS=10): MAP_QUALITY=5 self.slam = RMHC_SLAM(laser_model, MAP_SIZE_PIXELS, MAP_SIZE_METERS, MAP_QUALITY) - + def run(self, distances, angles, map_bytes): - + self.slam.update(distances, scan_angles_degrees=angles) x, y, theta = self.slam.getpos() @@ -743,7 +743,7 @@ def shutdown(self): pass -class BreezyMap(object): +class BreezyMap(): ''' bitmap that may optionally be constructed by BreezySLAM ''' @@ -757,7 +757,7 @@ def shutdown(self): pass -class MapToImage(object): +class MapToImage(): def __init__(self, resolution=(500, 500)): self.resolution = resolution @@ -775,11 +775,11 @@ def shutdown(self): import cv2 import json from threading import Thread - + def convert_from_image_to_cv2(img: Image) -> np.ndarray: # return cv2.cvtColor(np.array(img), cv2.COLOR_RGB2BGR) return np.asarray(img) - + # parse arguments parser = argparse.ArgumentParser() parser.add_argument("-r", "--rate", type=float, default=20, @@ -804,45 +804,45 @@ def convert_from_image_to_cv2(img: Image) -> np.ndarray: # Read arguments from command line args = parser.parse_args() - + help = [] if args.rate < 1: help.append("-r/--rate: must be >= 1.") - + if args.number < 1: help.append("-n/--number: must be >= 1.") - + if args.min_distance < 0: help.append("-d/--min-distance must be >= 0") if args.max_distance <= 0: help.append("-D/--max-distance must be > 0") - + if args.min_angle < 0 or args.min_angle > 360: help.append("-a/--min-angle must be 0 <= min-angle <= 360") if args.max_angle <= 0 or args.max_angle > 360: help.append("-A/--max-angle must be 0 < max-angle <= 360") - + if args.forward_angle < 0 or args.forward_angle > 360: help.append("-f/--forward-angle must be 0 <= forward-angle <= 360") - + if args.angle_direction != CLOCKWISE and \ args.angle_direction != COUNTER_CLOCKWISE: help.append("-s/--angle-direction must be 1 (clockwise) or -1 (counter-clockwise)") # noqa - + if args.rotate_plot < 0 or args.rotate_plot > 360: help.append("-p/--rotate-plot must be 0 <= min-angle <= 360") - + if len(help) > 0: parser.print_help() for h in help: print(" " + h) sys.exit(1) - + lidar_thread = None lidar = None - + try: scan_count = 0 seconds_per_scan = 1.0 / args.rate @@ -857,7 +857,7 @@ def convert_from_image_to_cv2(img: Image) -> np.ndarray: forward_angle=args.forward_angle, angle_direction=args.angle_direction, batch_ms=1000.0/args.rate) - + # # construct a lidar plotter # @@ -867,7 +867,7 @@ def convert_from_image_to_cv2(img: Image) -> np.ndarray: rotate_plot=args.rotate_plot, background_color=(32, 32, 32), border_color=(128, 128, 128), - point_color=(64, 255, 64)) + point_color=(64, 255, 64)) # # start the threaded part # and a threaded window to show plot @@ -877,7 +877,7 @@ def convert_from_image_to_cv2(img: Image) -> np.ndarray: lidar_thread = Thread(target=lidar.update, args=()) lidar_thread.start() cv2.startWindowThread() - + while scan_count < args.number: start_time = time.time() @@ -889,13 +889,13 @@ def convert_from_image_to_cv2(img: Image) -> np.ndarray: measurements = lidar.run_threaded() else: measurements = lidar.run() - + img = plotter.run(measurements) - + # show the image in the window cv2img = convert_from_image_to_cv2(img) cv2.imshow("lidar", cv2img) - + if not args.threaded: key = cv2.waitKey(1) & 0xFF if 27 == key or key == ord('q') or key == ord('Q'): @@ -912,7 +912,7 @@ def convert_from_image_to_cv2(img: Image) -> np.ndarray: print('Stopping early.') except Exception as e: print(e) - exit(1) + sys.exit(1) finally: if lidar is not None: lidar.shutdown() diff --git a/donkeycar/parts/line_follower.py b/donkeycar/parts/line_follower.py index f9ee665e4..36ec53760 100644 --- a/donkeycar/parts/line_follower.py +++ b/donkeycar/parts/line_follower.py @@ -122,10 +122,10 @@ def overlay_display(self, cam_img, mask, max_yellow, confidense): # img = cv2.cvtColor(img, cv2.COLOR_RGB2BGR) display_str = [] - display_str.append("STEERING:{:.1f}".format(self.steering)) - display_str.append("THROTTLE:{:.2f}".format(self.throttle)) - display_str.append("I YELLOW:{:d}".format(max_yellow)) - display_str.append("CONF:{:.2f}".format(confidense)) + display_str.append(f"STEERING:{self.steering:.1f}") + display_str.append(f"THROTTLE:{self.throttle:.2f}") + display_str.append(f"I YELLOW:{max_yellow:d}") + display_str.append(f"CONF:{confidense:.2f}") y = 10 x = 10 @@ -135,4 +135,3 @@ def overlay_display(self, cam_img, mask, max_yellow, confidense): y += 10 return img - diff --git a/donkeycar/parts/network.py b/donkeycar/parts/network.py index 181fe2980..855383fac 100644 --- a/donkeycar/parts/network.py +++ b/donkeycar/parts/network.py @@ -1,9 +1,10 @@ import socket -import zlib, pickle +import zlib +import pickle import zmq import time -class ZMQValuePub(object): +class ZMQValuePub(): ''' Use Zero Message Queue (zmq) to publish values ''' @@ -13,7 +14,7 @@ def __init__(self, name, port = 5556, hwm=10): self.socket = context.socket(zmq.PUB) self.socket.set_hwm(hwm) self.socket.bind("tcp://*:%d" % port) - + def run(self, values): packet = { "name": self.name, "val" : values } p = pickle.dumps(packet) @@ -26,7 +27,7 @@ def shutdown(self): context = zmq.Context() context.destroy() -class ZMQValueSub(object): +class ZMQValueSub(): ''' Use Zero Message Queue (zmq) to subscribe to value messages from a remote publisher ''' @@ -57,7 +58,7 @@ def run(self): obj = pickle.loads(p) if self.name == obj['name']: - self.last = obj['val'] + self.last = obj['val'] return obj['val'] if self.return_last: @@ -69,7 +70,7 @@ def shutdown(self): context = zmq.Context() context.destroy() -class UDPValuePub(object): +class UDPValuePub(): ''' Use udp to broadcast values on local network ''' @@ -77,7 +78,7 @@ def __init__(self, name, port = 37021): self.name = name self.port = port self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP) - self.sock.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1) + self.sock.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1) self.sock.settimeout(0.2) self.sock.bind(("", 44444)) @@ -91,7 +92,7 @@ def run(self, values): def shutdown(self): self.sock.close() -class UDPValueSub(object): +class UDPValueSub(): ''' Use UDP to listen for broadcase packets ''' @@ -132,7 +133,7 @@ def shutdown(self): import select -class TCPServeValue(object): +class TCPServeValue(): ''' Use tcp to serve values on local network ''' @@ -165,7 +166,7 @@ def run(self, values): self.clients, [], timeout) - + if len(ready_to_write) > 0: packet = { "name": self.name, "val" : values } p = pickle.dumps(packet) @@ -176,7 +177,7 @@ def run(self, values): except BrokenPipeError or ConnectionResetError: print("client dropped connection") self.clients.remove(client) - + if self.sock in ready_to_read: client, addr = self.sock.accept() print("got connection from", addr) @@ -191,7 +192,7 @@ def shutdown(self): self.sock.close() -class TCPClientValue(object): +class TCPClientValue(): ''' Use tcp to get values on local network ''' @@ -250,16 +251,16 @@ def reset(self): self.sock.close() self.sock = None self.lastread = time.time() - - + + def run(self): time_since_last_read = abs(time.time() - self.lastread) - + if self.sock is None: if not self.connect(): return None - elif time_since_last_read > 5.0: + elif time_since_last_read > 5.0: print("error: no data from server. may have died") self.reset() return None @@ -290,7 +291,7 @@ def run(self): return None if self.name == obj['name']: - self.last = obj['val'] + self.last = obj['val'] return obj['val'] if len(in_error) > 0: @@ -302,7 +303,7 @@ def run(self): def shutdown(self): self.sock.close() -class MQTTValuePub(object): +class MQTTValuePub(): ''' Use MQTT to send values on network pip install paho-mqtt @@ -329,7 +330,7 @@ def shutdown(self): self.client.loop_stop() -class MQTTValueSub(object): +class MQTTValueSub(): ''' Use MQTT to recv values on network pip install paho-mqtt @@ -350,7 +351,7 @@ def __init__(self, name, broker="iot.eclipse.org", def_value=None): def on_message(self, client, userdata, message): self.data = message.payload - + def run(self): if self.data is None: return self.def_value @@ -362,7 +363,7 @@ def run(self): self.last = obj['val'] #print("steering, throttle", obj['val']) return obj['val'] - + return self.def_value def shutdown(self): @@ -371,7 +372,7 @@ def shutdown(self): def test_pub_sub(ip): - + if ip is None: print("publishing test..") p = ZMQValuePub('test') @@ -395,7 +396,7 @@ def test_pub_sub(ip): time.sleep(1) def test_udp_broadcast(ip): - + if ip is None: print("udp broadcast test..") p = UDPValuePub('camera') @@ -404,7 +405,7 @@ def test_udp_broadcast(ip): cam = PiCamera(160, 120, 3, framerate=4) img_conv = ImgArrToJpg() time.sleep(1) - + while True: cam_img = cam.run() jpg = img_conv.run(cam_img) @@ -440,7 +441,7 @@ def test_tcp_client_server(ip): time.sleep(0.01) def test_mqtt_pub_sub(ip): - + if ip is None: print("publishing test..") p = MQTTValuePub('donkey/camera') @@ -484,5 +485,3 @@ def test_mqtt_pub_sub(ip): #test_udp_broadcast(ip) #test_mqtt_pub_sub(ip) test_tcp_client_server(ip) - - diff --git a/donkeycar/parts/object_detector/stop_sign_detector.py b/donkeycar/parts/object_detector/stop_sign_detector.py index 93175e977..dc267edeb 100755 --- a/donkeycar/parts/object_detector/stop_sign_detector.py +++ b/donkeycar/parts/object_detector/stop_sign_detector.py @@ -11,7 +11,7 @@ import urllib.request -class StopSignDetector(object): +class StopSignDetector(): ''' Requires an EdgeTPU for this part to work @@ -70,7 +70,7 @@ def detect_stop_sign (self, img_arr): for obj in ans: if (obj.label_id == self.STOP_SIGN_CLASS_ID): if self.debug: - print("stop sign detected, score = {}".format(obj.score)) + print(f"stop sign detected, score = {obj.score}") if (obj.score > max_score): print(obj.bounding_box) traffic_light_obj = obj @@ -116,7 +116,7 @@ def run(self, img_arr, throttle, debug=False): if traffic_light_obj or self.is_reversing: if self.show_bounding_box and traffic_light_obj != None: self.draw_bounding_box(traffic_light_obj, img_arr) - + # Set the throttle to reverse within the max reverse count when detected the traffic light object if self.reverse_count < self.max_reverse_count: self.is_reversing = True diff --git a/donkeycar/parts/oled.py b/donkeycar/parts/oled.py index 2ce137a46..25a830280 100644 --- a/donkeycar/parts/oled.py +++ b/donkeycar/parts/oled.py @@ -8,7 +8,7 @@ import adafruit_ssd1306 -class OLEDDisplay(object): +class OLEDDisplay(): ''' Manages drawing of text on the OLED display. ''' @@ -85,7 +85,7 @@ def update(self): self.display.show() -class OLEDPart(object): +class OLEDPart(): ''' The part that updates status on the oled display. ''' @@ -102,11 +102,11 @@ def __init__(self, rotation, resolution, auto_record_on_throttle=False): eth0 = OLEDPart.get_ip_address('eth0') wlan0 = OLEDPart.get_ip_address('wlan0') if eth0 is not None: - self.eth0 = 'eth0:%s' % (eth0) + self.eth0 = f'eth0:{eth0}' else: self.eth0 = None if wlan0 is not None: - self.wlan0 = 'wlan0:%s' % (wlan0) + self.wlan0 = f'wlan0:{wlan0}' else: self.wlan0 = None @@ -119,11 +119,11 @@ def run_threaded(self, recording, num_records, user_mode): self.num_records = num_records if recording: - self.recording = 'YES (Records = %s)' % (self.num_records) + self.recording = f'YES (Records = {self.num_records})' else: - self.recording = 'NO (Records = %s)' % (self.num_records) + self.recording = f'NO (Records = {self.num_records})' - self.user_mode = 'User Mode (%s)' % (user_mode) + self.user_mode = f'User Mode ({user_mode})' def update_slots(self): updates = [self.eth0, self.wlan0, self.recording, self.user_mode] @@ -158,4 +158,4 @@ def get_ip_address(cls, interface): @classmethod def get_network_interface_state(cls, interface): - return subprocess.check_output('cat /sys/class/net/%s/operstate' % interface, shell=True).decode('ascii')[:-1] + return subprocess.check_output(f'cat /sys/class/net/{interface}/operstate', shell=True).decode('ascii')[:-1] diff --git a/donkeycar/parts/path.py b/donkeycar/parts/path.py index c0bd4985c..957d6077f 100644 --- a/donkeycar/parts/path.py +++ b/donkeycar/parts/path.py @@ -137,7 +137,7 @@ def load(self, filename): self.recording = False return True -class PImage(object): +class PImage(): def __init__(self, resolution=(500, 500), color="white", clear_each_frame=False): self.resolution = resolution self.color = color @@ -151,7 +151,7 @@ def run(self): return self.img -class OriginOffset(object): +class OriginOffset(): ''' Use this to set the car back to the origin without restarting it. ''' @@ -217,7 +217,7 @@ def init_to_last(self): self.set_origin(self.last_x, self.last_y) -class PathPlot(object): +class PathPlot(): ''' draw a path plot to an image ''' @@ -233,7 +233,7 @@ def plot_line(self, sx, sy, ex, ey, draw, color): draw.line((sx,sy, ex, ey), fill=color, width=1) def run(self, img, path): - + if type(img) is numpy.ndarray: stacked_img = numpy.stack((img,)*3, axis=-1) img = arr_to_img(stacked_img) @@ -257,7 +257,7 @@ def run(self, img, path): return img -class PlotCircle(object): +class PlotCircle(): ''' draw a circle plot to an image ''' @@ -285,14 +285,14 @@ def run(self, img, x, y): self.plot_circle(x * self.scale + self.offset[0], y * -self.scale + self.offset[1], # y increases going north self.radius, - draw, + draw, self.color) return img from donkeycar.la import Line3D, Vec3 -class CTE(object): +class CTE(): def __init__(self, look_ahead=1, look_behind=1, num_pts=None) -> None: self.num_pts = num_pts @@ -347,7 +347,7 @@ def nearest_two_pts(self, path, x, y): # get the next point in the path as the end of the segment iB = (iA + 2) % len(path) b = path[iB] - + return a, b def nearest_waypoints(self, path, x, y, look_ahead=1, look_behind=1, from_pt=0, num_pts=None): @@ -411,10 +411,10 @@ def run(self, path, x, y, from_pt=None): cte = 0. i = from_pt - a, b, i = self.nearest_track(path, x, y, - look_ahead=self.look_ahead, look_behind=self.look_behind, + a, b, i = self.nearest_track(path, x, y, + look_ahead=self.look_ahead, look_behind=self.look_behind, from_pt=from_pt, num_pts=self.num_pts) - + if a and b: logging.info(f"nearest: ({a[0]}, {a[1]}) to ({x}, {y})") a_v = Vec3(a[0], 0., a[1]) @@ -426,13 +426,13 @@ def run(self, path, x, y, from_pt=None): cp = line.dir.cross(err.normalized()) if cp.y > 0.0 : sign = -1.0 - cte = err.mag() * sign + cte = err.mag() * sign else: logging.info(f"no nearest point to ({x},{y}))") return cte, i -class PID_Pilot(object): +class PID_Pilot(): def __init__( self, diff --git a/donkeycar/parts/pigpio_enc.py b/donkeycar/parts/pigpio_enc.py index 58b8b4032..71e36a157 100644 --- a/donkeycar/parts/pigpio_enc.py +++ b/donkeycar/parts/pigpio_enc.py @@ -8,7 +8,7 @@ # @deprecated("Deprecated in favor of donkeycar.parts.odometer.Odometer") -class OdomDist(object): +class OdomDist(): """ Take a tick input from odometry and compute the distance travelled """ @@ -34,14 +34,14 @@ def run(self, ticks, throttle): start_time = self.last_time end_time = time.time() self.last_time = end_time - + #calculate elapsed time and distance traveled seconds = end_time - start_time distance = new_ticks * self.m_per_tick if throttle < 0.0: distance = distance * -1.0 velocity = distance / seconds - + #update the odometer values self.meters += distance self.meters_per_second = velocity @@ -88,5 +88,3 @@ def shutdown(self): while True: time.sleep(0.1) e.run() - - diff --git a/donkeycar/parts/pins.py b/donkeycar/parts/pins.py index f9c4091c5..3a9f9ad20 100644 --- a/donkeycar/parts/pins.py +++ b/donkeycar/parts/pins.py @@ -28,6 +28,7 @@ from abc import ABC, abstractmethod from typing import Any, Callable import logging +import sys logger = logging.getLogger(__name__) @@ -394,13 +395,13 @@ def pwm_pin( # ----- RPi.GPIO/Jetson.GPIO implementations ----- # try: - import RPi.GPIO as GPIO + from RPi import GPIO # lookups to convert abstact api to GPIO values gpio_pin_edge = [None, GPIO.RISING, GPIO.FALLING, GPIO.BOTH] gpio_pin_pull = [None, GPIO.PUD_OFF, GPIO.PUD_DOWN, GPIO.PUD_UP] gpio_pin_scheme = {PinScheme.BOARD: GPIO.BOARD, PinScheme.BCM: GPIO.BCM} except ImportError: - logger.warn("RPi.GPIO was not imported.") + logger.warning("RPi.GPIO was not imported.") globals()["GPIO"] = None @@ -753,7 +754,7 @@ def duty_cycle(self, duty: float) -> None: pigpio_pin_edge = [None, pigpio.RISING_EDGE, pigpio.FALLING_EDGE, pigpio.EITHER_EDGE] pigpio_pin_pull = [None, pigpio.PUD_OFF, pigpio.PUD_DOWN, pigpio.PUD_UP] except ImportError: - logger.warn("pigpio was not imported.") + logger.warning("pigpio was not imported.") globals()["pigpio"] = None @@ -1055,7 +1056,7 @@ def on_input(): print('Stopping early.') except Exception as e: print(e) - exit(1) + sys.exit(1) finally: if pwm_out_pin is not None: pwm_out_pin.stop() diff --git a/donkeycar/parts/pytorch/ResNet18.py b/donkeycar/parts/pytorch/ResNet18.py index 2990466e2..2f4cb5522 100644 --- a/donkeycar/parts/pytorch/ResNet18.py +++ b/donkeycar/parts/pytorch/ResNet18.py @@ -1,11 +1,11 @@ import pytorch_lightning as pl -import torchvision.models as models +from torchvision import models import torchmetrics -import torch.nn as nn +from torch import nn import torch.nn.functional as F import torch import numpy as np -import torch.optim as optim +from torch import optim from donkeycar.parts.pytorch.torch_data import get_default_transform @@ -101,5 +101,5 @@ def run(self, img_arr: np.ndarray, other_arr: np.ndarray = None): # Convert from being normalized between [0, 1] to being between [-1, 1] result = result * 2 - 1 - print("ResNet18 result: {}".format(result)) + print(f"ResNet18 result: {result}") return result diff --git a/donkeycar/parts/pytorch/torch_train.py b/donkeycar/parts/pytorch/torch_train.py index 844b68ade..855129e21 100644 --- a/donkeycar/parts/pytorch/torch_train.py +++ b/donkeycar/parts/pytorch/torch_train.py @@ -55,6 +55,6 @@ def train(cfg, tub_paths, model_output_path, model_type, checkpoint_path=None): if is_torch_model: checkpoint_model_path = f'{os.path.splitext(output_path)[0]}.ckpt' trainer.save_checkpoint(checkpoint_model_path) - print("Saved final model to {}".format(checkpoint_model_path)) + print(f"Saved final model to {checkpoint_model_path}") return model.loss_history diff --git a/donkeycar/parts/pytorch/torch_utils.py b/donkeycar/parts/pytorch/torch_utils.py index b4b904a75..dfa4f7ee3 100644 --- a/donkeycar/parts/pytorch/torch_utils.py +++ b/donkeycar/parts/pytorch/torch_utils.py @@ -8,7 +8,7 @@ def get_model_by_type(model_type, cfg, checkpoint_path=None): ''' if model_type is None: model_type = cfg.DEFAULT_MODEL_TYPE - print("\"get_model_by_type\" model Type is: {}".format(model_type)) + print(f"\"get_model_by_type\" model Type is: {model_type}") input_shape = (cfg.BATCH_SIZE, cfg.IMAGE_DEPTH, cfg.IMAGE_H, cfg.IMAGE_W) @@ -25,7 +25,7 @@ def get_model_by_type(model_type, cfg, checkpoint_path=None): .format(model_type)) if checkpoint_path: - print("Loading model from checkpoint {}".format(checkpoint_path)) + print(f"Loading model from checkpoint {checkpoint_path}") model.load_from_checkpoint(checkpoint_path) return model diff --git a/donkeycar/parts/realsense2.py b/donkeycar/parts/realsense2.py index 3df5aed3f..0265747e3 100644 --- a/donkeycar/parts/realsense2.py +++ b/donkeycar/parts/realsense2.py @@ -10,7 +10,7 @@ import numpy as np import pyrealsense2 as rs -class RS_T265(object): +class RS_T265(): ''' The Intel Realsense T265 camera is a device which uses an imu, twin fisheye cameras, and an Movidius chip to do sensor fusion and emit a world space coordinate frame that @@ -22,7 +22,7 @@ def __init__(self, image_output=False, calib_filename=None): # This can be a bit much for USB2, but you can try it. Docs recommend USB3 connection for this. self.image_output = image_output - # When we have and encoder, this will be the last vel measured. + # When we have and encoder, this will be the last vel measured. self.enc_vel_ms = 0.0 self.wheel_odometer = None @@ -34,7 +34,7 @@ def __init__(self, image_output=False, calib_filename=None): profile = cfg.resolve(self.pipe) dev = profile.get_device() tm2 = dev.as_tm2() - + if self.image_output: #right now it's required for both streams to be enabled @@ -43,7 +43,7 @@ def __init__(self, image_output=False, calib_filename=None): if calib_filename is not None: pose_sensor = tm2.first_pose_sensor() - self.wheel_odometer = pose_sensor.as_wheel_odometer() + self.wheel_odometer = pose_sensor.as_wheel_odometer() # calibration to list of uint8 f = open(calib_filename) @@ -54,14 +54,14 @@ def __init__(self, image_output=False, calib_filename=None): # load/configure wheel odometer print("loading wheel config", calib_filename) - self.wheel_odometer.load_wheel_odometery_config(chars) + self.wheel_odometer.load_wheel_odometery_config(chars) # Start streaming with requested config self.pipe.start(cfg) self.running = True print("Warning: T265 needs a warmup period of a few seconds before it will emit tracking data.") - + zero_vec = (0.0, 0.0, 0.0) self.pos = zero_vec self.vel = zero_vec @@ -99,7 +99,7 @@ def poll(self): self.pos = data.translation self.vel = data.velocity self.acc = data.acceleration - logging.debug('realsense pos(%f, %f, %f)' % (self.pos.x, self.pos.y, self.pos.z)) + logging.debug(f'realsense pos({self.pos.x:f}, {self.pos.y:f}, {self.pos.z:f})') def update(self): diff --git a/donkeycar/parts/realsense435i.py b/donkeycar/parts/realsense435i.py index 3511d9972..44eedef37 100644 --- a/donkeycar/parts/realsense435i.py +++ b/donkeycar/parts/realsense435i.py @@ -30,7 +30,7 @@ HEIGHT = 240 CHANNELS = 3 -class RealSense435i(object): +class RealSense435i(): """ Donkeycar part for the Intel Realsense depth cameras D435 and D435i. The Intel Realsense D435i camera is a device which uses an imu, twin fisheye cameras, @@ -52,7 +52,7 @@ def __init__(self, width = WIDTH, height = HEIGHT, channels = CHANNELS, enable_r self.channels = channels self.resize = (width != WIDTH) or (height != height) or (channels != CHANNELS) if self.resize: - print("The output images will be resized from {} to {}. This requires opencv.".format((WIDTH, HEIGHT, CHANNELS), (self.width, self.height, self.channels))) + print(f"The output images will be resized from {WIDTH, HEIGHT, CHANNELS} to {self.width, self.height, self.channels}. This requires opencv.") # Configure streams self.imu_pipeline = None @@ -309,7 +309,7 @@ def shutdown(self): break if profile_frames > 0: if frame_count == profile_frames: - print("Aquired {} frames in {} seconds for {} fps".format(str(frame_count), str(frame_time - start_time), str(frame_count / (frame_time - start_time)))) + print(f"Aquired {str(frame_count)} frames in {str(frame_time - start_time)} seconds for {str(frame_count / (frame_time - start_time))} fps") break else: time.sleep(0.05) diff --git a/donkeycar/parts/robohat.py b/donkeycar/parts/robohat.py index 768787a7f..ebbe283a9 100755 --- a/donkeycar/parts/robohat.py +++ b/donkeycar/parts/robohat.py @@ -53,7 +53,7 @@ def __init__(self, cfg, debug=False): def shutdown(self): try: self.serial.close() - except: + except Exception: pass def read_serial(self): @@ -68,14 +68,14 @@ def read_serial(self): output = line.split(", ") if len(output) == 2: if self.SHOW_STEERING_VALUE: - print("MM1: steering={}".format(output[0])) + print(f"MM1: steering={output[0]}") if output[0].isnumeric() and output[1].isnumeric(): angle_pwm = float(output[0]) throttle_pwm = float(output[1]) if self.debug: - print("angle_pwm = {}, throttle_pwm= {}".format(angle_pwm, throttle_pwm)) + print(f"angle_pwm = {angle_pwm}, throttle_pwm= {throttle_pwm}") if throttle_pwm >= self.STOPPED_PWM: @@ -116,7 +116,7 @@ def read_serial(self): 0, 1) if self.debug: - print("angle = {}, throttle = {}".format(self.angle, self.throttle)) + print(f"angle = {self.angle}, throttle = {self.throttle}") if self.auto_record_on_throttle: was_recording = self.recording @@ -135,7 +135,7 @@ def update(self): while True: try: self.read_serial() - except: + except Exception: print("MM1: Error reading serial input!") break @@ -196,10 +196,10 @@ def __init__(self, cfg, debug=False): def trim_out_of_bound_value(self, value): if value > 1: - print("MM1: Warning, value out of bound. Value = {}".format(value)) + print(f"MM1: Warning, value out of bound. Value = {value}") return 1.0 elif value < -1: - print("MM1: Warning, value out of bound. Value = {}".format(value)) + print(f"MM1: Warning, value out of bound. Value = {value}") return -1.0 else: return value @@ -238,13 +238,10 @@ def set_pulse(self, steering, throttle): except OSError as err: print( - "Unexpected issue setting PWM (check wires to motor board): {0}".format(err)) + f"Unexpected issue setting PWM (check wires to motor board): {err}") def is_valid_pwm_value(self, value): - if 1000 <= value <= 2000: - return True - else: - return False + return 1000 <= value <= 2000 def write_pwm(self, steering, throttle): self.pwm.write(b"%d, %d\r" % (steering, throttle)) @@ -255,5 +252,5 @@ def run(self, steering, throttle): def shutdown(self): try: self.serial.close() - except: + except Exception: pass diff --git a/donkeycar/parts/ros.py b/donkeycar/parts/ros.py index ab577e421..28c5007cf 100755 --- a/donkeycar/parts/ros.py +++ b/donkeycar/parts/ros.py @@ -8,7 +8,7 @@ https://discourse.ros.org/t/should-we-warn-new-users-about-difficulties-with-python-3-and-alternative-python-interpreters/3874/3 ''' -class RosPubisher(object): +class RosPubisher(): ''' A ROS node to pubish to a data stream ''' @@ -24,9 +24,9 @@ def run(self, data): if data != self.data and not rospy.is_shutdown(): self.data = data self.pub.publish(data) - -class RosSubscriber(object): + +class RosSubscriber(): ''' A ROS node to subscribe to a data stream ''' @@ -34,11 +34,10 @@ class RosSubscriber(object): def __init__(self, node_name, channel_name, stream_type=String, anonymous=True): self.data = "" rospy.init_node(node_name, anonymous=anonymous) - self.pub = rospy.Subscriber(channel_name, stream_type, self.on_data_recv) + self.pub = rospy.Subscriber(channel_name, stream_type, self.on_data_recv) def on_data_recv(self, data): self.data = data.data def run(self): return self.data - diff --git a/donkeycar/parts/salient.py b/donkeycar/parts/salient.py index 31a01d85c..9f233bb28 100644 --- a/donkeycar/parts/salient.py +++ b/donkeycar/parts/salient.py @@ -41,20 +41,20 @@ def init_salient(self, model): for layer_num in ('1', '2', '3', '4', '5'): self.convolution_part.get_layer('conv' + layer_num).set_weights(model.get_layer('conv2d_' + layer_num).get_weights()) - + self.inp = self.convolution_part.input # input placeholder self.outputs = [layer.output for layer in self.convolution_part.layers[1:]] # all layer outputs self.functor = K.function([self.inp], self.outputs) kernel_3x3 = tf.constant(np.array([ - [[[1]], [[1]], [[1]]], - [[[1]], [[1]], [[1]]], + [[[1]], [[1]], [[1]]], + [[[1]], [[1]], [[1]]], [[[1]], [[1]], [[1]]] ]), tf.float32) kernel_5x5 = tf.constant(np.array([ - [[[1]], [[1]], [[1]], [[1]], [[1]]], - [[[1]], [[1]], [[1]], [[1]], [[1]]], + [[[1]], [[1]], [[1]], [[1]], [[1]]], + [[[1]], [[1]], [[1]], [[1]], [[1]]], [[[1]], [[1]], [[1]], [[1]], [[1]]], [[[1]], [[1]], [[1]], [[1]], [[1]]], [[[1]], [[1]], [[1]], [[1]], [[1]]] @@ -64,10 +64,10 @@ def init_salient(self, model): self.layers_strides = {5: [1, 1, 1, 1], 4: [1, 2, 2, 1], 3: [1, 2, 2, 1], 2: [1, 2, 2, 1], 1: [1, 2, 2, 1]} - + def compute_visualisation_mask(self, img): #from https://github.com/ermolenkodev/keras-salient-object-visualisation - + activations = self.functor([np.array([img])]) activations = [np.reshape(img, (1, img.shape[0], img.shape[1], img.shape[2]))] + activations upscaled_activation = np.ones((3, 6)) @@ -80,8 +80,8 @@ def compute_visualisation_mask(self, img): ) conv = tf.nn.conv2d_transpose( x, self.layers_kernels[layer], - output_shape=(1,output_shape[0],output_shape[1], 1), - strides=self.layers_strides[layer], + output_shape=(1,output_shape[0],output_shape[1], 1), + strides=self.layers_strides[layer], padding='VALID' ) with tf.Session() as session: @@ -103,4 +103,3 @@ def draw_salient(self, img): def shutdown(self): pass - diff --git a/donkeycar/parts/serial_port.py b/donkeycar/parts/serial_port.py index cb9b84bf6..12e76a125 100644 --- a/donkeycar/parts/serial_port.py +++ b/donkeycar/parts/serial_port.py @@ -4,7 +4,7 @@ import serial.tools.list_ports import threading import time -import donkeycar.utilities.dk_platform as dk_platform +from donkeycar.utilities import dk_platform logger = logging.getLogger(__name__) @@ -92,7 +92,7 @@ def readBytes(self, count:int=0) -> Tuple[bool, bytes]: input = self.ser.read(count) return (waiting, input) except (serial.serialutil.SerialException, TypeError): - logger.warn("failed reading bytes from serial port") + logger.warning("failed reading bytes from serial port") return (False, b'') def read(self, count:int=0) -> Tuple[bool, str]: @@ -135,11 +135,11 @@ def readln(self) -> Tuple[bool, str]: input = buffer.decode(self.charset) return (waiting, input) except (serial.serialutil.SerialException, TypeError): - logger.warn("failed reading line from serial port") + logger.warning("failed reading line from serial port") return (False, "") except UnicodeDecodeError: # the first read often includes mis-framed garbase - logger.warn("failed decoding unicode line from serial port") + logger.warning("failed decoding unicode line from serial port") return (False, "") def writeBytes(self, value:bytes): @@ -148,9 +148,9 @@ def writeBytes(self, value:bytes): """ if self.ser is not None and self.ser.is_open: try: - self.ser.write(value) + self.ser.write(value) except (serial.serialutil.SerialException, TypeError): - logger.warn("Can't write to serial port") + logger.warning("Can't write to serial port") def write(self, value:str): """ @@ -327,4 +327,3 @@ def read_lines(): line_reader.shutdown() if update_thread is not None: update_thread.join() # wait for thread to end - diff --git a/donkeycar/parts/simulation.py b/donkeycar/parts/simulation.py index 782bf9248..94e9c0a84 100755 --- a/donkeycar/parts/simulation.py +++ b/donkeycar/parts/simulation.py @@ -70,4 +70,4 @@ def run(self, x, y, box_size=None, color=None): frame = np.zeros(shape=self.resolution + (3,)) frame[y - radius: y + radius, x - radius: x + radius, :] = color - return frame \ No newline at end of file + return frame diff --git a/donkeycar/parts/sombrero.py b/donkeycar/parts/sombrero.py index 5c043eeff..cdc33fd77 100755 --- a/donkeycar/parts/sombrero.py +++ b/donkeycar/parts/sombrero.py @@ -14,7 +14,7 @@ def __init__(self): GPIO.setup(37, GPIO.OUT) GPIO.output(37, GPIO.LOW) print("sombrero enabled") - except: + except Exception: pass def __del__(self): @@ -23,5 +23,5 @@ def __del__(self): GPIO.cleanup() print("sombrero disabled") - except: + except Exception: pass diff --git a/donkeycar/parts/tachometer.py b/donkeycar/parts/tachometer.py index 26d7b02fa..d4adca770 100644 --- a/donkeycar/parts/tachometer.py +++ b/donkeycar/parts/tachometer.py @@ -2,6 +2,7 @@ import logging import threading import time +import sys from typing import Tuple from donkeycar.utils import is_number_type @@ -135,7 +136,7 @@ def __init__(self, serial_port:SerialPort=None, debug=False): self.lock = threading.Lock() self.buffered_ticks = [] self.running = False - + def start_ticks(self): self.ser.start() self.ser.writeln('r') # restart the encoder to zero @@ -162,7 +163,7 @@ def poll_ticks(self, direction:int): return: updated encoder ticks """ # - # If there are characters waiting, + # If there are characters waiting, # then read from the serial port. # Read all lines and use the last one # because it has the most recent reading @@ -174,7 +175,7 @@ def poll_ticks(self, direction:int): # # queue up another reading by sending the "p" command to the Arduino # - self.ser.writeln('p') + self.ser.writeln('p') # # if we got data, update the ticks @@ -183,12 +184,12 @@ def poll_ticks(self, direction:int): # data for encoders is separated by semicolon # and ticks and time for single encoder # is comma separated. - # + # # "ticks,ticksMs;ticks,ticksMs" # if input != '': try: - # + # # split separate encoder outputs # "ticks,time;ticks,time" -> ["ticks,time", "ticks,time"] # @@ -310,7 +311,7 @@ def __init__(self, gpio_pin: InputPin, debounce_ns:int=0, debug=False): self.debounce_ns:int = debounce_ns self.debounce_time:int = 0 if self.debounce_ns > 0: - logger.warn("GpioEncoder debounce_ns will be ignored.") + logger.warning("GpioEncoder debounce_ns will be ignored.") self.lock = threading.Lock() def _cb(self): @@ -331,13 +332,13 @@ def _cb(self): self._cb_counter = 0 finally: self.lock.release() - + def start_ticks(self): # configure GPIO pin self.pin.start(on_input=lambda: self._cb(), edge=PinEdge.RISING) logger.info(f'GpioEncoder on InputPin "RPI_GPIO.{self.pin.pin_scheme_str}.{self.pin.pin_number}" started.') - def poll_ticks(self, direction:int): + def poll_ticks(self, direction:int): """ read the encoder ticks direction: 1 if forward, -1 if reverse, 0 if stopped. @@ -502,7 +503,7 @@ def poll(self, throttle, timestamp): self.encoder.poll_ticks(self.direction) self.ticks = self.encoder.get_ticks() if self.debug and self.ticks != lastTicks: - logger.info("tachometer: t = {}, r = {}, ts = {}".format(self.ticks, self.ticks / self.ticks_per_revolution, timestamp)) + logger.info(f"tachometer: t = {self.ticks}, r = {self.ticks / self.ticks_per_revolution}, ts = {timestamp}") def update(self): while(self.running): @@ -607,13 +608,13 @@ def run_threaded(self, distance:float, timestamp=None): help = "Number of readings per second") parser.add_argument("-n", "--number", type=int, default=40, help = "Number of readings to collect") - parser.add_argument("-ppr", "--pulses-per-revolution", type=int, required=True, + parser.add_argument("-ppr", "--pulses-per-revolution", type=int, required=True, help="Pulses per revolution of output shaft") - parser.add_argument("-d", "--direction-mode", type=int, default=1, + parser.add_argument("-d", "--direction-mode", type=int, default=1, help="1=FORWARD_ONLY, 2=FORWARD_REVERSE, 3=FORWARD_REVERSE_STOP") parser.add_argument("-s", "--serial-port", type=str, default=None, help="serial-port to open, like '/dev/ttyACM0'") - parser.add_argument("-b", "--baud-rate", type=int, default=115200, + parser.add_argument("-b", "--baud-rate", type=int, default=115200, help="Serial port baud rate") parser.add_argument("-e", "--encoder-index", type=int, default=0, help="Serial encoder index (0 based) if more than one encoder") @@ -626,20 +627,20 @@ def run_threaded(self, distance:float, timestamp=None): # Read arguments from command line args = parser.parse_args() - + help = [] if args.rate < 1: help.append("-r/--rate: must be >= 1.") - + if args.number < 1: help.append("-n/--number: must be >= 1.") - + if args.direction_mode < 1 and args.direction_mode > 3: help.append("-d/--direction-mode must be 1, 2, or") if args.pulses_per_revolution <= 0: help.append("-ppr/--pulses-per-revolution must be > 0") - + if args.serial_port is None and args.pin is None: help.append("either -s/--serial_port or -p/--pin must be passed") @@ -648,26 +649,26 @@ def run_threaded(self, distance:float, timestamp=None): if args.serial_port is not None and len(args.serial_port) == 0: help.append("-s/--serial-port not be empty if passed") - + if args.baud_rate <= 0: help.append("-b/--baud-rate must be > 0") - + if args.pin is not None and args.pin == "": help.append("-p/--pin must be non-empty if passed") if args.debounce_ns < 0: help.append("-dbc/--debounce-ns must be greater than zero") - + if len(help) > 0: parser.print_help() for h in help: print(" " + h) sys.exit(1) - + update_thread = None serial_port = None tachometer = None - + try: scan_count = 0 seconds_per_scan = 1.0 / args.rate @@ -680,17 +681,17 @@ def run_threaded(self, distance:float, timestamp=None): serial_port = SerialPort(args.serial_port, args.baud_rate) tachometer = Tachometer( encoder=EncoderChannel(SerialEncoder(serial_port=serial_port, debug=args.debug), args.encoder_index), - ticks_per_revolution=args.pulses_per_revolution, - direction_mode=args.direction_mode, - poll_delay_secs=1/(args.rate*2), + ticks_per_revolution=args.pulses_per_revolution, + direction_mode=args.direction_mode, + poll_delay_secs=1/(args.rate*2), debug=args.debug) if args.pin is not None: tachometer = Tachometer( encoder=GpioEncoder(gpio_pin=input_pin_by_id(args.pin), debounce_ns=args.debounce_ns, debug=args.debug), - ticks_per_revolution=args.pulses_per_revolution, + ticks_per_revolution=args.pulses_per_revolution, direction_mode=args.direction_mode, debug=args.debug) - + # # start the threaded part # and a threaded window to show plot @@ -698,7 +699,7 @@ def run_threaded(self, distance:float, timestamp=None): if args.threaded: update_thread = Thread(target=tachometer.update, args=()) update_thread.start() - + while scan_count < args.number: start_time = time.time() @@ -712,7 +713,7 @@ def run_threaded(self, distance:float, timestamp=None): measurements = tachometer.run() print(measurements) - + # yield time to background threads sleep_time = seconds_per_scan - (time.time() - start_time) if sleep_time > 0.0: @@ -724,7 +725,7 @@ def run_threaded(self, distance:float, timestamp=None): print('Stopping early.') except Exception as e: print(e) - exit(1) + sys.exit(1) finally: if tachometer is not None: tachometer.shutdown() diff --git a/donkeycar/parts/teensy.py b/donkeycar/parts/teensy.py index aded31fb4..5ca70fced 100644 --- a/donkeycar/parts/teensy.py +++ b/donkeycar/parts/teensy.py @@ -82,4 +82,3 @@ def shutdown(self): self.on = False print('stopping TeensyRCin') time.sleep(.5) - diff --git a/donkeycar/parts/telemetry.py b/donkeycar/parts/telemetry.py index f6a32aaca..a2393874c 100644 --- a/donkeycar/parts/telemetry.py +++ b/donkeycar/parts/telemetry.py @@ -50,14 +50,14 @@ def __init__(self, cfg): logger.addHandler(self) def add_step_inputs(self, inputs, types): - + # Add inputs if supported and not yet registered for ind in range(0, len(inputs or [])): if types[ind] in ['float', 'str', 'int'] and inputs[ind] not in self._step_inputs: self._step_inputs.append(inputs[ind]) self._step_types.append(types[ind]) - - return self._step_inputs, self._step_types + + return self._step_inputs, self._step_types @staticmethod def filter_supported_metrics(inputs, types): @@ -104,7 +104,7 @@ def publish(self): if not packet: return - + if self._use_json_format: packet = [{'ts': k, 'values': v} for k, v in packet.items()] payload = json.dumps(packet) @@ -119,7 +119,7 @@ def publish(self): for k, v in last_sample.items(): if k in self._step_inputs: topic = f'{self._topic}/{k}' - + try: # Convert unsupported numpy types to python standard if isinstance(v, np.generic): @@ -149,7 +149,7 @@ def run(self, *args): pairs them with their inputs keys and saves them to disk. """ assert len(self._step_inputs) == len(args) - + # Add to queue record = dict(zip(self._step_inputs, args)) self.report(record) diff --git a/donkeycar/parts/tfmini.py b/donkeycar/parts/tfmini.py index aeed62368..73f283cd0 100644 --- a/donkeycar/parts/tfmini.py +++ b/donkeycar/parts/tfmini.py @@ -45,10 +45,10 @@ def poll(self): try: count = self.ser.in_waiting if count > 8: - recv = self.ser.read(9) - self.ser.reset_input_buffer() + recv = self.ser.read(9) + self.ser.reset_input_buffer() - if recv[0] == 0x59 and recv[1] == 0x59: + if recv[0] == 0x59 and recv[1] == 0x59: dist = recv[2] + recv[3] * 256 strength = recv[4] + recv[5] * 256 diff --git a/donkeycar/parts/throttle_filter.py b/donkeycar/parts/throttle_filter.py index f4fe2819c..7d01b2136 100644 --- a/donkeycar/parts/throttle_filter.py +++ b/donkeycar/parts/throttle_filter.py @@ -1,5 +1,5 @@ -class ThrottleFilter(object): +class ThrottleFilter(): ''' allow reverse to trigger automatic reverse throttle ''' diff --git a/donkeycar/parts/transform.py b/donkeycar/parts/transform.py index 3f0442ca7..30bc19513 100644 --- a/donkeycar/parts/transform.py +++ b/donkeycar/parts/transform.py @@ -11,10 +11,10 @@ def __init__(self, f): Accepts the function to use. """ self.f = f - + def run(self, *args, **kwargs): return self.f(*args, **kwargs) - + def shutdown(self): return @@ -140,7 +140,7 @@ def twiddle(evaluator, tol=0.001, params=3, error_cmp=None, initial_guess=None): def _error_cmp(a, b): # Returns true if a is closer to zero than b. return abs(a) < abs(b) - + if error_cmp is None: error_cmp = _error_cmp @@ -155,11 +155,11 @@ def _error_cmp(a, b): steps += 1 print('steps:', steps, 'tol:', tol, 'best error:', best_err) for i, _ in enumerate(p): - + # first try to increase param p[i] += dp[i] err = evaluator(*p) - + if error_cmp(err, best_err): # Increasing param reduced error, so record and continue to increase dp range. best_err = err @@ -168,15 +168,15 @@ def _error_cmp(a, b): # Otherwise, increased error, so undo and try decreasing dp p[i] -= 2.*dp[i] err = evaluator(*p) - + if error_cmp(err, best_err): # Decreasing param reduced error, so record and continue to increase dp range. best_err = err dp[i] *= 1.1 - + else: # Otherwise, reset param and reduce dp range. p[i] += dp[i] dp[i] *= 0.9 - + return p diff --git a/donkeycar/parts/tub_v2.py b/donkeycar/parts/tub_v2.py index 07c2faefc..83138826a 100644 --- a/donkeycar/parts/tub_v2.py +++ b/donkeycar/parts/tub_v2.py @@ -10,7 +10,7 @@ from donkeycar.parts.datastore_v2 import Manifest, ManifestIterator -class Tub(object): +class Tub(): """ A datastore to store sensor data in a key, value format. \n Accepts str, int, float, image_array, image, and array data types. @@ -112,7 +112,7 @@ def _image_file_name(cls, index, key, extension='.jpg'): return name -class TubWriter(object): +class TubWriter(): """ A Donkey part, which can write records to the datastore. """ @@ -169,4 +169,4 @@ def run(self, is_delete): self._active_loop = True else: # trigger released, reset active loop - self._active_loop = False \ No newline at end of file + self._active_loop = False diff --git a/donkeycar/parts/velocity.py b/donkeycar/parts/velocity.py index 7304aec59..ca76235ca 100644 --- a/donkeycar/parts/velocity.py +++ b/donkeycar/parts/velocity.py @@ -22,8 +22,8 @@ def run(self, speed:float) -> float: if speed >= self.max_speed: return s * 1.0 return s * map_frange( - speed, - self.min_speed, self.max_speed, + speed, + self.min_speed, self.max_speed, self.min_normal_speed, 1.0) def shutdown(self): @@ -47,7 +47,7 @@ def run(self, speed:float) -> float: if speed >= 1.0: return s * 1.0 return s * map_frange( - speed, + speed, self.min_normal_speed, 1.0, self.min_speed, self.max_speed) @@ -74,10 +74,10 @@ def __init__(self, min_speed:float, max_speed:float, throttle_step:float=1/255, self.max_speed = max_speed self.min_throttle = min_throttle self.step_size = throttle_step - + def run(self, throttle:float, speed:float, target_speed:float) -> float: """ - Given current throttle and speed and a target speed, + Given current throttle and speed and a target speed, calculate a new throttle to attain target speed @param throttle is current throttle (-1 to 1) @param speed is current speed where reverse speeds are negative @@ -95,7 +95,7 @@ def run(self, throttle:float, speed:float, target_speed:float) -> float: target_speed = abs(target_speed) speed = abs(speed) - # + # # treat speed below minimum as zero # if target_speed < self.min_speed: @@ -103,18 +103,18 @@ def run(self, throttle:float, speed:float, target_speed:float) -> float: # # when changing direction or starting from stopped, - # calculate a feed-forward throttle estimate + # calculate a feed-forward throttle estimate # so we jump into a working range quickly # if direction != target_direction: # if we are going too fast to just reverse, then slow down first if speed > self.min_speed: return 0 - + # calculate first estimate of throttle to achieve target speed return target_direction * map_frange(target_speed, self.min_speed, self.max_speed, self.min_throttle, 1.0) - # + # # modify throttle # if speed > target_speed: diff --git a/donkeycar/parts/voice_control/alexa.py b/donkeycar/parts/voice_control/alexa.py index a243641e8..95aa0efcf 100644 --- a/donkeycar/parts/voice_control/alexa.py +++ b/donkeycar/parts/voice_control/alexa.py @@ -2,7 +2,7 @@ import requests -class AlexaController(object): +class AlexaController(): ''' Accept simple command from alexa. For the command supported, please refer to the README.md @@ -20,10 +20,10 @@ def __init__(self, ctr, cfg, debug=False): raise Exception("Please set cfg.ALEXA_DEVICE_CODE in myconfig.py") def log(self, msg): - print("Voice control: {}".format(msg)) + print(f"Voice control: {msg}") def get_command(self): - url = "{}/{}".format(self.API_ENDPOINT, 'command') + url = f"{self.API_ENDPOINT}/command" params = { 'deviceCode': self.cfg.ALEXA_DEVICE_CODE @@ -50,9 +50,9 @@ def update(self): while (self.running): command = self.get_command() if self.debug: - self.log("Command = {}".format(command)) + self.log(f"Command = {command}") elif command is not None: - self.log("Command = {}".format(command)) + self.log(f"Command = {command}") if command == "autopilot": self.ctr.mode = "local" diff --git a/donkeycar/parts/web_controller/web.py b/donkeycar/parts/web_controller/web.py index 7a8eef072..7eec8aae9 100644 --- a/donkeycar/parts/web_controller/web.py +++ b/donkeycar/parts/web_controller/web.py @@ -141,8 +141,7 @@ def __init__(self, port=8887, mode='user'): settings = {'debug': True} super().__init__(handlers, **settings) - print("... you can now go to {}.local:{} to drive " - "your car.".format(gethostname(), port)) + print(f"... you can now go to {gethostname()}.local:{port} to drive your car.") def update(self): ''' Start the tornado webserver. ''' @@ -159,7 +158,7 @@ def update_wsclients(self, data): logger.debug(f"Updating web client: {data_str}") wsclient.write_message(data_str) except Exception as e: - logger.warn("Error writing websocket message", exc_info=e) + logger.warning("Error writing websocket message", exc_info=e) pass def run_threaded(self, img_arr=None, num_records=0, mode=None, recording=None): @@ -187,9 +186,9 @@ def run_threaded(self, img_arr=None, num_records=0, mode=None, recording=None): self.recording = recording changes["recording"] = self.recording if self.recording_latch is not None: - self.recording = self.recording_latch; - self.recording_latch = None; - changes["recording"] = self.recording; + self.recording = self.recording_latch + self.recording_latch = None + changes["recording"] = self.recording # Send record count to websocket clients if (self.num_records is not None and self.recording is True): @@ -340,9 +339,9 @@ def on_message(self, message): elif self.application.drive_train_type == "MM1": if ('MM1_STEERING_MID' in config) and (config['MM1_STEERING_MID'] != 0): - self.application.drive_train.STEERING_MID = config['MM1_STEERING_MID'] + self.application.drive_train.STEERING_MID = config['MM1_STEERING_MID'] if ('MM1_MAX_FORWARD' in config) and (config['MM1_MAX_FORWARD'] != 0): - self.application.drive_train.MAX_FORWARD = config['MM1_MAX_FORWARD'] + self.application.drive_train.MAX_FORWARD = config['MM1_MAX_FORWARD'] if ('MM1_MAX_REVERSE' in config) and (config['MM1_MAX_REVERSE'] != 0): self.application.drive_train.MAX_REVERSE = config['MM1_MAX_REVERSE'] @@ -379,7 +378,7 @@ async def get(self): self.write(my_boundary) self.write("Content-type: image/jpeg\r\n") - self.write("Content-length: %s\r\n\r\n" % len(img)) + self.write(f"Content-length: {len(img)}\r\n\r\n") self.write(img) served_image_timestamp = time.time() try: @@ -438,5 +437,3 @@ def run(self, img_arr=None): def shutdown(self): pass - - diff --git a/donkeycar/pipeline/__init__.py b/donkeycar/pipeline/__init__.py index 9509025d7..297586d60 100644 --- a/donkeycar/pipeline/__init__.py +++ b/donkeycar/pipeline/__init__.py @@ -1 +1 @@ -# The new donkey car training pipeline. \ No newline at end of file +# The new donkey car training pipeline. diff --git a/donkeycar/pipeline/augmentations.py b/donkeycar/pipeline/augmentations.py index b44e4e5fe..df56e45d0 100644 --- a/donkeycar/pipeline/augmentations.py +++ b/donkeycar/pipeline/augmentations.py @@ -42,4 +42,3 @@ def create(cls, aug_type: str, config: Config, prob, always) -> \ def run(self, img_arr): aug_img_arr = self.augmentations(image=img_arr)["image"] return aug_img_arr - diff --git a/donkeycar/pipeline/training.py b/donkeycar/pipeline/training.py index 5dd2714ea..c11d62854 100644 --- a/donkeycar/pipeline/training.py +++ b/donkeycar/pipeline/training.py @@ -19,7 +19,7 @@ import numpy as np -class BatchSequence(object): +class BatchSequence(): """ The idea is to have a shallow sequence with types that can hydrate themselves to np.ndarray initially and later into the types required by @@ -187,4 +187,4 @@ def train(cfg: Config, tub_paths: str, model: str = None, database.add_entry(database_entry) database.write() - return history \ No newline at end of file + return history diff --git a/donkeycar/pipeline/types.py b/donkeycar/pipeline/types.py index 6885918b1..67f8f02c9 100644 --- a/donkeycar/pipeline/types.py +++ b/donkeycar/pipeline/types.py @@ -33,7 +33,7 @@ ) -class TubRecord(object): +class TubRecord(): def __init__(self, config: Config, base_path: str, underlying: TubRecordDict) -> None: self.config = config @@ -75,7 +75,7 @@ def __repr__(self) -> str: return repr(self.underlying) -class TubDataset(object): +class TubDataset(): """ Loads the dataset and creates a TubRecord list (or list of lists). """ @@ -142,5 +142,3 @@ def __iter__(self) -> Iterator[List[TubRecord]]: break if len(seq) == self.seq_length: yield seq - - diff --git a/donkeycar/templates/basic.py b/donkeycar/templates/basic.py index 3c0bdc9cd..5d9feb63e 100755 --- a/donkeycar/templates/basic.py +++ b/donkeycar/templates/basic.py @@ -65,7 +65,7 @@ def drive(cfg, model_path=None, model_type=None): # add camera inputs = [] if cfg.DONKEY_GYM: - from donkeycar.parts.dgym import DonkeyGymEnv + from donkeycar.parts.dgym import DonkeyGymEnv cam = DonkeyGymEnv(cfg.DONKEY_SIM_PATH, host=cfg.SIM_HOST, env_name=cfg.DONKEY_GYM_ENV_NAME, conf=cfg.GYM_CONF, delay=cfg.SIM_ARTIFICIAL_LATENCY) @@ -100,7 +100,7 @@ def drive(cfg, model_path=None, model_type=None): from donkeycar.parts.camera import ImageListCamera cam = ImageListCamera(path_mask=cfg.PATH_MASK) else: - raise (Exception("Unkown camera type: %s" % cfg.CAMERA_TYPE)) + raise (Exception(f"Unkown camera type: {cfg.CAMERA_TYPE}")) car.add(cam, inputs=inputs, outputs=['cam/image_array'], threaded=True) diff --git a/donkeycar/templates/cfg_complete.py b/donkeycar/templates/cfg_complete.py index 108cecaec..2ae79c69f 100644 --- a/donkeycar/templates/cfg_complete.py +++ b/donkeycar/templates/cfg_complete.py @@ -32,7 +32,7 @@ CAMERA_FRAMERATE = DRIVE_LOOP_HZ CAMERA_VFLIP = False CAMERA_HFLIP = False -CAMERA_INDEX = 0 # used for 'WEBCAM' and 'CVCAM' when there is more than one camera connected +CAMERA_INDEX = 0 # used for 'WEBCAM' and 'CVCAM' when there is more than one camera connected # For CSIC camera - If the camera is mounted in a rotated position, changing the below parameter will correct the output frame orientation CSIC_CAM_GSTREAMER_FLIP_PARM = 0 # (0 => none , 4 => Flip horizontally, 6 => Flip vertically) BGR2RGB = False # true to convert from BRG format to RGB format; requires opencv @@ -120,14 +120,14 @@ # - configures a steering servo and an HBridge in 2pin mode (2 pwm pins) # - Servo takes a standard servo PWM pulse between 1 millisecond (fully reverse) # and 2 milliseconds (full forward) with 1.5ms being neutral. -# - the motor is controlled by two pwm pins, -# one for forward and one for backward (reverse). +# - the motor is controlled by two pwm pins, +# one for forward and one for backward (reverse). # - the pwm pin produces a duty cycle from 0 (completely LOW) # to 1 (100% completely high), which is proportional to the # amount of power delivered to the motor. # - in forward mode, the reverse pwm is 0 duty_cycle, # in backward mode, the forward pwm is 0 duty cycle. -# - both pwms are 0 duty cycle (LOW) to 'detach' motor and +# - both pwms are 0 duty cycle (LOW) to 'detach' motor and # and glide to a stop. # - both pwms are full duty cycle (100% HIGH) to brake # @@ -140,7 +140,7 @@ # - must use BCM (broadcom) pin numbering scheme # - for example, "PIGPIO.BCM.13" # - use PCA9685 for PCA9685 pin output -# - include colon separated I2C channel and address +# - include colon separated I2C channel and address # - for example "PCA9685.1:40.13" # - RPI_GPIO, PIGPIO and PCA9685 can be mixed arbitrarily, # although it is discouraged to mix RPI_GPIO and PIGPIO. @@ -160,8 +160,8 @@ # - configures a steering servo and an HBridge in 3pin mode (2 ttl pins, 1 pwm pin) # - Servo takes a standard servo PWM pulse between 1 millisecond (fully reverse) # and 2 milliseconds (full forward) with 1.5ms being neutral. -# - the motor is controlled by three pins, -# one ttl output for forward, one ttl output +# - the motor is controlled by three pins, +# one ttl output for forward, one ttl output # for backward (reverse) enable and one pwm pin # for motor power. # - the pwm pin produces a duty cycle from 0 (completely LOW) @@ -169,9 +169,9 @@ # amount of power delivered to the motor. # - in forward mode, the forward pin is HIGH and the # backward pin is LOW, -# - in backward mode, the forward pin is LOW and the +# - in backward mode, the forward pin is LOW and the # backward pin is HIGH. -# - both forward and backward pins are LOW to 'detach' motor +# - both forward and backward pins are LOW to 'detach' motor # and glide to a stop. # - both forward and backward pins are HIGH to brake # @@ -184,7 +184,7 @@ # - must use BCM (broadcom) pin numbering scheme # - for example, "PIGPIO.BCM.13" # - use PCA9685 for PCA9685 pin output -# - include colon separated I2C channel and address +# - include colon separated I2C channel and address # - for example "PCA9685.1:40.13" # - RPI_GPIO, PIGPIO and PCA9685 can be mixed arbitrarily, # although it is discouraged to mix RPI_GPIO and PIGPIO. @@ -237,9 +237,9 @@ # # DC_STEER_THROTTLE with one motor as steering, one as drive # - uses L298N type motor controller in two pin wiring -# scheme utilizing two pwm pins per motor; one for +# scheme utilizing two pwm pins per motor; one for # forward(or right) and one for reverse (or left) -# +# # GPIO pin configuration for the DRIVE_TRAIN_TYPE=DC_STEER_THROTTLE # - use RPI_GPIO for RPi/Nano header pin output # - use BOARD for board pin numbering @@ -249,7 +249,7 @@ # - must use BCM (broadcom) pin numbering scheme # - for example, "PIGPIO.BCM.13" # - use PCA9685 for PCA9685 pin output -# - include colon separated I2C channel and address +# - include colon separated I2C channel and address # - for example "PCA9685.1:40.13" # - RPI_GPIO, PIGPIO and PCA9685 can be mixed arbitrarily, # although it is discouraged to mix RPI_GPIO and PIGPIO. @@ -265,14 +265,14 @@ # DC_TWO_WHEEL pin configuration # - configures L298N_HBridge_2pin driver # - two wheels as differential drive, left and right. -# - each wheel is controlled by two pwm pins, -# one for forward and one for backward (reverse). +# - each wheel is controlled by two pwm pins, +# one for forward and one for backward (reverse). # - each pwm pin produces a duty cycle from 0 (completely LOW) # to 1 (100% completely high), which is proportional to the # amount of power delivered to the motor. # - in forward mode, the reverse pwm is 0 duty_cycle, # in backward mode, the forward pwm is 0 duty cycle. -# - both pwms are 0 duty cycle (LOW) to 'detach' motor and +# - both pwms are 0 duty cycle (LOW) to 'detach' motor and # and glide to a stop. # - both pwms are full duty cycle (100% HIGH) to brake # @@ -285,7 +285,7 @@ # - must use BCM (broadcom) pin numbering scheme # - for example, "PIGPIO.BCM.13" # - use PCA9685 for PCA9685 pin output -# - include colon separated I2C channel and address +# - include colon separated I2C channel and address # - for example "PCA9685.1:40.13" # - RPI_GPIO, PIGPIO and PCA9685 can be mixed arbitrarily, # although it is discouraged to mix RPI_GPIO and PIGPIO. @@ -301,8 +301,8 @@ # DC_TWO_WHEEL_L298N pin configuration # - configures L298N_HBridge_3pin driver # - two wheels as differential drive, left and right. -# - each wheel is controlled by three pins, -# one ttl output for forward, one ttl output +# - each wheel is controlled by three pins, +# one ttl output for forward, one ttl output # for backward (reverse) enable and one pwm pin # for motor power. # - the pwm pin produces a duty cycle from 0 (completely LOW) @@ -310,9 +310,9 @@ # amount of power delivered to the motor. # - in forward mode, the forward pin is HIGH and the # backward pin is LOW, -# - in backward mode, the forward pin is LOW and the +# - in backward mode, the forward pin is LOW and the # backward pin is HIGH. -# - both forward and backward pins are LOW to 'detach' motor +# - both forward and backward pins are LOW to 'detach' motor # and glide to a stop. # - both forward and backward pins are HIGH to brake # @@ -325,7 +325,7 @@ # - must use BCM (broadcom) pin numbering scheme # - for example, "PIGPIO.BCM.13" # - use PCA9685 for PCA9685 pin output -# - include colon separated I2C channel and address +# - include colon separated I2C channel and address # - for example "PCA9685.1:40.13" # - RPI_GPIO, PIGPIO and PCA9685 can be mixed arbitrarily, # although it is discouraged to mix RPI_GPIO and PIGPIO. @@ -341,8 +341,8 @@ } #ODOMETRY -HAVE_ODOM = False # Do you have an odometer/encoder -ENCODER_TYPE = 'GPIO' # What kind of encoder? GPIO|Arduino|Astar +HAVE_ODOM = False # Do you have an odometer/encoder +ENCODER_TYPE = 'GPIO' # What kind of encoder? GPIO|Arduino|Astar MM_PER_TICK = 12.7625 # How much travel with a single tick, in mm. Roll you car a meter and divide total ticks measured by 1,000 ODOM_PIN = 13 # if using GPIO, which GPIO board mode pin to use as input ODOM_DEBUG = False # Write out values on vel and distance as it runs @@ -436,7 +436,7 @@ # the absolute file path to the python file that has the transformer # class. For instance, if you called the file # `my_custom_transformer.py` and put in in the root of -# your `mycar` folder, next to `myconfig.py`, then you would add +# your `mycar` folder, next to `myconfig.py`, then you would add # the following to your myconfig.py file (keeping with the crop example); # `CUSTOM_CROP_MODULE = "/home/pi/mycar/my_custom_transformer.py"` # The actual path will depend on what OS you are using and what @@ -607,12 +607,12 @@ MM1_STOPPED_PWM = 1500 MM1_MAX_REVERSE = 1000 # Max throttle to go reverse. The smaller the faster MM1_SHOW_STEERING_VALUE = False -# Serial port +# Serial port # -- Default Pi: '/dev/ttyS0' # -- Jetson Nano: '/dev/ttyTHS1' # -- Google coral: '/dev/ttymxc0' # -- Windows: 'COM3', Arduino: '/dev/ttyACM0' -# -- MacOS/Linux:please use 'ls /dev/tty.*' to find the correct serial port for mm1 +# -- MacOS/Linux:please use 'ls /dev/tty.*' to find the correct serial port for mm1 # eg.'/dev/tty.usbmodemXXXXXX' and replace the port accordingly MM1_SERIAL_PORT = '/dev/ttyS0' # Serial Port for reading and sending MM1 data. diff --git a/donkeycar/templates/cfg_cv_control.py b/donkeycar/templates/cfg_cv_control.py index f7e8604f2..6c25d635a 100755 --- a/donkeycar/templates/cfg_cv_control.py +++ b/donkeycar/templates/cfg_cv_control.py @@ -612,4 +612,3 @@ DEC_PID_D_BTN = None # button to change PID 'D' constant by -PID_D_DELTA INC_PID_P_BTN = "R2" # button to change PID 'P' constant by PID_P_DELTA DEC_PID_P_BTN = "L2" # button to change PID 'P' constant by -PID_P_DELTA - diff --git a/donkeycar/templates/cfg_path_follow.py b/donkeycar/templates/cfg_path_follow.py index 4ac8a7895..0b4c3c896 100644 --- a/donkeycar/templates/cfg_path_follow.py +++ b/donkeycar/templates/cfg_path_follow.py @@ -643,7 +643,7 @@ PATH_MIN_DIST = 0.2 # after travelling this distance (m), save a path point PATH_SEARCH_LENGTH = None # number of points to search for closest point, None to search entire path PATH_LOOK_AHEAD = 1 # number of points ahead of the closest point to include in cte track -PATH_LOOK_BEHIND = 1 # number of points behind the closest point to include in cte track +PATH_LOOK_BEHIND = 1 # number of points behind the closest point to include in cte track PID_P = -0.5 # proportional mult for PID path follower PID_I = 0.000 # integral mult for PID path follower PID_D = -0.3 # differential mult for PID path follower @@ -671,4 +671,3 @@ # Intel Realsense T265 tracking camera REALSENSE_T265_ID = None # serial number of camera or None if you only have one camera (it will autodetect) WHEEL_ODOM_CALIB = "calibration_odometry.json" - diff --git a/donkeycar/templates/cfg_simulator.py b/donkeycar/templates/cfg_simulator.py index ea498fc5d..4313617c8 100644 --- a/donkeycar/templates/cfg_simulator.py +++ b/donkeycar/templates/cfg_simulator.py @@ -161,12 +161,12 @@ MM1_STOPPED_PWM = 1500 MM1_MAX_REVERSE = 1000 # Max throttle to go reverse. The smaller the faster MM1_SHOW_STEERING_VALUE = False -# Serial port +# Serial port # -- Default Pi: '/dev/ttyS0' # -- Jetson Nano: '/dev/ttyTHS1' # -- Google coral: '/dev/ttymxc0' # -- Windows: 'COM3', Arduino: '/dev/ttyACM0' -# -- MacOS/Linux:please use 'ls /dev/tty.*' to find the correct serial port for mm1 +# -- MacOS/Linux:please use 'ls /dev/tty.*' to find the correct serial port for mm1 # eg.'/dev/tty.usbmodemXXXXXX' and replace the port accordingly MM1_SERIAL_PORT = '/dev/ttyS0' # Serial Port for reading and sending MM1 data. diff --git a/donkeycar/templates/complete.py b/donkeycar/templates/complete.py index e2c807a78..4e1d62a7c 100644 --- a/donkeycar/templates/complete.py +++ b/donkeycar/templates/complete.py @@ -11,7 +11,7 @@ --js Use physical joystick. -f --file= A text file containing paths to tub files, one per line. Option may be used more than once. --meta= Key/Value strings describing describing a piece of meta data about this drive. Option may be used more than once. - --myconfig=filename Specify myconfig file to use. + --myconfig=filename Specify myconfig file to use. [default: myconfig.py] """ from docopt import docopt @@ -22,7 +22,7 @@ # try: import cv2 -except: +except Exception: pass @@ -85,7 +85,7 @@ def drive(cfg, model_path=None, use_joystick=False, model_type=None, if cfg.HAVE_MQTT_TELEMETRY: from donkeycar.parts.telemetry import MqttTelemetry tel = MqttTelemetry(cfg) - + # # if we are using the simulator, set it up # @@ -146,11 +146,11 @@ def drive(cfg, model_path=None, use_joystick=False, model_type=None, # For example: adding a button handler is just adding a part with a run_condition # set to the button's name, so it runs when button is pressed. # - V.add(Lambda(lambda v: print(f"web/w1 clicked")), inputs=["web/w1"], run_condition="web/w1") - V.add(Lambda(lambda v: print(f"web/w2 clicked")), inputs=["web/w2"], run_condition="web/w2") - V.add(Lambda(lambda v: print(f"web/w3 clicked")), inputs=["web/w3"], run_condition="web/w3") - V.add(Lambda(lambda v: print(f"web/w4 clicked")), inputs=["web/w4"], run_condition="web/w4") - V.add(Lambda(lambda v: print(f"web/w5 clicked")), inputs=["web/w5"], run_condition="web/w5") + V.add(Lambda(lambda v: print("web/w1 clicked")), inputs=["web/w1"], run_condition="web/w1") + V.add(Lambda(lambda v: print("web/w2 clicked")), inputs=["web/w2"], run_condition="web/w2") + V.add(Lambda(lambda v: print("web/w3 clicked")), inputs=["web/w3"], run_condition="web/w3") + V.add(Lambda(lambda v: print("web/w4 clicked")), inputs=["web/w4"], run_condition="web/w4") + V.add(Lambda(lambda v: print("web/w5 clicked")), inputs=["web/w5"], run_condition="web/w5") #this throttle filter will allow one tap back for esc reverse th_filter = ThrottleFilter() @@ -257,7 +257,7 @@ def show_record_count_status(): if isinstance(ctr, JoystickController): ctr.set_button_down_trigger('circle', show_record_count_status) #then we are not using the circle button. hijack that to force a record count indication else: - + show_record_count_status() #Sombrero @@ -277,14 +277,14 @@ def load_model(kl, model_path): start = time.time() print('loading model', model_path) kl.load(model_path) - print('finished loading in %s sec.' % (str(time.time() - start)) ) + print(f'finished loading in {str(time.time() - start)} sec.' ) def load_weights(kl, weights_path): start = time.time() try: print('loading model weights', weights_path) kl.model.load_weights(weights_path) - print('finished loading in %s sec.' % (str(time.time() - start)) ) + print(f'finished loading in {str(time.time() - start)} sec.' ) except Exception as e: print(e) print('ERR>> problems loading weights', weights_path) @@ -297,7 +297,7 @@ def load_model_json(kl, json_fnm): with open(json_fnm, 'r') as handle: contents = handle.read() kl.model = keras.models.model_from_json(contents) - print('finished loading json in %s sec.' % (str(time.time() - start)) ) + print(f'finished loading json in {str(time.time() - start)} sec.' ) except Exception as e: print(e) print("ERR>> problems loading model json", json_fnm) @@ -363,7 +363,7 @@ def reload_weights(filename): V.add(bh, outputs=['behavior/state', 'behavior/label', "behavior/one_hot_state_array"]) try: ctr.set_button_down_trigger('L1', bh.increment_state) - except: + except Exception: pass inputs = ['cam/image_array', "behavior/one_hot_state_array"] @@ -406,7 +406,7 @@ def run(self, *components): # # add the complete set of pre and post augmentation transformations # - logger.info(f"Adding inference transformations") + logger.info("Adding inference transformations") V.add(ImageTransformations(cfg, 'TRANSFORMATIONS', 'POST_TRANSFORMATIONS'), inputs=['cam/image_array'], outputs=['cam/image_array_trans']) @@ -426,7 +426,7 @@ def run(self, *components): cfg.STOP_SIGN_REVERSE_THROTTLE), inputs=['cam/image_array', 'pilot/throttle'], outputs=['pilot/throttle', 'cam/image_array']) - V.add(ThrottleFilter(), + V.add(ThrottleFilter(), inputs=['pilot/throttle'], outputs=['pilot/throttle']) @@ -822,7 +822,7 @@ def get_camera(cfg): from donkeycar.parts.camera import MockCamera cam = MockCamera(image_w=cfg.IMAGE_W, image_h=cfg.IMAGE_H, image_d=cfg.IMAGE_DEPTH) else: - raise(Exception("Unkown camera type: %s" % cfg.CAMERA_TYPE)) + raise(Exception(f"Unkown camera type: {cfg.CAMERA_TYPE}")) return cam @@ -834,7 +834,7 @@ def add_camera(V, cfg, camera_type): On output this will be modified. :param cfg: the configuration (from myconfig.py) """ - logger.info("cfg.CAMERA_TYPE %s"%cfg.CAMERA_TYPE) + logger.info(f"cfg.CAMERA_TYPE {cfg.CAMERA_TYPE}") if camera_type == "stereo": if cfg.CAMERA_TYPE == "WEBCAM": from donkeycar.parts.camera import Webcam @@ -848,7 +848,7 @@ def add_camera(V, cfg, camera_type): camA = CvCam(image_w=cfg.IMAGE_W, image_h=cfg.IMAGE_H, image_d=cfg.IMAGE_DEPTH, iCam = 0) camB = CvCam(image_w=cfg.IMAGE_W, image_h=cfg.IMAGE_H, image_d=cfg.IMAGE_DEPTH, iCam = 1) else: - raise(Exception("Unsupported camera type: %s" % cfg.CAMERA_TYPE)) + raise(Exception(f"Unsupported camera type: {cfg.CAMERA_TYPE}")) V.add(camA, outputs=['cam/image_array_a'], threaded=True) V.add(camB, outputs=['cam/image_array_b'], threaded=True) @@ -1117,10 +1117,10 @@ def add_drivetrain(V, cfg): min_pulse=cfg.THROTTLE_REVERSE_PWM) V.add(steering, inputs=['steering'], threaded=True) V.add(throttle, inputs=['throttle'], threaded=True) - + elif cfg.DRIVE_TRAIN_TYPE == "VESC": from donkeycar.parts.actuator import VESC - logger.info("Creating VESC at port {}".format(cfg.VESC_SERIAL_PORT)) + logger.info(f"Creating VESC at port {cfg.VESC_SERIAL_PORT}") vesc = VESC(cfg.VESC_SERIAL_PORT, cfg.VESC_MAX_SPEED_PERCENT, cfg.VESC_HAS_SENSOR, diff --git a/donkeycar/templates/cv_control.py b/donkeycar/templates/cv_control.py index 1ee305d9f..046f8bccc 100755 --- a/donkeycar/templates/cv_control.py +++ b/donkeycar/templates/cv_control.py @@ -44,7 +44,7 @@ def drive(cfg, use_joystick=False, camera_type='single', meta=[]): Parts may have named outputs and inputs. The framework handles passing named outputs to parts requesting the same named input. ''' - + #Initialize car V = dk.vehicle.Vehicle() @@ -84,19 +84,19 @@ def drive(cfg, use_joystick=False, camera_type='single', meta=[]): pid = PID(Kp=cfg.PID_P, Ki=cfg.PID_I, Kd=cfg.PID_D) def dec_pid_d(): pid.Kd -= cfg.PID_D_DELTA - logging.info("pid: d- %f" % pid.Kd) + logging.info(f"pid: d- {pid.Kd:f}") def inc_pid_d(): pid.Kd += cfg.PID_D_DELTA - logging.info("pid: d+ %f" % pid.Kd) + logging.info(f"pid: d+ {pid.Kd:f}") def dec_pid_p(): pid.Kp -= cfg.PID_P_DELTA - logging.info("pid: p- %f" % pid.Kp) + logging.info(f"pid: p- {pid.Kp:f}") def inc_pid_p(): pid.Kp += cfg.PID_P_DELTA - logging.info("pid: p+ %f" % pid.Kp) + logging.info(f"pid: p+ {pid.Kp:f}") # # Computer Vision Controller @@ -215,7 +215,7 @@ def inc_pid_p(): # # run the vehicle # - V.start(rate_hz=cfg.DRIVE_LOOP_HZ, + V.start(rate_hz=cfg.DRIVE_LOOP_HZ, max_loop_count=cfg.MAX_LOOPS) @@ -223,27 +223,27 @@ def inc_pid_p(): # Computer Vision Controller # def add_cv_controller( - V, cfg, pid, - module_name="donkeycar.parts.line_follower", - class_name="LineFollower", - inputs=['cam/image_array'], - outputs=['pilot/steering', 'pilot/throttle', 'cv/image_array'], - run_condition="run_pilot"): + V, cfg, pid, + module_name="donkeycar.parts.line_follower", + class_name="LineFollower", + inputs=['cam/image_array'], + outputs=['pilot/steering', 'pilot/throttle', 'cv/image_array'], + run_condition="run_pilot"): - # __import__ the module - module = __import__(module_name) + # __import__ the module + module = __import__(module_name) - # walk module path to get to module with class - for attr in module_name.split('.')[1:]: - module = getattr(module, attr) + # walk module path to get to module with class + for attr in module_name.split('.')[1:]: + module = getattr(module, attr) - my_class = getattr(module, class_name) + my_class = getattr(module, class_name) - # add instance of class to vehicle - V.add(my_class(pid, cfg), - inputs=inputs, - outputs=outputs, - run_condition=run_condition) + # add instance of class to vehicle + V.add(my_class(pid, cfg), + inputs=inputs, + outputs=outputs, + run_condition=run_condition) if __name__ == '__main__': @@ -253,7 +253,7 @@ def add_cv_controller( log_level = args['--log'] or "INFO" numeric_level = getattr(logging, log_level.upper(), None) if not isinstance(numeric_level, int): - raise ValueError('Invalid log level: %s' % log_level) + raise ValueError(f'Invalid log level: {log_level}') logging.basicConfig(level=numeric_level) if args['drive']: diff --git a/donkeycar/templates/just_drive.py b/donkeycar/templates/just_drive.py index b7eae21a7..59e4ee44c 100755 --- a/donkeycar/templates/just_drive.py +++ b/donkeycar/templates/just_drive.py @@ -31,7 +31,7 @@ def drive(cfg): #Initialize car V = dk.vehicle.Vehicle() - + class MyController: ''' a simple controller class that outputs a constant steering and throttle. @@ -46,26 +46,26 @@ def run(self): #Drive train setup steering_controller = PCA9685(cfg.STEERING_CHANNEL, cfg.PCA9685_I2C_ADDR, busnum=cfg.PCA9685_I2C_BUSNUM) steering = PWMSteering(controller=steering_controller, - left_pulse=cfg.STEERING_LEFT_PWM, + left_pulse=cfg.STEERING_LEFT_PWM, right_pulse=cfg.STEERING_RIGHT_PWM) - + throttle_controller = PCA9685(cfg.THROTTLE_CHANNEL, cfg.PCA9685_I2C_ADDR, busnum=cfg.PCA9685_I2C_BUSNUM) throttle = PWMThrottle(controller=throttle_controller, max_pulse=cfg.THROTTLE_FORWARD_PWM, - zero_pulse=cfg.THROTTLE_STOPPED_PWM, + zero_pulse=cfg.THROTTLE_STOPPED_PWM, min_pulse=cfg.THROTTLE_REVERSE_PWM) V.add(steering, inputs=['angle']) V.add(throttle, inputs=['throttle']) - + #run the vehicle for 20 seconds - V.start(rate_hz=cfg.DRIVE_LOOP_HZ, + V.start(rate_hz=cfg.DRIVE_LOOP_HZ, max_loop_count=cfg.MAX_LOOPS) if __name__ == '__main__': args = docopt(__doc__) cfg = dk.load_config() - + if args['drive']: drive(cfg) diff --git a/donkeycar/templates/myconfig.py b/donkeycar/templates/myconfig.py index 773232c67..425db7d06 100755 --- a/donkeycar/templates/myconfig.py +++ b/donkeycar/templates/myconfig.py @@ -1,10 +1,9 @@ -# """ -# My CAR CONFIG +# """ +# My CAR CONFIG # This file is read by your car application's manage.py script to change the car # performance -# If desired, all config overrides can be specified here. +# If desired, all config overrides can be specified here. # The update operation will not touch this file. # """ - diff --git a/donkeycar/templates/path_follow.py b/donkeycar/templates/path_follow.py index 1d029bbf2..110a0f269 100644 --- a/donkeycar/templates/path_follow.py +++ b/donkeycar/templates/path_follow.py @@ -39,6 +39,7 @@ """ from distutils.log import debug import os +import sys import logging # @@ -49,7 +50,7 @@ try: import cv2 -except: +except Exception: pass @@ -90,7 +91,7 @@ def drive(cfg, use_joystick=False, camera_type='single'): if cfg.HAVE_SOMBRERO: from donkeycar.utils import Sombrero s = Sombrero() - + #Initialize logging before anything else to allow console logging if cfg.HAVE_CONSOLE_LOGGING: logger.setLevel(logging.getLevelName(cfg.LOGGING_LEVEL)) @@ -137,7 +138,7 @@ def run(self): print("You must supply a json file when using odom with T265. " "There is a sample file in templates.") print("cp donkeycar/donkeycar/templates/calibration_odometry.json .") - exit(1) + sys.exit(1) # # NOTE: image output on the T265 is broken in the python API and @@ -233,14 +234,14 @@ def save_path(): def load_path(): if os.path.exists(cfg.PATH_FILENAME) and path.load(cfg.PATH_FILENAME): - print("The path was loaded was loaded from ", cfg.PATH_FILENAME) + print("The path was loaded was loaded from ", cfg.PATH_FILENAME) - # we loaded the path; also load any recorded gps readings - if gps_player: - gps_player.stop().nmea.load() - gps_player.start() + # we loaded the path; also load any recorded gps readings + if gps_player: + gps_player.stop().nmea.load() + gps_player.start() else: - print("path _not_ loaded; make sure you have saved a path.") + print("path _not_ loaded; make sure you have saved a path.") def erase_path(): origin_reset.reset_origin() @@ -287,19 +288,19 @@ def reset_origin(): def dec_pid_d(): pid.Kd -= cfg.PID_D_DELTA - logging.info("pid: d- %f" % pid.Kd) + logging.info(f"pid: d- {pid.Kd:f}") def inc_pid_d(): pid.Kd += cfg.PID_D_DELTA - logging.info("pid: d+ %f" % pid.Kd) + logging.info(f"pid: d+ {pid.Kd:f}") def dec_pid_p(): pid.Kp -= cfg.PID_P_DELTA - logging.info("pid: p- %f" % pid.Kp) + logging.info(f"pid: p- {pid.Kp:f}") def inc_pid_p(): pid.Kp += cfg.PID_P_DELTA - logging.info("pid: p+ %f" % pid.Kp) + logging.info(f"pid: p+ {pid.Kp:f}") recording_control = ToggleRecording(cfg.AUTO_RECORD_ON_THROTTLE, cfg.RECORD_DURING_AI) @@ -438,7 +439,7 @@ def inc_pid_p(): V.add(loc_plot, inputs=['map/image', 'pos/x', 'pos/y'], outputs=['map/image'], run_condition='run_user') - V.start(rate_hz=cfg.DRIVE_LOOP_HZ, + V.start(rate_hz=cfg.DRIVE_LOOP_HZ, max_loop_count=cfg.MAX_LOOPS) @@ -486,7 +487,7 @@ def add_gps(V, cfg): log_level = args['--log'] or "INFO" numeric_level = getattr(logging, log_level.upper(), None) if not isinstance(numeric_level, int): - raise ValueError('Invalid log level: %s' % log_level) + raise ValueError(f'Invalid log level: {log_level}') logging.basicConfig(level=numeric_level) diff --git a/donkeycar/templates/simulator.py b/donkeycar/templates/simulator.py index 9effcf8c1..2c0076005 100644 --- a/donkeycar/templates/simulator.py +++ b/donkeycar/templates/simulator.py @@ -11,7 +11,7 @@ --js Use physical joystick. -f --file= A text file containing paths to tub files, one per line. Option may be used more than once. --meta= Key/Value strings describing describing a piece of meta data about this drive. Option may be used more than once. - --myconfig=filename Specify myconfig file to use. + --myconfig=filename Specify myconfig file to use. [default: myconfig.py] """ import os @@ -74,7 +74,7 @@ def drive(cfg, model_path=None, use_joystick=False, model_type=None, camera_type #modify max_throttle closer to 1.0 to have more power #modify steering_scale lower than 1.0 to have less responsive steering if cfg.CONTROLLER_TYPE == "MM1": - from donkeycar.parts.robohat import RoboHATController + from donkeycar.parts.robohat import RoboHATController ctr = RoboHATController(cfg) elif "custom" == cfg.CONTROLLER_TYPE: # @@ -97,8 +97,8 @@ def drive(cfg, model_path=None, use_joystick=False, model_type=None, camera_type netwkJs = JoyStickSub(cfg.NETWORK_JS_SERVER_IP) V.add(netwkJs, threaded=True) ctr.js = netwkJs - - V.add(ctr, + + V.add(ctr, inputs=['cam/image_array'], outputs=['user/angle', 'user/throttle', 'user/mode', 'recording'], threaded=True) @@ -107,7 +107,7 @@ def drive(cfg, model_path=None, use_joystick=False, model_type=None, camera_type #This web controller will create a web server that is capable #of managing steering, throttle, and modes, and more. ctr = LocalWebController(port=cfg.WEB_CONTROL_PORT, mode=cfg.WEB_INIT_MODE) - + V.add(ctr, inputs=['cam/image_array', 'tub/num_records'], outputs=['user/angle', 'user/throttle', 'user/mode', 'recording'], @@ -231,7 +231,7 @@ def show_record_acount_status(): V.add(bh, outputs=['behavior/state', 'behavior/label', "behavior/one_hot_state_array"]) try: ctr.set_button_down_trigger('L1', bh.increment_state) - except: + except Exception: pass inputs = ['cam/image_array', "behavior/one_hot_state_array"] @@ -242,14 +242,14 @@ def load_model(kl, model_path): start = time.time() print('loading model', model_path) kl.load(model_path) - print('finished loading in %s sec.' % (str(time.time() - start)) ) + print(f'finished loading in {str(time.time() - start)} sec.' ) def load_weights(kl, weights_path): start = time.time() try: print('loading model weights', weights_path) kl.model.load_weights(weights_path) - print('finished loading in %s sec.' % (str(time.time() - start)) ) + print(f'finished loading in {str(time.time() - start)} sec.' ) except Exception as e: print(e) print('ERR>> problems loading weights', weights_path) @@ -262,7 +262,7 @@ def load_model_json(kl, json_fnm): with open(json_fnm, 'r') as handle: contents = handle.read() kl.model = keras.models.model_from_json(contents) - print('finished loading json in %s sec.' % (str(time.time() - start)) ) + print(f'finished loading json in {str(time.time() - start)} sec.' ) except Exception as e: print(e) print("ERR>> problems loading model json", json_fnm) @@ -317,7 +317,7 @@ def reload_weights(filename): V.add(kl, inputs=inputs, outputs=outputs, run_condition='run_pilot') - + if cfg.STOP_SIGN_DETECTOR: from donkeycar.parts.object_detector.stop_sign_detector import StopSignDetector V.add(StopSignDetector(cfg.STOP_SIGN_MIN_SCORE, cfg.STOP_SIGN_SHOW_BOUNDING_BOX), inputs=['cam/image_array', 'pilot/throttle'], outputs=['pilot/throttle', 'cam/image_array']) @@ -434,4 +434,3 @@ def run(self, mode, recording): meta=args['--meta']) elif args['train']: print('Use python train.py instead.\n') - diff --git a/donkeycar/templates/square.py b/donkeycar/templates/square.py index dbc6c5bc5..eb7fb6c34 100644 --- a/donkeycar/templates/square.py +++ b/donkeycar/templates/square.py @@ -16,7 +16,7 @@ import os from docopt import docopt -import donkeycar as dk +import donkeycar as dk from donkeycar.parts.datastore import TubGroup, TubHandler from donkeycar.parts.transform import Lambda @@ -28,33 +28,33 @@ def drive(cfg, model_path=None): V = dk.vehicle.Vehicle() #initialize values - V.mem.put(['square/angle', 'square/throttle'], (100,100)) - + V.mem.put(['square/angle', 'square/throttle'], (100,100)) + #display square box given by cooridantes. cam = SquareBoxCamera(resolution=(cfg.IMAGE_H, cfg.IMAGE_W)) - V.add(cam, + V.add(cam, inputs=['square/angle', 'square/throttle'], outputs=['cam/image_array']) - + #display the image and read user values from a local web controller ctr = LocalWebController() - V.add(ctr, + V.add(ctr, inputs=['cam/image_array'], - outputs=['user/angle', 'user/throttle', + outputs=['user/angle', 'user/throttle', 'user/mode', 'recording'], threaded=True) - - #See if we should even run the pilot module. + + #See if we should even run the pilot module. #This is only needed because the part run_contion only accepts boolean def pilot_condition(mode): if mode == 'user': return False else: return True - + pilot_condition_part = Lambda(pilot_condition) V.add(pilot_condition_part, inputs=['user/mode'], outputs=['run_pilot']) - + #Run the pilot if the mode is not user. kl = KerasCategorical() if model_path: @@ -63,61 +63,61 @@ def pilot_condition(mode): V.add(kl, inputs=['cam/image_array'], outputs=['pilot/angle', 'pilot/throttle'], run_condition='run_pilot') - - - #See if we should even run the pilot module. - def drive_mode(mode, + + + #See if we should even run the pilot module. + def drive_mode(mode, user_angle, user_throttle, pilot_angle, pilot_throttle): if mode == 'user': return user_angle, user_throttle - + elif mode == 'pilot_angle': return pilot_angle, user_throttle - - else: + + else: return pilot_angle, pilot_throttle - + drive_mode_part = Lambda(drive_mode) - V.add(drive_mode_part, + V.add(drive_mode_part, inputs=['user/mode', 'user/angle', 'user/throttle', - 'pilot/angle', 'pilot/throttle'], + 'pilot/angle', 'pilot/throttle'], outputs=['angle', 'throttle']) - - - + + + #transform angle and throttle values to coordinate values f = lambda x : int(x * 100 + 100) l = Lambda(f) V.add(l, inputs=['user/angle'], outputs=['square/angle']) V.add(l, inputs=['user/throttle'], outputs=['square/throttle']) - + #add tub to save data inputs=['cam/image_array', - 'user/angle', 'user/throttle', - 'pilot/angle', 'pilot/throttle', + 'user/angle', 'user/throttle', + 'pilot/angle', 'pilot/throttle', 'square/angle', 'square/throttle', 'user/mode'] types=['image_array', - 'float', 'float', - 'float', 'float', + 'float', 'float', + 'float', 'float', 'float', 'float', 'str'] - + th = TubHandler(path=cfg.DATA_PATH) tub = th.new_tub_writer(inputs=inputs, types=types) V.add(tub, inputs=inputs, run_condition='recording') - + #run the vehicle for 20 seconds V.start(rate_hz=50, max_loop_count=10000) - - - + + + def train(cfg, tub_names, model_name): - + X_keys = ['cam/image_array'] y_keys = ['user/angle', 'user/throttle'] - + def rt(record): record['user/angle'] = dk.utils.linear_bin(record['user/angle']) return record @@ -128,7 +128,7 @@ def combined_gen(gens): for gen in gens: combined_gen = itertools.chain(combined_gen, gen) return combined_gen - + kl = KerasCategorical() print('tub_names', tub_names) if not tub_names: @@ -154,14 +154,14 @@ def combined_gen(gens): train_split=cfg.TRAIN_TEST_SPLIT) - + if __name__ == '__main__': args = docopt(__doc__) cfg = dk.load_config() - + if args['drive']: drive(cfg, args['--model']) - + elif args['train']: tub = args['--tub'] model = args['--model'] diff --git a/donkeycar/tests/setup.py b/donkeycar/tests/setup.py index 19d850b80..995fd34fc 100644 --- a/donkeycar/tests/setup.py +++ b/donkeycar/tests/setup.py @@ -30,7 +30,7 @@ def tub(tub_path): @pytest.fixture def tubs(tmpdir, tubs=5): tubs_dir = tmpdir.mkdir('tubs') - tub_paths = [str(tubs_dir.join('tub_{}'.format(i))) for i in range(tubs)] + tub_paths = [str(tubs_dir.join(f'tub_{i}')) for i in range(tubs)] tubs = [create_sample_tub(tub_path, records=5) for tub_path in tub_paths] return str(tubs_dir), tub_paths, tubs diff --git a/donkeycar/tests/test_catalog_v2.py b/donkeycar/tests/test_catalog_v2.py index 29d1c7097..4347b70f0 100644 --- a/donkeycar/tests/test_catalog_v2.py +++ b/donkeycar/tests/test_catalog_v2.py @@ -27,7 +27,7 @@ def test_basic_catalog_operations(self): line = catalog_2.seekable.readline() count = 0 while line is not None and len(line) > 0: - print('Contents %s' % (line)) + print(f'Contents {line}') count += 1 line = catalog_2.seekable.readline() diff --git a/donkeycar/tests/test_controller.py b/donkeycar/tests/test_controller.py index 992bb82c8..7f9d28c30 100755 --- a/donkeycar/tests/test_controller.py +++ b/donkeycar/tests/test_controller.py @@ -30,4 +30,4 @@ def test_fn(): js.toggle_mode() js.chaos_monkey_on_left() js.chaos_monkey_on_right() - js.chaos_monkey_off() \ No newline at end of file + js.chaos_monkey_off() diff --git a/donkeycar/tests/test_datastore_v2.py b/donkeycar/tests/test_datastore_v2.py index a4eaadfc2..2db7c708e 100644 --- a/donkeycar/tests/test_datastore_v2.py +++ b/donkeycar/tests/test_datastore_v2.py @@ -22,7 +22,7 @@ def test_basic_datastore_operations(self): read_records = 0 for entry in manifest: - print('Entry %s' % (entry)) + print(f'Entry {entry}') read_records += 1 self.assertEqual(count, read_records) diff --git a/donkeycar/tests/test_keras.py b/donkeycar/tests/test_keras.py index 2c71bff0e..5fc010224 100644 --- a/donkeycar/tests/test_keras.py +++ b/donkeycar/tests/test_keras.py @@ -86,7 +86,3 @@ def test_keras_vs_tflite_and_tensorrt(keras_pilot, tmp_dir): out3 = krt.run(*args) assert out3 == approx(out1, rel=TOLERANCE, abs=TOLERANCE) print(out1, out2, out3) - - - - diff --git a/donkeycar/tests/test_kinematics.py b/donkeycar/tests/test_kinematics.py index 4875748c4..5679cca45 100644 --- a/donkeycar/tests/test_kinematics.py +++ b/donkeycar/tests/test_kinematics.py @@ -127,7 +127,7 @@ def do_90degree_turn(self, steering_angle): turn_direction = sign(steering_angle) steering_angle = limit_angle(steering_angle) - wheel_base = 0.5 + wheel_base = 0.5 bicycle = Bicycle(wheel_base) # wheel base is 1/2 meter @@ -372,7 +372,7 @@ def test_normalize(self): max_forward_velocity = 10 max_steering_angle = math.pi / 6 max_angular_velocity = bicycle_angular_velocity(wheel_base, max_forward_velocity, max_steering_angle) - normalize = BicycleNormalizeAngularVelocity(wheel_base, max_forward_velocity, max_steering_angle) + normalize = BicycleNormalizeAngularVelocity(wheel_base, max_forward_velocity, max_steering_angle) unnormalize = BicycleUnnormalizeAngularVelocity(wheel_base, max_forward_velocity, max_steering_angle) angular_velocity = normalize.run(max_angular_velocity) @@ -407,7 +407,7 @@ def test_normalize(self): axle_length = 0.1 max_forward_velocity = 10 max_angular_velocity = unicycle_max_angular_velocity(wheel_radius, axle_length, max_forward_velocity) - normalize = UnicycleNormalizeAngularVelocity(wheel_radius, axle_length, max_forward_velocity) + normalize = UnicycleNormalizeAngularVelocity(wheel_radius, axle_length, max_forward_velocity) unnormalize = UnicycleUnnormalizeAngularVelocity(wheel_radius, axle_length, max_forward_velocity) angular_velocity = normalize.run(max_angular_velocity / 2) @@ -419,7 +419,7 @@ def test_normalize(self): class TestNormalizeSteeringAngle(unittest.TestCase): def test_normalize(self): max_steering_angle = math.pi / 6 - normalize = NormalizeSteeringAngle(max_steering_angle) + normalize = NormalizeSteeringAngle(max_steering_angle) unnormalize = UnnormalizeSteeringAngle(max_steering_angle) # diff --git a/donkeycar/tests/test_launch.py b/donkeycar/tests/test_launch.py index ca0efac24..733d053bf 100755 --- a/donkeycar/tests/test_launch.py +++ b/donkeycar/tests/test_launch.py @@ -88,4 +88,3 @@ def test_ai_launch_keep_enabled(): new_throttle = ai_launch.run(mode, ai_throttle) assert(new_throttle == 0.0) - diff --git a/donkeycar/tests/test_lidar.py b/donkeycar/tests/test_lidar.py index 37622a080..8b597a79e 100644 --- a/donkeycar/tests/test_lidar.py +++ b/donkeycar/tests/test_lidar.py @@ -90,7 +90,8 @@ def test_simple_express_scan(): for count, scan in enumerate(scan_generator()): print(count, scan) - if count == 20: break + if count == 20: + break lidar.stop() lidar.set_motor_pwm(0) diff --git a/donkeycar/tests/test_memory.py b/donkeycar/tests/test_memory.py index d64809e6d..f14bb91e6 100755 --- a/donkeycar/tests/test_memory.py +++ b/donkeycar/tests/test_memory.py @@ -64,5 +64,5 @@ def test_get_values(self): def test_get_iter(self): mem = Memory() mem.put(['myitem'], 888) - + assert dict(mem.items()) == {'myitem': 888} diff --git a/donkeycar/tests/test_odometer.py b/donkeycar/tests/test_odometer.py index 3e629bfed..0d6d5e1f9 100644 --- a/donkeycar/tests/test_odometer.py +++ b/donkeycar/tests/test_odometer.py @@ -5,7 +5,7 @@ from donkeycar.parts.odometer import Odometer class TestOdometer(unittest.TestCase): - + def test_odometer(self): odometer = Odometer(0.2) # 0.2 meters per revolution @@ -26,4 +26,3 @@ def test_odometer(self): self.assertEqual(ts, timestamp) self.assertEqual(0.4, distance) # still at 0.4 meters travelled self.assertEqual(0, velocity) # 0 meter per second in last interval - diff --git a/donkeycar/tests/test_parts.py b/donkeycar/tests/test_parts.py index 8b1378917..e69de29bb 100755 --- a/donkeycar/tests/test_parts.py +++ b/donkeycar/tests/test_parts.py @@ -1 +0,0 @@ - diff --git a/donkeycar/tests/test_scripts.py b/donkeycar/tests/test_scripts.py index afc0ef9a3..41813c04c 100755 --- a/donkeycar/tests/test_scripts.py +++ b/donkeycar/tests/test_scripts.py @@ -82,4 +82,3 @@ def test_tubplot(cardir): line = pipe.stdout.readline().decode() print(f'List model dir: {os.listdir(model_dir)}') assert os.path.exists(model_path + '_pred.png') - diff --git a/donkeycar/tests/test_tachometer.py b/donkeycar/tests/test_tachometer.py index 44a72ab3d..73b4fa009 100644 --- a/donkeycar/tests/test_tachometer.py +++ b/donkeycar/tests/test_tachometer.py @@ -31,14 +31,14 @@ def __init__(self, ticks_per_revolution: float, direction_mode, debug=False): class TestTachometer(unittest.TestCase): - + def test_tachometer_forward_only(self): # # FORWARD_ONLY mode will ignore throttle # and just increase revolutions # tachometer = MockTachometer( - ticks_per_revolution=10, + ticks_per_revolution=10, direction_mode=EncoderMode.FORWARD_ONLY) ts = time.time() @@ -59,7 +59,7 @@ def test_tachometer_forward_only(self): ts += 1 # add one second and reverse one revolution revolutions, timestamp = tachometer.run(throttle=-1, timestamp=ts) self.assertEqual(ts, timestamp) - self.assertAlmostEqual(0.4, revolutions, 4) + self.assertAlmostEqual(0.4, revolutions, 4) ts += 1 # add one second, but stopped and coasting revolutions, timestamp = tachometer.run(throttle=0, timestamp=ts) @@ -77,7 +77,7 @@ def test_tachometer_forward_reverse(self): # will continue in reverse. # tachometer = MockTachometer( - ticks_per_revolution=10, + ticks_per_revolution=10, direction_mode=EncoderMode.FORWARD_REVERSE) ts = time.time() @@ -98,7 +98,7 @@ def test_tachometer_forward_reverse(self): ts += 1 # add one second and reverse one revolution revolutions, timestamp = tachometer.run(throttle=-1, timestamp=ts) self.assertEqual(ts, timestamp) - self.assertAlmostEqual(0.2, revolutions, 4) + self.assertAlmostEqual(0.2, revolutions, 4) ts += 1 # add one second, but stopped and coasting revolutions, timestamp = tachometer.run(throttle=0, timestamp=ts) @@ -109,13 +109,13 @@ def test_tachometer_forward_reverse(self): def test_tachometer_forward_reverse_stop(self): # # FORWARD_REVERSE_STOP mode will honor the - # throttle completely; + # throttle completely; # positive throttle being forward, increasing revolutions # negative throttle being reverse, decreasing revolutions # zero throttle being stopped; no change in revolutions # tachometer = MockTachometer( - ticks_per_revolution=10, + ticks_per_revolution=10, direction_mode=EncoderMode.FORWARD_REVERSE_STOP) ts = time.time() @@ -136,7 +136,7 @@ def test_tachometer_forward_reverse_stop(self): ts += 1 # add one second and reverse one revolution revolutions, timestamp = tachometer.run(throttle=-1, timestamp=ts) self.assertEqual(ts, timestamp) - self.assertAlmostEqual(0.1, revolutions, 4) + self.assertAlmostEqual(0.1, revolutions, 4) ts += 1 # add one second, but stopped revolutions, timestamp = tachometer.run(throttle=0, timestamp=ts) diff --git a/donkeycar/tests/test_telemetry.py b/donkeycar/tests/test_telemetry.py index 872cf8620..713a152f9 100644 --- a/donkeycar/tests/test_telemetry.py +++ b/donkeycar/tests/test_telemetry.py @@ -12,7 +12,7 @@ def test_mqtt_telemetry(): cfg.TELEMETRY_DEFAULT_INPUTS = 'pilot/angle,pilot/throttle' - cfg.TELEMETRY_DONKEY_NAME = 'test{}'.format(randint(0, 1000)) + cfg.TELEMETRY_DONKEY_NAME = f'test{randint(0, 1000)}' cfg.TELEMETRY_MQTT_JSON_ENABLE = True # Create receiver @@ -26,7 +26,7 @@ def test_mqtt_telemetry(): sub.on_message = on_message_mock sub.connect(cfg.TELEMETRY_MQTT_BROKER_HOST) sub.loop_start() - name = "donkey/%s/#" % cfg.TELEMETRY_DONKEY_NAME + name = f"donkey/{cfg.TELEMETRY_DONKEY_NAME}/#" sub.subscribe(name) t = MqttTelemetry(cfg) diff --git a/donkeycar/tests/test_torch.py b/donkeycar/tests/test_torch.py index 3d6bb9fd6..29668c3f7 100644 --- a/donkeycar/tests/test_torch.py +++ b/donkeycar/tests/test_torch.py @@ -69,7 +69,7 @@ def pilot_path(name): tub_dir = os.path.join(car_dir, 'tub') loss = train(config, tub_dir, pilot_path( data.name), data.type, checkpoint_path=None) - + # check loss is converging assert loss[-1] < loss[0] * data.convergence diff --git a/donkeycar/tests/test_train.py b/donkeycar/tests/test_train.py index 0abe0dc6f..dedd74a27 100644 --- a/donkeycar/tests/test_train.py +++ b/donkeycar/tests/test_train.py @@ -231,4 +231,3 @@ def test_training_pipeline(config: Config, model_type: str, # compare record values with values from tf.data for k, v in batch.items(): assert np.isclose(v, np_dict[k]).all() - diff --git a/donkeycar/tests/test_vehicle.py b/donkeycar/tests/test_vehicle.py index d101ba138..0c548b75b 100755 --- a/donkeycar/tests/test_vehicle.py +++ b/donkeycar/tests/test_vehicle.py @@ -38,7 +38,7 @@ def test_should_raise_assertion_on_non_list_inputs_for_add_part(): inputs = 'any' with pytest.raises(AssertionError): vehicle.add(_get_sample_lambda(), inputs=inputs) - pytest.fail("inputs is not a list: %r" % inputs) + pytest.fail(f"inputs is not a list: {inputs!r}") def test_should_raise_assertion_on_non_list_outputs_for_add_part(): @@ -46,7 +46,7 @@ def test_should_raise_assertion_on_non_list_outputs_for_add_part(): outputs = 'any' with pytest.raises(AssertionError): vehicle.add(_get_sample_lambda(), outputs=outputs) - pytest.fail("outputs is not a list: %r" % outputs) + pytest.fail(f"outputs is not a list: {outputs!r}") def test_should_raise_assertion_on_non_boolean_threaded_for_add_part(): @@ -54,4 +54,4 @@ def test_should_raise_assertion_on_non_boolean_threaded_for_add_part(): threaded = 'non_boolean' with pytest.raises(AssertionError): vehicle.add(_get_sample_lambda(), threaded=threaded) - pytest.fail("threaded is not a boolean: %r" % threaded) \ No newline at end of file + pytest.fail(f"threaded is not a boolean: {threaded!r}") diff --git a/donkeycar/tests/test_web_controller.py b/donkeycar/tests/test_web_controller.py index d3b95e9bd..1901ebfd3 100755 --- a/donkeycar/tests/test_web_controller.py +++ b/donkeycar/tests/test_web_controller.py @@ -16,9 +16,9 @@ def test_json_output(server): result = server.run() json_result = json.dumps(result) d = json.loads(json_result) - + assert server.port == 8887 - + assert d is not None assert int(d[0]) == 0 @@ -27,6 +27,5 @@ def test_web_control_user_defined_port(): os.environ['WEB_CONTROL_PORT'] = "12345" reload(cfg) server = LocalWebController(port=cfg.WEB_CONTROL_PORT) - - assert server.port == 12345 + assert server.port == 12345 diff --git a/donkeycar/utilities/circular_buffer.py b/donkeycar/utilities/circular_buffer.py index d3285ef8a..c24be7623 100644 --- a/donkeycar/utilities/circular_buffer.py +++ b/donkeycar/utilities/circular_buffer.py @@ -46,7 +46,7 @@ def enqueue(self, value): self.tailIndex = (self.tailIndex + 1) % self.capacity # write value at head - self.buffer[(self.tailIndex + self.count - 1) % self.capacity] = value + self.buffer[(self.tailIndex + self.count - 1) % self.capacity] = value def dequeue(self): """ @@ -140,4 +140,3 @@ def truncateTo(self, count): raise ValueError("count is out of range") self.count = count self.tailIndex = (self.tailIndex + count) % self.capacity - diff --git a/donkeycar/utilities/deprecated.py b/donkeycar/utilities/deprecated.py index 333c0ef5a..96613c5b3 100644 --- a/donkeycar/utilities/deprecated.py +++ b/donkeycar/utilities/deprecated.py @@ -2,7 +2,7 @@ import inspect import warnings -string_types = (type(b''), type(u'')) +string_types = (type(b''), type('')) def deprecated(reason): diff --git a/donkeycar/utilities/dk_platform.py b/donkeycar/utilities/dk_platform.py index cbcecbe77..2cab44992 100644 --- a/donkeycar/utilities/dk_platform.py +++ b/donkeycar/utilities/dk_platform.py @@ -2,7 +2,7 @@ import platform # -# functions to query hardware and os +# functions to query hardware and os # def is_mac(): return "Darwin" == platform.system() diff --git a/donkeycar/utils.py b/donkeycar/utils.py index bd2e892c2..cd241006b 100644 --- a/donkeycar/utils.py +++ b/donkeycar/utils.py @@ -109,7 +109,7 @@ def binary_to_img(binary): try: img = Image.open(img) return img - except: + except Exception: return None @@ -175,7 +175,7 @@ def load_pil_image(filename, cfg): if cfg.IMAGE_DEPTH == 1: img = img.convert('L') - + return img except Exception as e: @@ -400,7 +400,7 @@ def throttle(input_value): ''' def is_number_type(i): - return type(i) == int or type(i) == float; + return type(i) == int or type(i) == float def sign(x): @@ -604,7 +604,7 @@ def train_test_split(data_list: List[Any], """ -class FPSTimer(object): +class FPSTimer(): def __init__(self): self.t = time.time() self.iter = 0 diff --git a/donkeycar/vehicle.py b/donkeycar/vehicle.py index 614b9d78d..ad0e14351 100644 --- a/donkeycar/vehicle.py +++ b/donkeycar/vehicle.py @@ -50,10 +50,10 @@ def report(self): if len(arr) == 0: continue row = [p.__class__.__name__, - "%.2f" % (max(arr) * 1000), - "%.2f" % (min(arr) * 1000), - "%.2f" % (sum(arr) / len(arr) * 1000)] - row += ["%.2f" % (np.percentile(arr, p) * 1000) for p in pctile] + f"{max(arr) * 1000:.2f}", + f"{min(arr) * 1000:.2f}", + f"{sum(arr) / len(arr) * 1000:.2f}"] + row += [f"{np.percentile(arr, p) * 1000:.2f}" for p in pctile] pt.add_row(row) logger.info('\n' + str(pt)) @@ -87,12 +87,12 @@ def add(self, part, inputs=[], outputs=[], run_condition : str If a part should be run or not """ - assert type(inputs) is list, "inputs is not a list: %r" % inputs - assert type(outputs) is list, "outputs is not a list: %r" % outputs - assert type(threaded) is bool, "threaded is not a boolean: %r" % threaded + assert type(inputs) is list, f"inputs is not a list: {inputs!r}" + assert type(outputs) is list, f"outputs is not a list: {outputs!r}" + assert type(threaded) is bool, f"threaded is not a boolean: {threaded!r}" p = part - logger.info('Adding part {}.'.format(p.__class__.__name__)) + logger.info(f'Adding part {p.__class__.__name__}.') entry = {} entry['part'] = p entry['inputs'] = inputs @@ -144,7 +144,7 @@ def start(self, rate_hz=10, max_loop_count=None, verbose=False): entry.get('thread').start() # wait until the parts warm up. - logger.info('Starting vehicle at {} Hz'.format(rate_hz)) + logger.info(f'Starting vehicle at {rate_hz} Hz') loop_start_time = time.time() loop_count = 0 @@ -194,7 +194,7 @@ def update_parts(self): if entry.get('run_condition'): run_condition = entry.get('run_condition') run = self.mem.get([run_condition])[0] - + if run: # get part p = entry['part'] @@ -214,7 +214,7 @@ def update_parts(self): # finish timing part run self.profiler.on_part_finished(p) - def stop(self): + def stop(self): logger.info('Shutting down vehicle and its parts...') for entry in self.parts: try: diff --git a/scripts/freeze_model.py b/scripts/freeze_model.py index 410a4b276..e0dd3167a 100755 --- a/scripts/freeze_model.py +++ b/scripts/freeze_model.py @@ -17,7 +17,7 @@ in_model = os.path.expanduser(args['--model']) output = os.path.expanduser(args['--output']) output_path = Path(output) -output_meta = Path('%s/%s.metadata' % (output_path.parent.as_posix(), output_path.stem)) +output_meta = Path(f'{output_path.parent.as_posix()}/{output_path.stem}.metadata') tf.compat.v1.disable_eager_execution() @@ -46,7 +46,6 @@ output_file.write(graph_frozen.SerializeToString()) meta_file.write(json.dumps(meta)) - print ('Inputs = [%s], Outputs = [%s]' % (input_names, output_names)) - print ('Writing metadata to %s' % output_meta.as_posix()) - print ('To convert use: \n `convert-to-uff %s`' % (output)) - + print (f'Inputs = [{input_names}], Outputs = [{output_names}]') + print (f'Writing metadata to {output_meta.as_posix()}') + print (f'To convert use: \n `convert-to-uff {output}`') diff --git a/scripts/hsv_picker.py b/scripts/hsv_picker.py index a76dce379..267cdc6ec 100644 --- a/scripts/hsv_picker.py +++ b/scripts/hsv_picker.py @@ -1,5 +1,5 @@ # -# Python/opencv script to show an image and then mask it +# Python/opencv script to show an image and then mask it # using low and high HSV values chosen with trackbars # or sampled from a rectangular select. # - click on a pixel to show it's position, RGB and HSV values @@ -20,11 +20,11 @@ def nothing(x): pass -# +# # Text metrics # font = cv2.FONT_HERSHEY_SIMPLEX -line_height = 25 +line_height = 25 fontScale = 0.4 text_color = (0, 0, 0) text_lines = [] @@ -42,22 +42,22 @@ def show_pixel_values(image, x, y): colorsRGB = image[y,x] text.append(f"Pixel RGB = ({colorsRGB[0]}, {colorsRGB[1]}, {colorsRGB[2]})") - + colorsHSV = bgr_to_hsv(colorsRGB) text.append(f"Pixel HSV = ({colorsHSV[0]}, {colorsHSV[1]}, {colorsHSV[2]})") - + hsv_low, hsv_high = get_hsv_trackbars() if hsv_low is not None and hsv_high is not None: text.append(f"Mask HSV Low = ({hsv_low[0]}, {hsv_low[1]}, {hsv_low[2]})") text.append(f"Mask HSV High = ({hsv_high[0]}, {hsv_high[1]}, {hsv_high[2]})") - + return text def get_hsv_range(image, left, top, right, bottom): if image is None: return ((0, 0, 0), (179, 255, 255 )) - + min_pixel = None max_pixel = None width = abs(right - left) @@ -70,14 +70,14 @@ def get_hsv_range(image, left, top, right, bottom): right = left + width top = min(top, bottom) bottom = top + height - + for y in range(top, bottom): for x in range(left, right): pixel = bgr_to_hsv(image[y, x]) if pixel[0] > 0: # reject black noise pixels min_pixel = pixel if min_pixel is None else np.minimum(pixel, min_pixel) max_pixel = pixel if max_pixel is None else np.maximum(pixel, max_pixel) - + return (min_pixel, max_pixel) @@ -87,10 +87,10 @@ def get_hsv_range(image, left, top, right, bottom): # mouse callback function def mouse_callback(event, x, y, flags, param): global drag_rect, frame, text_lines - + if frame is None: return - + if event == cv2.EVENT_LBUTTONDOWN: #checks mouse left button down condition drag_rect = (x, y, x, y) text_lines = show_pixel_values(frame, x, y) @@ -140,7 +140,7 @@ def bgr_to_hsv(pixelRGB): """ Convert a single RGB pixel to HSV """ - imgRGB = np.uint8([[pixelRGB]]) + imgRGB = np.uint8([[pixelRGB]]) imgHSV = cv2.cvtColor(imgRGB, cv2.COLOR_BGR2HSV) pixelHSV = imgHSV[0][0] return pixelHSV @@ -156,7 +156,7 @@ def main(camera_index=0, width=640, height=480, file_image=None): cap = cv2.VideoCapture(camera_index) cap.set(cv2.CAP_PROP_FRAME_WIDTH, width) cap.set(cv2.CAP_PROP_FRAME_HEIGHT, height) - + cv2.namedWindow(window_name) # Starting with 100's to prevent error while masking @@ -179,15 +179,15 @@ def main(camera_index=0, width=640, height=480, file_image=None): frame = None if file_image is not None: frame = file_image.copy() - else: + else: _, frame = cap.read() if frame is None: continue - + # # mask the image using the current HSV value # - + #converting to HSV hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV) @@ -199,16 +199,16 @@ def main(camera_index=0, width=640, height=480, file_image=None): hsv_high = np.array(hsv_high) mask = cv2.inRange(hsv, hsv_low, hsv_high) image = cv2.bitwise_and(frame, frame, mask = mask) - + # draw drag rectangle if drag_rect is not None: top_left = (min(drag_rect[0], drag_rect[2]), min(drag_rect[1], drag_rect[3])) bottom_right = (max(drag_rect[0], drag_rect[2]), max(drag_rect[1], drag_rect[3])) - + # white rectangle with black outline image = cv2.rectangle(image, (top_left[0] - 1, top_left[1] - 1), (bottom_right[0] + 1, bottom_right[1] + 1), (0, 0, 0), 1) image = cv2.rectangle(image, top_left, bottom_right, (255, 255, 255), 1) - + # draw pixel value if text_lines: x = line_height @@ -232,15 +232,15 @@ def main(camera_index=0, width=640, height=480, file_image=None): print_hsv_trackbars() print_hsv_trackbars() - + if cap is not None: cap.release() cv2.destroyAllWindows() - + if __name__ == "__main__": import argparse - + parser = argparse.ArgumentParser() parser.add_argument("-c", "--camera", type=int, default=0, help = "index of camera if using multiple cameras") @@ -253,7 +253,7 @@ def main(camera_index=0, width=640, height=480, file_image=None): # Read arguments from command line args = parser.parse_args() - + image = None help = [] if args.file is not None: @@ -267,17 +267,17 @@ def main(camera_index=0, width=640, height=480, file_image=None): help.append("-wd/--width must be >= 160") if args.height < 120: help.append("-ht/--height must be >= 120") - + if len(help) > 0: parser.print_help() for h in help: print(" " + h) sys.exit(1) - + print("- click on a pixel to show it's position, RGB and HSV values") print("- select an area to sample low and high HSV value for an image mask OR") print("- adjust the trackbars to choose low and high HSV values for an image mask") print("- press Escape to reset the low and high hsv value") print("- press 'q' to quit") - + main(args.camera, args.width, args.height, image) diff --git a/scripts/multi_train.py b/scripts/multi_train.py index 3c4f68bed..73e8f145b 100755 --- a/scripts/multi_train.py +++ b/scripts/multi_train.py @@ -13,47 +13,48 @@ import uuid num_clients = 4 -model_file = "mtn_drv2.h5" #or any model in ~/mycar/models/ +model_file = "mtn_drv2.h5" # or any model in ~/mycar/models/ body_styles = ["donkey", "bare", "car01"] host = '127.0.0.1' procs = [] for i in range(num_clients): - conf_file = "client%d.py" % i - with open(conf_file, "wt") as outfile: - outfile.write('WEB_CONTROL_PORT = 888%d\n' % i) - outfile.write('WEB_INIT_MODE = "local"\n') - outfile.write('DONKEY_GYM = True\n') - outfile.write('DONKEY_GYM_ENV_NAME = "donkey-generated-track-v0"\n') - outfile.write('DONKEY_SIM_PATH = "remote"\n') - outfile.write('SIM_HOST = "%s"\n' % host) - iStyle = random.randint(0, len(body_styles) - 1) - body_style = body_styles[iStyle] - r = random.randint(0, 255) - g = random.randint(0, 255) - b = random.randint(0, 255) - outfile.write('GYM_CONF = { "body_style" : "%s", "body_rgb" : (%d, %d, %d), "car_name" : "ai%d", "font_size" : 100}\n' % (body_style, r, g, b, i+1)) - outfile.write('GYM_CONF["racer_name"] = "ai-%d"\n' % (i+1)) - outfile.write('GYM_CONF["country"] = "USA"\n') - outfile.write('GYM_CONF["bio"] = "I am an ai!"\n') - outfile.write('GYM_CONF["guid"] = "%d"\n' % i) - outfile.close() + conf_file = "client%d.py" % i + with open(conf_file, "wt") as outfile: + outfile.write('WEB_CONTROL_PORT = 888%d\n' % i) + outfile.write('WEB_INIT_MODE = "local"\n') + outfile.write('DONKEY_GYM = True\n') + outfile.write('DONKEY_GYM_ENV_NAME = "donkey-generated-track-v0"\n') + outfile.write('DONKEY_SIM_PATH = "remote"\n') + outfile.write(f'SIM_HOST = "{host}\"\n') + iStyle = random.randint(0, len(body_styles) - 1) + body_style = body_styles[iStyle] + r = random.randint(0, 255) + g = random.randint(0, 255) + b = random.randint(0, 255) + outfile.write('GYM_CONF = { "body_style" : "%s", "body_rgb" : (%d, %d, %d), "car_name" : "ai%d", "font_size" : 100}\n' % ( + body_style, r, g, b, i+1)) + outfile.write('GYM_CONF["racer_name"] = "ai-%d"\n' % (i+1)) + outfile.write('GYM_CONF["country"] = "USA"\n') + outfile.write('GYM_CONF["bio"] = "I am an ai!"\n') + outfile.write('GYM_CONF["guid"] = "%d"\n' % i) + outfile.close() - command = "python manage.py drive --model=models/%s --myconfig=%s" % (model_file, conf_file) - com_list = command.split(" ") - print(com_list) - proc = subprocess.Popen(com_list) - procs.append(proc) - time.sleep(2) + command = f"python manage.py drive --model=models/{model_file} --myconfig={conf_file}" + com_list = command.split(" ") + print(com_list) + proc = subprocess.Popen(com_list) + procs.append(proc) + time.sleep(2) print("running for 30 min...") try: - time.sleep(60 * 30) -except: - pass + time.sleep(60 * 30) +except Exception: + pass print("stopping ai") for proc in procs: - proc.kill() + proc.kill() print('done') diff --git a/scripts/pigpio_donkey.py b/scripts/pigpio_donkey.py index 13e3732bc..c661c9fe9 100755 --- a/scripts/pigpio_donkey.py +++ b/scripts/pigpio_donkey.py @@ -10,12 +10,13 @@ # sudo update && sudo apt install pigpio python3-pigpio& sudo systemctl start pigpiod ''' import os + +import pigpio + import donkeycar as dk from donkeycar.parts.controller import PS3JoystickController from donkeycar.parts.actuator import PWMSteering, PWMThrottle -import pigpio - class PiGPIO_PWM(): def __init__(self, pin, pgio, freq=75): self.pin = pin @@ -57,18 +58,16 @@ def run(self, pulse): steering_controller = PiGPIO_PWM(cfg.STEERING_CHANNEL, p) steering = PWMSteering(controller=steering_controller, - left_pulse=cfg.STEERING_LEFT_PWM, - right_pulse=cfg.STEERING_RIGHT_PWM) + left_pulse=cfg.STEERING_LEFT_PWM, + right_pulse=cfg.STEERING_RIGHT_PWM) throttle_controller = PiGPIO_PWM(cfg.THROTTLE_CHANNEL, p) throttle = PWMThrottle(controller=throttle_controller, - max_pulse=cfg.THROTTLE_FORWARD_PWM, - zero_pulse=cfg.THROTTLE_STOPPED_PWM, - min_pulse=cfg.THROTTLE_REVERSE_PWM) + max_pulse=cfg.THROTTLE_FORWARD_PWM, + zero_pulse=cfg.THROTTLE_STOPPED_PWM, + min_pulse=cfg.THROTTLE_REVERSE_PWM) V.add(steering, inputs=['angle']) V.add(throttle, inputs=['throttle']) V.start() - - diff --git a/scripts/profile.py b/scripts/profile.py index c6d48f3b7..20f86821f 100755 --- a/scripts/profile.py +++ b/scripts/profile.py @@ -4,7 +4,7 @@ Usage: profile.py (--model=) (--type=) - + Options: -h --help Show this screen. """ @@ -20,7 +20,7 @@ def profile(model_path, model_type): model_path = os.path.expanduser(model_path) model = dk.utils.get_model_by_type(model_type, cfg) model.load(model_path) - + h, w, ch = cfg.IMAGE_H, cfg.IMAGE_W, cfg.IMAGE_DEPTH # generate random array in the right shape in [0,1) diff --git a/scripts/profile_coral.py b/scripts/profile_coral.py index 8344e54dc..fa01c0cca 100755 --- a/scripts/profile_coral.py +++ b/scripts/profile_coral.py @@ -5,23 +5,23 @@ import numpy as np def main(): - parser = argparse.ArgumentParser() - parser.add_argument( - '--model', help='File path of Tflite model.', required=True) - parser.add_argument( - '--image', help='File path of the image to be recognized.', required=True) - args = parser.parse_args() - # Initialize engine. - engine = InferenceEngine(args.model) - # Run inference. - img = Image.open(args.image) - result = engine.Inference(np.array(img)) - print("inference result", result) + parser = argparse.ArgumentParser() + parser.add_argument( + '--model', help='File path of Tflite model.', required=True) + parser.add_argument( + '--image', help='File path of the image to be recognized.', required=True) + args = parser.parse_args() + # Initialize engine. + engine = InferenceEngine(args.model) + # Run inference. + img = Image.open(args.image) + result = engine.Inference(np.array(img)) + print("inference result", result) - timer = FPSTimer() - while True: - engine.Inference(np.array(img)) - timer.on_frame() + timer = FPSTimer() + while True: + engine.Inference(np.array(img)) + timer.on_frame() if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/scripts/remote_cam_view.py b/scripts/remote_cam_view.py index 1f6981874..d9f263225 100755 --- a/scripts/remote_cam_view.py +++ b/scripts/remote_cam_view.py @@ -25,14 +25,14 @@ args = docopt(__doc__) print(args) -V.add(MQTTValueSub(name="donkey/%s/camera" % args["--name"], broker=args["--broker"]), outputs=["jpg"]) -V.add(JpgToImgArr(), inputs=["jpg"], outputs=["img_arr"]) +V.add(MQTTValueSub(name=f"donkey/{args['--name']}/camera", broker=args["--broker"]), outputs=["jpg"]) +V.add(JpgToImgArr(), inputs=["jpg"], outputs=["img_arr"]) V.add(ImgBGR2RGB(), inputs=["img_arr"], outputs=["rgb"]) V.add(ImageScale(4.0), inputs=["rgb"], outputs=["lg_img"]) V.add(CvImageView(), inputs=["lg_img"]) V.add(ArrowKeyboardControls(), outputs=["control"]) -V.add(MQTTValuePub(name="donkey/%s/controls" % args["--name"]), inputs=["control"]) +V.add(MQTTValuePub(name=f"donkey/{args['--name']}/controls"), inputs=["control"]) record_path = args["--record"] if record_path is not None: @@ -40,16 +40,15 @@ class ImageSaver: def __init__(self, path): self.index = 0 self.path = path - + def run(self, img_arr): if img_arr is None: return dest_path = os.path.join(self.path, "img_%d.jpg" % self.index) self.index += 1 cv2.imwrite(dest_path, img_arr) - + V.add(ImageSaver(record_path), inputs=["rgb"]) V.start(rate_hz=20) - diff --git a/scripts/remote_cam_view_tcp.py b/scripts/remote_cam_view_tcp.py index 824065c20..152964b5d 100755 --- a/scripts/remote_cam_view_tcp.py +++ b/scripts/remote_cam_view_tcp.py @@ -7,7 +7,7 @@ Options: -h --help Show this screen. --record= If data should be recorded (locally) specify the path - + """ from docopt import docopt import donkeycar as dk @@ -32,14 +32,14 @@ class ImageSaver: def __init__(self, path): self.index = 0 self.path = path - + def run(self, img_arr): if img_arr is None: return dest_path = os.path.join(self.path, "img_%d.jpg" % self.index) self.index += 1 cv2.imwrite(dest_path, img_arr) - + V.add(ImageSaver(record_path), inputs=["rgb"]) - + V.start(rate_hz=20) diff --git a/scripts/salient_vis_listener.py b/scripts/salient_vis_listener.py index ff6d5b18f..4b8872fb7 100755 --- a/scripts/salient_vis_listener.py +++ b/scripts/salient_vis_listener.py @@ -35,11 +35,10 @@ model.load(model_path) V.add(TCPClientValue(name="camera", host=ip), outputs=["packet"]) -V.add(JpgToImgArr(), inputs=["packet"], outputs=["img"]) +V.add(JpgToImgArr(), inputs=["packet"], outputs=["img"]) V.add(ImgBGR2RGB(), inputs=["img"], outputs=["img"]) V.add(SalientVis(model), inputs=["img"], outputs=["img"]) V.add(ImageScale(4.0), inputs=["img"], outputs=["lg_img"]) V.add(CvImageView(), inputs=["lg_img"]) V.start(rate_hz=1) - diff --git a/scripts/tflite_convert.py b/scripts/tflite_convert.py index a688a3d92..8217bed03 100755 --- a/scripts/tflite_convert.py +++ b/scripts/tflite_convert.py @@ -14,6 +14,5 @@ args = docopt(__doc__) in_model = os.path.expanduser(args['--model']) -out_model = os.path.expanduser(args['--out']) +out_model = os.path.expanduser(args['--out']) keras_model_to_tflite(in_model, out_model) - diff --git a/scripts/tflite_profile.py b/scripts/tflite_profile.py index 30e7fa54a..62c373115 100755 --- a/scripts/tflite_profile.py +++ b/scripts/tflite_profile.py @@ -45,4 +45,3 @@ interpreter.set_tensor(input_details[0]['index'], input_data) interpreter.invoke() timer.on_frame() -