Adding changes to cython files to pass static analysis

pull/31491/head
Milan Medic 1 year ago
parent 52d3ea22f4
commit 9a0eb73319
  1. 208
      common/params_pyx.pyx
  2. 105
      common/transformations/transformations.pxd
  3. 18
      common/transformations/transformations.pyx
  4. 37
      selfdrive/boardd/boardd_api_impl.pyx
  5. 20
      selfdrive/modeld/models/commonmodel.pxd
  6. 8
      selfdrive/modeld/models/commonmodel_pyx.pxd
  7. 46
      selfdrive/modeld/models/commonmodel_pyx.pyx
  8. 16
      selfdrive/modeld/runners/runmodel.pxd
  9. 2
      selfdrive/modeld/runners/runmodel_pyx.pxd
  10. 55
      selfdrive/modeld/runners/runmodel_pyx.pyx
  11. 4
      selfdrive/modeld/runners/snpemodel.pxd
  12. 4
      selfdrive/modeld/runners/snpemodel_pyx.pyx
  13. 4
      selfdrive/modeld/runners/thneedmodel.pxd
  14. 4
      selfdrive/modeld/runners/thneedmodel_pyx.pyx

@ -5,114 +5,114 @@ from libcpp.string cimport string
from libcpp.vector cimport vector from libcpp.vector cimport vector
cdef extern from "common/params.h": cdef extern from "common/params.h":
cpdef enum ParamKeyType: cpdef enum ParamKeyType:
PERSISTENT PERSISTENT
CLEAR_ON_MANAGER_START CLEAR_ON_MANAGER_START
CLEAR_ON_ONROAD_TRANSITION CLEAR_ON_ONROAD_TRANSITION
CLEAR_ON_OFFROAD_TRANSITION CLEAR_ON_OFFROAD_TRANSITION
DEVELOPMENT_ONLY DEVELOPMENT_ONLY
ALL ALL
cdef cppclass c_Params "Params": cdef cppclass c_Params "Params":
c_Params(string) except + nogil c_Params(string) except + nogil
string get(string, bool) nogil string get(string, bool) nogil
bool getBool(string, bool) nogil bool getBool(string, bool) nogil
int remove(string) nogil int remove(string) nogil
int put(string, string) nogil int put(string, string) nogil
void putNonBlocking(string, string) nogil void putNonBlocking(string, string) nogil
void putBoolNonBlocking(string, bool) nogil void putBoolNonBlocking(string, bool) nogil
int putBool(string, bool) nogil int putBool(string, bool) nogil
bool checkKey(string) nogil bool checkKey(string) nogil
string getParamPath(string) nogil string getParamPath(string) nogil
void clearAll(ParamKeyType) void clearAll(ParamKeyType)
vector[string] allKeys() vector[string] allKeys()
def ensure_bytes(v): 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): class UnknownKeyName(Exception):
pass pass
cdef class Params: cdef class Params:
cdef c_Params* p cdef c_Params* p
def __cinit__(self, d=""): def __cinit__(self, d=""):
cdef string path = <string>d.encode() cdef string path = <string>d.encode()
with nogil: with nogil:
self.p = new c_Params(path) self.p = new c_Params(path)
def __dealloc__(self): def __dealloc__(self):
del self.p del self.p
def clear_all(self, tx_type=ParamKeyType.ALL): def clear_all(self, tx_type=ParamKeyType.ALL):
self.p.clearAll(tx_type) self.p.clearAll(tx_type)
def check_key(self, key): def check_key(self, key):
key = ensure_bytes(key) key = ensure_bytes(key)
if not self.p.checkKey(key): if not self.p.checkKey(key):
raise UnknownKeyName(key) raise UnknownKeyName(key)
return key return key
def get(self, key, bool block=False, encoding=None): def get(self, key, bool block=False, encoding=None):
cdef string k = self.check_key(key) cdef string k = self.check_key(key)
cdef string val cdef string val
with nogil: with nogil:
val = self.p.get(k, block) val = self.p.get(k, block)
if val == b"":
if val == b"": if block:
if block: # If we got no value while running in blocked mode
# If we got no value while running in blocked mode # it means we got an interrupt while waiting
# it means we got an interrupt while waiting raise KeyboardInterrupt
raise KeyboardInterrupt else:
else: return None
return None return val if encoding is None else val.decode(encoding)
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)
def get_bool(self, key, bool block=False): cdef bool r
cdef string k = self.check_key(key) with nogil:
cdef bool r r = self.p.getBool(k, block)
with nogil: return r
r = self.p.getBool(k, block)
return r def put(self, key, dat):
"""
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.
Warning: This function blocks until the param is written to disk! Use the put_nonblocking, put_bool_nonblocking in time sensitive code, but
In very rare cases this can take over a second, and your code will hang. in general try to avoid writing params as much as possible.
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)
cdef string k = self.check_key(key) with nogil:
cdef string dat_bytes = ensure_bytes(dat) self.p.put(k, dat_bytes)
with nogil:
self.p.put(k, dat_bytes) def put_bool(self, key, bool val):
cdef string k = self.check_key(key)
def put_bool(self, key, bool val): with nogil:
cdef string k = self.check_key(key) self.p.putBool(k, val)
with nogil:
self.p.putBool(k, val) def put_nonblocking(self, key, dat):
cdef string k = self.check_key(key)
def put_nonblocking(self, key, dat): cdef string dat_bytes = ensure_bytes(dat)
cdef string k = self.check_key(key) with nogil:
cdef string dat_bytes = ensure_bytes(dat) self.p.putNonBlocking(k, dat_bytes)
with nogil:
self.p.putNonBlocking(k, dat_bytes) def put_bool_nonblocking(self, key, bool val):
cdef string k = self.check_key(key)
def put_bool_nonblocking(self, key, bool val): with nogil:
cdef string k = self.check_key(key) self.p.putBoolNonBlocking(k, val)
with nogil:
self.p.putBoolNonBlocking(k, val) def remove(self, key):
cdef string k = self.check_key(key)
def remove(self, key): with nogil:
cdef string k = self.check_key(key) self.p.remove(k)
with nogil:
self.p.remove(k) def get_param_path(self, key=""):
cdef string key_bytes = ensure_bytes(key)
def get_param_path(self, key=""): return self.p.getParamPath(key_bytes).decode("utf-8")
cdef string key_bytes = ensure_bytes(key)
return self.p.getParamPath(key_bytes).decode("utf-8") def all_keys(self):
return self.p.allKeys()
def all_keys(self):
return self.p.allKeys()

@ -1,72 +1,71 @@
#cython: language_level=3 # cython: language_level=3
from libcpp cimport bool from libcpp cimport bool
cdef extern from "orientation.cc": cdef extern from "orientation.cc":
pass pass
cdef extern from "orientation.hpp": cdef extern from "orientation.hpp":
cdef cppclass Quaternion "Eigen::Quaterniond": cdef cppclass Quaternion "Eigen::Quaterniond":
Quaternion() Quaternion()
Quaternion(double, double, double, double) Quaternion(double, double, double, double)
double w() double w()
double x() double x()
double y() double y()
double z() double z()
cdef cppclass Vector3 "Eigen::Vector3d": cdef cppclass Vector3 "Eigen::Vector3d":
Vector3() Vector3()
Vector3(double, double, double) Vector3(double, double, double)
double operator()(int) double operator()(int)
cdef cppclass Matrix3 "Eigen::Matrix3d": cdef cppclass Matrix3 "Eigen::Matrix3d":
Matrix3() Matrix3()
Matrix3(double*) Matrix3(double*)
double operator()(int, int)
double operator()(int, int) Quaternion euler2quat(Vector3)
Vector3 quat2euler(Quaternion)
Quaternion euler2quat(Vector3) Matrix3 quat2rot(Quaternion)
Vector3 quat2euler(Quaternion) Quaternion rot2quat(Matrix3)
Matrix3 quat2rot(Quaternion) Vector3 rot2euler(Matrix3)
Quaternion rot2quat(Matrix3) Matrix3 euler2rot(Vector3)
Vector3 rot2euler(Matrix3) Matrix3 rot_matrix(double, double, double)
Matrix3 euler2rot(Vector3) Vector3 ecef_euler_from_ned(ECEF, Vector3)
Matrix3 rot_matrix(double, double, double) Vector3 ned_euler_from_ecef(ECEF, Vector3)
Vector3 ecef_euler_from_ned(ECEF, Vector3)
Vector3 ned_euler_from_ecef(ECEF, Vector3)
cdef extern from "coordinates.cc": cdef extern from "coordinates.cc":
cdef struct ECEF: cdef struct ECEF:
double x double x
double y double y
double z double z
cdef struct NED: cdef struct NED:
double n double n
double e double e
double d double d
cdef struct Geodetic: cdef struct Geodetic:
double lat double lat
double lon double lon
double alt double alt
bool radians bool radians
ECEF geodetic2ecef(Geodetic) ECEF geodetic2ecef(Geodetic)
Geodetic ecef2geodetic(ECEF) Geodetic ecef2geodetic(ECEF)
cdef cppclass LocalCoord_c "LocalCoord": cdef cppclass LocalCoord_c "LocalCoord":
Matrix3 ned2ecef_matrix Matrix3 ned2ecef_matrix
Matrix3 ecef2ned_matrix Matrix3 ecef2ned_matrix
LocalCoord_c(Geodetic, ECEF) LocalCoord_c(Geodetic, ECEF)
LocalCoord_c(Geodetic) LocalCoord_c(Geodetic)
LocalCoord_c(ECEF) LocalCoord_c(ECEF)
NED ecef2ned(ECEF) NED ecef2ned(ECEF)
ECEF ned2ecef(NED) ECEF ned2ecef(NED)
NED geodetic2ned(Geodetic) NED geodetic2ned(Geodetic)
Geodetic ned2geodetic(NED) Geodetic ned2geodetic(NED)
cdef extern from "coordinates.hpp": cdef extern from "coordinates.hpp":
pass pass

@ -17,7 +17,6 @@ from openpilot.common.transformations.transformations cimport ecef2geodetic as e
from openpilot.common.transformations.transformations cimport LocalCoord_c from openpilot.common.transformations.transformations cimport LocalCoord_c
import cython
import numpy as np import numpy as np
cimport numpy as np cimport numpy as np
@ -34,14 +33,14 @@ cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m):
return Matrix3(<double*>m.data) return Matrix3(<double*>m.data)
cdef ECEF list2ecef(ecef): cdef ECEF list2ecef(ecef):
cdef ECEF e; cdef ECEF e
e.x = ecef[0] e.x = ecef[0]
e.y = ecef[1] e.y = ecef[1]
e.z = ecef[2] e.z = ecef[2]
return e return e
cdef NED list2ned(ned): cdef NED list2ned(ned):
cdef NED n; cdef NED n
n.n = ned[0] n.n = ned[0]
n.e = ned[1] n.e = ned[1]
n.d = ned[2] n.d = ned[2]
@ -54,39 +53,47 @@ cdef Geodetic list2geodetic(geodetic):
g.alt = geodetic[2] g.alt = geodetic[2]
return g return g
def euler2quat_single(euler): def euler2quat_single(euler):
cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) cdef Vector3 e = Vector3(euler[0], euler[1], euler[2])
cdef Quaternion q = euler2quat_c(e) cdef Quaternion q = euler2quat_c(e)
return [q.w(), q.x(), q.y(), q.z()] return [q.w(), q.x(), q.y(), q.z()]
def quat2euler_single(quat): def quat2euler_single(quat):
cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) 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)] return [e(0), e(1), e(2)]
def quat2rot_single(quat): def quat2rot_single(quat):
cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3])
cdef Matrix3 r = quat2rot_c(q) cdef Matrix3 r = quat2rot_c(q)
return matrix2numpy(r) return matrix2numpy(r)
def rot2quat_single(rot): def rot2quat_single(rot):
cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double))
cdef Quaternion q = rot2quat_c(r) cdef Quaternion q = rot2quat_c(r)
return [q.w(), q.x(), q.y(), q.z()] return [q.w(), q.x(), q.y(), q.z()]
def euler2rot_single(euler): def euler2rot_single(euler):
cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) cdef Vector3 e = Vector3(euler[0], euler[1], euler[2])
cdef Matrix3 r = euler2rot_c(e) cdef Matrix3 r = euler2rot_c(e)
return matrix2numpy(r) return matrix2numpy(r)
def rot2euler_single(rot): def rot2euler_single(rot):
cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double))
cdef Vector3 e = rot2euler_c(r) cdef Vector3 e = rot2euler_c(r)
return [e(0), e(1), e(2)] return [e(0), e(1), e(2)]
def rot_matrix(roll, pitch, yaw): def rot_matrix(roll, pitch, yaw):
return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) return matrix2numpy(rot_matrix_c(roll, pitch, yaw))
def ecef_euler_from_ned_single(ecef_init, ned_pose): def ecef_euler_from_ned_single(ecef_init, ned_pose):
cdef ECEF init = list2ecef(ecef_init) cdef ECEF init = list2ecef(ecef_init)
cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2])
@ -94,6 +101,7 @@ def ecef_euler_from_ned_single(ecef_init, ned_pose):
cdef Vector3 e = ecef_euler_from_ned_c(init, pose) cdef Vector3 e = ecef_euler_from_ned_c(init, pose)
return [e(0), e(1), e(2)] return [e(0), e(1), e(2)]
def ned_euler_from_ecef_single(ecef_init, ecef_pose): def ned_euler_from_ecef_single(ecef_init, ecef_pose):
cdef ECEF init = list2ecef(ecef_init) cdef ECEF init = list2ecef(ecef_init)
cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2])
@ -101,11 +109,13 @@ def ned_euler_from_ecef_single(ecef_init, ecef_pose):
cdef Vector3 e = ned_euler_from_ecef_c(init, pose) cdef Vector3 e = ned_euler_from_ecef_c(init, pose)
return [e(0), e(1), e(2)] return [e(0), e(1), e(2)]
def geodetic2ecef_single(geodetic): def geodetic2ecef_single(geodetic):
cdef Geodetic g = list2geodetic(geodetic) cdef Geodetic g = list2geodetic(geodetic)
cdef ECEF e = geodetic2ecef_c(g) cdef ECEF e = geodetic2ecef_c(g)
return [e.x, e.y, e.z] return [e.x, e.y, e.z]
def ecef2geodetic_single(ecef): def ecef2geodetic_single(ecef):
cdef ECEF e = list2ecef(ecef) cdef ECEF e = list2ecef(ecef)
cdef Geodetic g = ecef2geodetic_c(e) cdef Geodetic g = ecef2geodetic_c(e)

@ -5,26 +5,27 @@ from libcpp.string cimport string
from libcpp cimport bool from libcpp cimport bool
cdef extern from "panda.h": cdef extern from "panda.h":
cdef struct can_frame: cdef struct can_frame:
long address long address
string dat string dat
long busTime long busTime
long src long src
cdef extern from "can_list_to_can_capnp.cc": 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): def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True):
cdef vector[can_frame] can_list cdef vector[can_frame] can_list
can_list.reserve(len(can_msgs)) can_list.reserve(len(can_msgs))
cdef can_frame f cdef can_frame f
for can_msg in can_msgs: for can_msg in can_msgs:
f.address = can_msg[0] f.address = can_msg[0]
f.busTime = can_msg[1] f.busTime = can_msg[1]
f.dat = can_msg[2] f.dat = can_msg[2]
f.src = can_msg[3] f.src = can_msg[3]
can_list.push_back(f) can_list.push_back(f)
cdef string out cdef string out
can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid)
return out return out

@ -3,18 +3,18 @@
from cereal.visionipc.visionipc cimport cl_device_id, cl_context, cl_mem from cereal.visionipc.visionipc cimport cl_device_id, cl_context, cl_mem
cdef extern from "common/mat.h": cdef extern from "common/mat.h":
cdef struct mat3: cdef struct mat3:
float v[9] float v[9]
cdef extern from "common/clutil.h": cdef extern from "common/clutil.h":
cdef unsigned long CL_DEVICE_TYPE_DEFAULT cdef unsigned long CL_DEVICE_TYPE_DEFAULT
cl_device_id cl_get_device_id(unsigned long) cl_device_id cl_get_device_id(unsigned long)
cl_context cl_create_context(cl_device_id) cl_context cl_create_context(cl_device_id)
cdef extern from "selfdrive/modeld/models/commonmodel.h": cdef extern from "selfdrive/modeld/models/commonmodel.h":
float sigmoid(float) float sigmoid(float)
cppclass ModelFrame: cppclass ModelFrame:
int buf_size int buf_size
ModelFrame(cl_device_id, cl_context) ModelFrame(cl_device_id, cl_context)
float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*) float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*)

@ -4,10 +4,10 @@ from cereal.visionipc.visionipc cimport cl_mem
from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext
cdef class CLContext(BaseCLContext): cdef class CLContext(BaseCLContext):
pass pass
cdef class CLMem: cdef class CLMem:
cdef cl_mem * mem; cdef cl_mem * mem
@staticmethod @staticmethod
cdef create(void*) cdef create(void*)

@ -10,34 +10,38 @@ 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 CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context
from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame
def sigmoid(x): def sigmoid(x):
return cppSigmoid(x) return cppSigmoid(x)
cdef class CLContext(BaseCLContext): cdef class CLContext(BaseCLContext):
def __cinit__(self): def __cinit__(self):
self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT)
self.context = cl_create_context(self.device_id) self.context = cl_create_context(self.device_id)
cdef class CLMem: cdef class CLMem:
@staticmethod @staticmethod
cdef create(void * cmem): cdef create(void * cmem):
mem = CLMem() mem = CLMem()
mem.mem = <cl_mem*> cmem mem.mem = <cl_mem*> cmem
return mem return mem
cdef class ModelFrame: cdef class ModelFrame:
cdef cppModelFrame * frame cdef cppModelFrame * frame
def __cinit__(self, CLContext context): def __cinit__(self, CLContext context):
self.frame = new cppModelFrame(context.device_id, context.context) self.frame = new cppModelFrame(context.device_id, context.context)
def __dealloc__(self): def __dealloc__(self):
del self.frame del self.frame
def prepare(self, VisionBuf buf, float[:] projection, CLMem output): def prepare(self, VisionBuf buf, float[:] projection, CLMem output):
cdef mat3 cprojection cdef mat3 cprojection
memcpy(cprojection.v, &projection[0], 9*sizeof(float)) 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) 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: if not data:
return None return None
return np.asarray(<cnp.float32_t[:self.frame.buf_size]> data) return np.asarray(<cnp.float32_t[:self.frame.buf_size]> data)

@ -3,12 +3,12 @@
from libcpp.string cimport string from libcpp.string cimport string
cdef extern from "selfdrive/modeld/runners/runmodel.h": cdef extern from "selfdrive/modeld/runners/runmodel.h":
cdef int USE_CPU_RUNTIME cdef int USE_CPU_RUNTIME
cdef int USE_GPU_RUNTIME cdef int USE_GPU_RUNTIME
cdef int USE_DSP_RUNTIME cdef int USE_DSP_RUNTIME
cdef cppclass RunModel: cdef cppclass RunModel:
void addInput(string, float*, int) void addInput(string, float*, int)
void setInputBuffer(string, float*, int) void setInputBuffer(string, float*, int)
void * getCLBuffer(string) void * getCLBuffer(string)
void execute() void execute()

@ -3,4 +3,4 @@
from .runmodel cimport RunModel as cppRunModel from .runmodel cimport RunModel as cppRunModel
cdef class RunModel: cdef class RunModel:
cdef cppRunModel * model cdef cppRunModel * model

@ -2,37 +2,38 @@
# cython: c_string_encoding=ascii # cython: c_string_encoding=ascii
from libcpp.string cimport string from libcpp.string cimport string
from libc.string cimport memcpy
from .runmodel cimport USE_CPU_RUNTIME, USE_GPU_RUNTIME, USE_DSP_RUNTIME from .runmodel cimport USE_CPU_RUNTIME, USE_GPU_RUNTIME, USE_DSP_RUNTIME
from selfdrive.modeld.models.commonmodel_pyx cimport CLMem from selfdrive.modeld.models.commonmodel_pyx cimport CLMem
class Runtime: class Runtime:
CPU = USE_CPU_RUNTIME CPU = USE_CPU_RUNTIME
GPU = USE_GPU_RUNTIME GPU = USE_GPU_RUNTIME
DSP = USE_DSP_RUNTIME DSP = USE_DSP_RUNTIME
cdef class RunModel: cdef class RunModel:
def __dealloc__(self): def __dealloc__(self):
del self.model del self.model
def addInput(self, string name, float[:] buffer): def addInput(self, string name, float[:] buffer):
if buffer is not None: if buffer is not None:
self.model.addInput(name, &buffer[0], len(buffer)) self.model.addInput(name, &buffer[0], len(buffer))
else: else:
self.model.addInput(name, NULL, 0) self.model.addInput(name, NULL, 0)
def setInputBuffer(self, string name, float[:] buffer): def setInputBuffer(self, string name, float[:] buffer):
if buffer is not None: if buffer is not None:
self.model.setInputBuffer(name, &buffer[0], len(buffer)) self.model.setInputBuffer(name, &buffer[0], len(buffer))
else: else:
self.model.setInputBuffer(name, NULL, 0) self.model.setInputBuffer(name, NULL, 0)
def getCLBuffer(self, string name): def getCLBuffer(self, string name):
cdef void * cl_buf = self.model.getCLBuffer(name) cdef void * cl_buf = self.model.getCLBuffer(name)
if not cl_buf: if not cl_buf:
return None return None
return CLMem.create(cl_buf) return CLMem.create(cl_buf)
def execute(self): def execute(self):
self.model.execute() self.model.execute()

@ -5,5 +5,5 @@ from libcpp.string cimport string
from cereal.visionipc.visionipc cimport cl_context from cereal.visionipc.visionipc cimport cl_context
cdef extern from "selfdrive/modeld/runners/snpemodel.h": cdef extern from "selfdrive/modeld/runners/snpemodel.h":
cdef cppclass SNPEModel: cdef cppclass SNPEModel:
SNPEModel(string, float*, size_t, int, bool, cl_context) SNPEModel(string, float*, size_t, int, bool, cl_context)

@ -13,5 +13,5 @@ from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel
os.environ['ADSP_LIBRARY_PATH'] = "/data/pythonpath/third_party/snpe/dsp/" os.environ['ADSP_LIBRARY_PATH'] = "/data/pythonpath/third_party/snpe/dsp/"
cdef class SNPEModel(RunModel): cdef class SNPEModel(RunModel):
def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context):
self.model = <cppRunModel *> new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) self.model = <cppRunModel *> new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context)

@ -5,5 +5,5 @@ from libcpp.string cimport string
from cereal.visionipc.visionipc cimport cl_context from cereal.visionipc.visionipc cimport cl_context
cdef extern from "selfdrive/modeld/runners/thneedmodel.h": cdef extern from "selfdrive/modeld/runners/thneedmodel.h":
cdef cppclass ThneedModel: cdef cppclass ThneedModel:
ThneedModel(string, float*, size_t, int, bool, cl_context) ThneedModel(string, float*, size_t, int, bool, cl_context)

@ -10,5 +10,5 @@ from selfdrive.modeld.runners.runmodel_pyx cimport RunModel
from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel
cdef class ThneedModel(RunModel): cdef class ThneedModel(RunModel):
def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context):
self.model = <cppRunModel *> new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) self.model = <cppRunModel *> new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context)

Loading…
Cancel
Save