From 4379e63f259f943a8935e0e39427a16f5c57a973 Mon Sep 17 00:00:00 2001 From: Milan Medic Date: Mon, 19 Feb 2024 09:29:58 +0100 Subject: [PATCH] Revert "Adding changes to cython files to pass static analysis" This reverts commit 9a0eb733199abd9eef1eac3d024ef2760348d67c. --- common/params_pyx.pyx | 208 +++++++++---------- common/transformations/transformations.pxd | 105 +++++----- common/transformations/transformations.pyx | 18 +- selfdrive/boardd/boardd_api_impl.pyx | 37 ++-- selfdrive/modeld/models/commonmodel.pxd | 20 +- selfdrive/modeld/models/commonmodel_pyx.pxd | 8 +- selfdrive/modeld/models/commonmodel_pyx.pyx | 46 ++-- selfdrive/modeld/runners/runmodel.pxd | 16 +- selfdrive/modeld/runners/runmodel_pyx.pxd | 2 +- selfdrive/modeld/runners/runmodel_pyx.pyx | 55 +++-- selfdrive/modeld/runners/snpemodel.pxd | 4 +- selfdrive/modeld/runners/snpemodel_pyx.pyx | 4 +- selfdrive/modeld/runners/thneedmodel.pxd | 4 +- selfdrive/modeld/runners/thneedmodel_pyx.pyx | 4 +- 14 files changed, 258 insertions(+), 273 deletions(-) diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 2a067439fa..47d2075df2 100644 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -5,114 +5,114 @@ from libcpp.string cimport string from libcpp.vector cimport vector cdef extern from "common/params.h": - cpdef enum ParamKeyType: - PERSISTENT - CLEAR_ON_MANAGER_START - CLEAR_ON_ONROAD_TRANSITION - CLEAR_ON_OFFROAD_TRANSITION - DEVELOPMENT_ONLY - ALL - - cdef cppclass c_Params "Params": - c_Params(string) except + nogil - string get(string, bool) nogil - bool getBool(string, bool) nogil - int remove(string) nogil - int put(string, string) nogil - void putNonBlocking(string, string) nogil - void putBoolNonBlocking(string, bool) nogil - int putBool(string, bool) nogil - bool checkKey(string) nogil - string getParamPath(string) nogil - void clearAll(ParamKeyType) - vector[string] allKeys() + cpdef enum ParamKeyType: + PERSISTENT + CLEAR_ON_MANAGER_START + CLEAR_ON_ONROAD_TRANSITION + CLEAR_ON_OFFROAD_TRANSITION + DEVELOPMENT_ONLY + ALL + + cdef cppclass c_Params "Params": + c_Params(string) except + nogil + string get(string, bool) nogil + bool getBool(string, bool) nogil + int remove(string) nogil + int put(string, string) nogil + void putNonBlocking(string, string) nogil + void putBoolNonBlocking(string, bool) nogil + int putBool(string, bool) nogil + bool checkKey(string) nogil + string getParamPath(string) nogil + void clearAll(ParamKeyType) + vector[string] allKeys() def ensure_bytes(v): - return v.encode() if isinstance(v, str) else v - + return v.encode() if isinstance(v, str) else v; class UnknownKeyName(Exception): - pass - + pass cdef class Params: - cdef c_Params* p - - def __cinit__(self, d=""): - cdef string path = d.encode() - with nogil: - self.p = new c_Params(path) - - def __dealloc__(self): - del self.p - - def clear_all(self, tx_type=ParamKeyType.ALL): - self.p.clearAll(tx_type) - - def check_key(self, key): - key = ensure_bytes(key) - if not self.p.checkKey(key): - raise UnknownKeyName(key) - return key - - def get(self, key, bool block=False, encoding=None): - cdef string k = self.check_key(key) - cdef string val - with nogil: - val = self.p.get(k, block) - if val == b"": - if block: - # If we got no value while running in blocked mode - # it means we got an interrupt while waiting - raise KeyboardInterrupt - else: - return None - return val if encoding is None else val.decode(encoding) - - def get_bool(self, key, bool block=False): - cdef string k = self.check_key(key) - cdef bool r - with nogil: - r = self.p.getBool(k, block) - return r - - def put(self, key, dat): - """ - Warning: This function blocks until the param is written to disk! - In very rare cases this can take over a second, and your code will hang. - Use the put_nonblocking, put_bool_nonblocking in time sensitive code, but - in general try to avoid writing params as much as possible. - """ - cdef string k = self.check_key(key) - cdef string dat_bytes = ensure_bytes(dat) - with nogil: - self.p.put(k, dat_bytes) - - def put_bool(self, key, bool val): - cdef string k = self.check_key(key) - with nogil: - self.p.putBool(k, val) - - def put_nonblocking(self, key, dat): - cdef string k = self.check_key(key) - cdef string dat_bytes = ensure_bytes(dat) - with nogil: - self.p.putNonBlocking(k, dat_bytes) - - def put_bool_nonblocking(self, key, bool val): - cdef string k = self.check_key(key) - with nogil: - self.p.putBoolNonBlocking(k, val) - - def remove(self, key): - cdef string k = self.check_key(key) - with nogil: - self.p.remove(k) - - def get_param_path(self, key=""): - cdef string key_bytes = ensure_bytes(key) - return self.p.getParamPath(key_bytes).decode("utf-8") - - def all_keys(self): - return self.p.allKeys() + cdef c_Params* p + + def __cinit__(self, d=""): + cdef string path = d.encode() + with nogil: + self.p = new c_Params(path) + + def __dealloc__(self): + del self.p + + def clear_all(self, tx_type=ParamKeyType.ALL): + self.p.clearAll(tx_type) + + def check_key(self, key): + key = ensure_bytes(key) + if not self.p.checkKey(key): + raise UnknownKeyName(key) + return key + + def get(self, key, bool block=False, encoding=None): + cdef string k = self.check_key(key) + cdef string val + with nogil: + val = self.p.get(k, block) + + if val == b"": + if block: + # If we got no value while running in blocked mode + # it means we got an interrupt while waiting + raise KeyboardInterrupt + else: + return None + + return val if encoding is None else val.decode(encoding) + + def get_bool(self, key, bool block=False): + cdef string k = self.check_key(key) + cdef bool r + with nogil: + r = self.p.getBool(k, block) + return r + + def put(self, key, dat): + """ + Warning: This function blocks until the param is written to disk! + In very rare cases this can take over a second, and your code will hang. + Use the put_nonblocking, put_bool_nonblocking in time sensitive code, but + in general try to avoid writing params as much as possible. + """ + cdef string k = self.check_key(key) + cdef string dat_bytes = ensure_bytes(dat) + with nogil: + self.p.put(k, dat_bytes) + + def put_bool(self, key, bool val): + cdef string k = self.check_key(key) + with nogil: + self.p.putBool(k, val) + + def put_nonblocking(self, key, dat): + cdef string k = self.check_key(key) + cdef string dat_bytes = ensure_bytes(dat) + with nogil: + self.p.putNonBlocking(k, dat_bytes) + + def put_bool_nonblocking(self, key, bool val): + cdef string k = self.check_key(key) + with nogil: + self.p.putBoolNonBlocking(k, val) + + def remove(self, key): + cdef string k = self.check_key(key) + with nogil: + self.p.remove(k) + + def get_param_path(self, key=""): + cdef string key_bytes = ensure_bytes(key) + return self.p.getParamPath(key_bytes).decode("utf-8") + + def all_keys(self): + return self.p.allKeys() diff --git a/common/transformations/transformations.pxd b/common/transformations/transformations.pxd index 8e72bd0168..7af0098701 100644 --- a/common/transformations/transformations.pxd +++ b/common/transformations/transformations.pxd @@ -1,71 +1,72 @@ -# cython: language_level=3 +#cython: language_level=3 from libcpp cimport bool cdef extern from "orientation.cc": - pass + pass cdef extern from "orientation.hpp": - cdef cppclass Quaternion "Eigen::Quaterniond": - Quaternion() - Quaternion(double, double, double, double) - double w() - double x() - double y() - double z() + cdef cppclass Quaternion "Eigen::Quaterniond": + Quaternion() + Quaternion(double, double, double, double) + double w() + double x() + double y() + double z() - cdef cppclass Vector3 "Eigen::Vector3d": - Vector3() - Vector3(double, double, double) - double operator()(int) + cdef cppclass Vector3 "Eigen::Vector3d": + Vector3() + Vector3(double, double, double) + double operator()(int) - cdef cppclass Matrix3 "Eigen::Matrix3d": - Matrix3() - Matrix3(double*) - double operator()(int, int) + cdef cppclass Matrix3 "Eigen::Matrix3d": + Matrix3() + Matrix3(double*) - Quaternion euler2quat(Vector3) - Vector3 quat2euler(Quaternion) - Matrix3 quat2rot(Quaternion) - Quaternion rot2quat(Matrix3) - Vector3 rot2euler(Matrix3) - Matrix3 euler2rot(Vector3) - Matrix3 rot_matrix(double, double, double) - Vector3 ecef_euler_from_ned(ECEF, Vector3) - Vector3 ned_euler_from_ecef(ECEF, Vector3) + double operator()(int, int) + + Quaternion euler2quat(Vector3) + Vector3 quat2euler(Quaternion) + Matrix3 quat2rot(Quaternion) + Quaternion rot2quat(Matrix3) + Vector3 rot2euler(Matrix3) + Matrix3 euler2rot(Vector3) + Matrix3 rot_matrix(double, double, double) + Vector3 ecef_euler_from_ned(ECEF, Vector3) + Vector3 ned_euler_from_ecef(ECEF, Vector3) cdef extern from "coordinates.cc": - cdef struct ECEF: - double x - double y - double z + cdef struct ECEF: + double x + double y + double z - cdef struct NED: - double n - double e - double d + cdef struct NED: + double n + double e + double d - cdef struct Geodetic: - double lat - double lon - double alt - bool radians + cdef struct Geodetic: + double lat + double lon + double alt + bool radians - ECEF geodetic2ecef(Geodetic) - Geodetic ecef2geodetic(ECEF) + ECEF geodetic2ecef(Geodetic) + Geodetic ecef2geodetic(ECEF) - cdef cppclass LocalCoord_c "LocalCoord": - Matrix3 ned2ecef_matrix - Matrix3 ecef2ned_matrix + cdef cppclass LocalCoord_c "LocalCoord": + Matrix3 ned2ecef_matrix + Matrix3 ecef2ned_matrix - LocalCoord_c(Geodetic, ECEF) - LocalCoord_c(Geodetic) - LocalCoord_c(ECEF) + LocalCoord_c(Geodetic, ECEF) + LocalCoord_c(Geodetic) + LocalCoord_c(ECEF) - NED ecef2ned(ECEF) - ECEF ned2ecef(NED) - NED geodetic2ned(Geodetic) - Geodetic ned2geodetic(NED) + NED ecef2ned(ECEF) + ECEF ned2ecef(NED) + NED geodetic2ned(Geodetic) + Geodetic ned2geodetic(NED) cdef extern from "coordinates.hpp": - pass + pass diff --git a/common/transformations/transformations.pyx b/common/transformations/transformations.pyx index 0d870e4618..c5cb9e0056 100644 --- a/common/transformations/transformations.pyx +++ b/common/transformations/transformations.pyx @@ -17,6 +17,7 @@ from openpilot.common.transformations.transformations cimport ecef2geodetic as e from openpilot.common.transformations.transformations cimport LocalCoord_c +import cython import numpy as np cimport numpy as np @@ -33,14 +34,14 @@ cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): return Matrix3(m.data) cdef ECEF list2ecef(ecef): - cdef ECEF e + cdef ECEF e; e.x = ecef[0] e.y = ecef[1] e.z = ecef[2] return e cdef NED list2ned(ned): - cdef NED n + cdef NED n; n.n = ned[0] n.e = ned[1] n.d = ned[2] @@ -53,47 +54,39 @@ cdef Geodetic list2geodetic(geodetic): g.alt = geodetic[2] return g - def euler2quat_single(euler): cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) cdef Quaternion q = euler2quat_c(e) return [q.w(), q.x(), q.y(), q.z()] - def quat2euler_single(quat): cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) - cdef Vector3 e = quat2euler_c(q) + cdef Vector3 e = quat2euler_c(q); return [e(0), e(1), e(2)] - def quat2rot_single(quat): cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) cdef Matrix3 r = quat2rot_c(q) return matrix2numpy(r) - def rot2quat_single(rot): cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) cdef Quaternion q = rot2quat_c(r) return [q.w(), q.x(), q.y(), q.z()] - def euler2rot_single(euler): cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) cdef Matrix3 r = euler2rot_c(e) return matrix2numpy(r) - def rot2euler_single(rot): cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) cdef Vector3 e = rot2euler_c(r) return [e(0), e(1), e(2)] - def rot_matrix(roll, pitch, yaw): return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) - def ecef_euler_from_ned_single(ecef_init, ned_pose): cdef ECEF init = list2ecef(ecef_init) cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) @@ -101,7 +94,6 @@ def ecef_euler_from_ned_single(ecef_init, ned_pose): cdef Vector3 e = ecef_euler_from_ned_c(init, pose) return [e(0), e(1), e(2)] - def ned_euler_from_ecef_single(ecef_init, ecef_pose): cdef ECEF init = list2ecef(ecef_init) cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) @@ -109,13 +101,11 @@ def ned_euler_from_ecef_single(ecef_init, ecef_pose): cdef Vector3 e = ned_euler_from_ecef_c(init, pose) return [e(0), e(1), e(2)] - def geodetic2ecef_single(geodetic): cdef Geodetic g = list2geodetic(geodetic) cdef ECEF e = geodetic2ecef_c(g) return [e.x, e.y, e.z] - def ecef2geodetic_single(ecef): cdef ECEF e = list2ecef(ecef) cdef Geodetic g = ecef2geodetic_c(e) diff --git a/selfdrive/boardd/boardd_api_impl.pyx b/selfdrive/boardd/boardd_api_impl.pyx index 7ccd6abb75..6a552bb447 100644 --- a/selfdrive/boardd/boardd_api_impl.pyx +++ b/selfdrive/boardd/boardd_api_impl.pyx @@ -5,27 +5,26 @@ from libcpp.string cimport string from libcpp cimport bool cdef extern from "panda.h": - cdef struct can_frame: - long address - string dat - long busTime - long src + cdef struct can_frame: + long address + string dat + long busTime + long src cdef extern from "can_list_to_can_capnp.cc": - void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) - + void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): - cdef vector[can_frame] can_list - can_list.reserve(len(can_msgs)) + cdef vector[can_frame] can_list + can_list.reserve(len(can_msgs)) - cdef can_frame f - for can_msg in can_msgs: - f.address = can_msg[0] - f.busTime = can_msg[1] - f.dat = can_msg[2] - f.src = can_msg[3] - can_list.push_back(f) - cdef string out - can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) - return out + cdef can_frame f + for can_msg in can_msgs: + f.address = can_msg[0] + f.busTime = can_msg[1] + f.dat = can_msg[2] + f.src = can_msg[3] + can_list.push_back(f) + cdef string out + can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) + return out diff --git a/selfdrive/modeld/models/commonmodel.pxd b/selfdrive/modeld/models/commonmodel.pxd index da186982c5..57b79aeafb 100644 --- a/selfdrive/modeld/models/commonmodel.pxd +++ b/selfdrive/modeld/models/commonmodel.pxd @@ -3,18 +3,18 @@ from cereal.visionipc.visionipc cimport cl_device_id, cl_context, cl_mem cdef extern from "common/mat.h": - cdef struct mat3: - float v[9] + cdef struct mat3: + float v[9] cdef extern from "common/clutil.h": - cdef unsigned long CL_DEVICE_TYPE_DEFAULT - cl_device_id cl_get_device_id(unsigned long) - cl_context cl_create_context(cl_device_id) + cdef unsigned long CL_DEVICE_TYPE_DEFAULT + cl_device_id cl_get_device_id(unsigned long) + cl_context cl_create_context(cl_device_id) cdef extern from "selfdrive/modeld/models/commonmodel.h": - float sigmoid(float) + float sigmoid(float) - cppclass ModelFrame: - int buf_size - ModelFrame(cl_device_id, cl_context) - float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) + cppclass ModelFrame: + int buf_size + ModelFrame(cl_device_id, cl_context) + float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) diff --git a/selfdrive/modeld/models/commonmodel_pyx.pxd b/selfdrive/modeld/models/commonmodel_pyx.pxd index 33fe10eb5c..21c0716de4 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pxd +++ b/selfdrive/modeld/models/commonmodel_pyx.pxd @@ -4,10 +4,10 @@ from cereal.visionipc.visionipc cimport cl_mem from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext cdef class CLContext(BaseCLContext): - pass + pass cdef class CLMem: - cdef cl_mem * mem + cdef cl_mem * mem; - @staticmethod - cdef create(void*) + @staticmethod + cdef create(void*) diff --git a/selfdrive/modeld/models/commonmodel_pyx.pyx b/selfdrive/modeld/models/commonmodel_pyx.pyx index f84b3f1b24..e33d301aff 100644 --- a/selfdrive/modeld/models/commonmodel_pyx.pyx +++ b/selfdrive/modeld/models/commonmodel_pyx.pyx @@ -10,38 +10,34 @@ from cereal.visionipc.visionipc_pyx cimport VisionBuf, CLContext as BaseCLContex from .commonmodel cimport CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame - def sigmoid(x): - return cppSigmoid(x) - + return cppSigmoid(x) cdef class CLContext(BaseCLContext): - def __cinit__(self): - self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) - self.context = cl_create_context(self.device_id) - + def __cinit__(self): + self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) + self.context = cl_create_context(self.device_id) cdef class CLMem: - @staticmethod - cdef create(void * cmem): - mem = CLMem() - mem.mem = cmem - return mem - + @staticmethod + cdef create(void * cmem): + mem = CLMem() + mem.mem = cmem + return mem cdef class ModelFrame: - cdef cppModelFrame * frame + cdef cppModelFrame * frame - def __cinit__(self, CLContext context): - self.frame = new cppModelFrame(context.device_id, context.context) + def __cinit__(self, CLContext context): + self.frame = new cppModelFrame(context.device_id, context.context) - def __dealloc__(self): - del self.frame + def __dealloc__(self): + del self.frame - def prepare(self, VisionBuf buf, float[:] projection, CLMem output): - cdef mat3 cprojection - memcpy(cprojection.v, &projection[0], 9*sizeof(float)) - cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) - if not data: - return None - return np.asarray( data) + def prepare(self, VisionBuf buf, float[:] projection, CLMem output): + cdef mat3 cprojection + memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) + if not data: + return None + return np.asarray( data) diff --git a/selfdrive/modeld/runners/runmodel.pxd b/selfdrive/modeld/runners/runmodel.pxd index 6e24101814..01b2a9cf2c 100644 --- a/selfdrive/modeld/runners/runmodel.pxd +++ b/selfdrive/modeld/runners/runmodel.pxd @@ -3,12 +3,12 @@ from libcpp.string cimport string cdef extern from "selfdrive/modeld/runners/runmodel.h": - cdef int USE_CPU_RUNTIME - cdef int USE_GPU_RUNTIME - cdef int USE_DSP_RUNTIME + cdef int USE_CPU_RUNTIME + cdef int USE_GPU_RUNTIME + cdef int USE_DSP_RUNTIME - cdef cppclass RunModel: - void addInput(string, float*, int) - void setInputBuffer(string, float*, int) - void * getCLBuffer(string) - void execute() + cdef cppclass RunModel: + void addInput(string, float*, int) + void setInputBuffer(string, float*, int) + void * getCLBuffer(string) + void execute() diff --git a/selfdrive/modeld/runners/runmodel_pyx.pxd b/selfdrive/modeld/runners/runmodel_pyx.pxd index 285b72719a..b6ede7cf37 100644 --- a/selfdrive/modeld/runners/runmodel_pyx.pxd +++ b/selfdrive/modeld/runners/runmodel_pyx.pxd @@ -3,4 +3,4 @@ from .runmodel cimport RunModel as cppRunModel cdef class RunModel: - cdef cppRunModel * model + cdef cppRunModel * model diff --git a/selfdrive/modeld/runners/runmodel_pyx.pyx b/selfdrive/modeld/runners/runmodel_pyx.pyx index 0b9255bc46..cdc62a79be 100644 --- a/selfdrive/modeld/runners/runmodel_pyx.pyx +++ b/selfdrive/modeld/runners/runmodel_pyx.pyx @@ -2,38 +2,37 @@ # cython: c_string_encoding=ascii from libcpp.string cimport string +from libc.string cimport memcpy from .runmodel cimport USE_CPU_RUNTIME, USE_GPU_RUNTIME, USE_DSP_RUNTIME from selfdrive.modeld.models.commonmodel_pyx cimport CLMem - class Runtime: - CPU = USE_CPU_RUNTIME - GPU = USE_GPU_RUNTIME - DSP = USE_DSP_RUNTIME - + CPU = USE_CPU_RUNTIME + GPU = USE_GPU_RUNTIME + DSP = USE_DSP_RUNTIME cdef class RunModel: - def __dealloc__(self): - del self.model - - def addInput(self, string name, float[:] buffer): - if buffer is not None: - self.model.addInput(name, &buffer[0], len(buffer)) - else: - self.model.addInput(name, NULL, 0) - - def setInputBuffer(self, string name, float[:] buffer): - if buffer is not None: - self.model.setInputBuffer(name, &buffer[0], len(buffer)) - else: - self.model.setInputBuffer(name, NULL, 0) - - def getCLBuffer(self, string name): - cdef void * cl_buf = self.model.getCLBuffer(name) - if not cl_buf: - return None - return CLMem.create(cl_buf) - - def execute(self): - self.model.execute() + def __dealloc__(self): + del self.model + + def addInput(self, string name, float[:] buffer): + if buffer is not None: + self.model.addInput(name, &buffer[0], len(buffer)) + else: + self.model.addInput(name, NULL, 0) + + def setInputBuffer(self, string name, float[:] buffer): + if buffer is not None: + self.model.setInputBuffer(name, &buffer[0], len(buffer)) + else: + self.model.setInputBuffer(name, NULL, 0) + + def getCLBuffer(self, string name): + cdef void * cl_buf = self.model.getCLBuffer(name) + if not cl_buf: + return None + return CLMem.create(cl_buf) + + def execute(self): + self.model.execute() diff --git a/selfdrive/modeld/runners/snpemodel.pxd b/selfdrive/modeld/runners/snpemodel.pxd index c6a3dfbf9f..1f928da332 100644 --- a/selfdrive/modeld/runners/snpemodel.pxd +++ b/selfdrive/modeld/runners/snpemodel.pxd @@ -5,5 +5,5 @@ from libcpp.string cimport string from cereal.visionipc.visionipc cimport cl_context cdef extern from "selfdrive/modeld/runners/snpemodel.h": - cdef cppclass SNPEModel: - SNPEModel(string, float*, size_t, int, bool, cl_context) + cdef cppclass SNPEModel: + SNPEModel(string, float*, size_t, int, bool, cl_context) diff --git a/selfdrive/modeld/runners/snpemodel_pyx.pyx b/selfdrive/modeld/runners/snpemodel_pyx.pyx index ee1462ccfa..c3b2b7e9bd 100644 --- a/selfdrive/modeld/runners/snpemodel_pyx.pyx +++ b/selfdrive/modeld/runners/snpemodel_pyx.pyx @@ -13,5 +13,5 @@ from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel os.environ['ADSP_LIBRARY_PATH'] = "/data/pythonpath/third_party/snpe/dsp/" cdef class SNPEModel(RunModel): - def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): - self.model = new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) + def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): + self.model = new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) diff --git a/selfdrive/modeld/runners/thneedmodel.pxd b/selfdrive/modeld/runners/thneedmodel.pxd index ae908e16b7..90af972865 100644 --- a/selfdrive/modeld/runners/thneedmodel.pxd +++ b/selfdrive/modeld/runners/thneedmodel.pxd @@ -5,5 +5,5 @@ from libcpp.string cimport string from cereal.visionipc.visionipc cimport cl_context cdef extern from "selfdrive/modeld/runners/thneedmodel.h": - cdef cppclass ThneedModel: - ThneedModel(string, float*, size_t, int, bool, cl_context) + cdef cppclass ThneedModel: + ThneedModel(string, float*, size_t, int, bool, cl_context) diff --git a/selfdrive/modeld/runners/thneedmodel_pyx.pyx b/selfdrive/modeld/runners/thneedmodel_pyx.pyx index 17af14cd7c..53487afa1b 100644 --- a/selfdrive/modeld/runners/thneedmodel_pyx.pyx +++ b/selfdrive/modeld/runners/thneedmodel_pyx.pyx @@ -10,5 +10,5 @@ from selfdrive.modeld.runners.runmodel_pyx cimport RunModel from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel cdef class ThneedModel(RunModel): - def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): - self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) + def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): + self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context)