Added cython bindings for model runners and commonmodel (#29607)

* Added cython bindings for model runners and commonmodel

* Removed cython language_level=3

* loop to set CXXFLAGS for both envs
old-commit-hash: e2e39d100b
beeps
Mitchell Goff 2 years ago committed by GitHub
parent bc017ab936
commit 5033da5e27
  1. 9
      release/files_common
  2. 27
      selfdrive/modeld/SConscript
  3. 0
      selfdrive/modeld/models/__init__.py
  4. 23
      selfdrive/modeld/models/commonmodel.pxd
  5. 13
      selfdrive/modeld/models/commonmodel_pyx.pxd
  6. 46
      selfdrive/modeld/models/commonmodel_pyx.pyx
  7. 0
      selfdrive/modeld/runners/__init__.py
  8. 9
      selfdrive/modeld/runners/onnxmodel.pxd
  9. 14
      selfdrive/modeld/runners/onnxmodel_pyx.pyx
  10. 10
      selfdrive/modeld/runners/runmodel.pxd
  11. 6
      selfdrive/modeld/runners/runmodel_pyx.pxd
  12. 32
      selfdrive/modeld/runners/runmodel_pyx.pyx
  13. 9
      selfdrive/modeld/runners/snpemodel.pxd
  14. 14
      selfdrive/modeld/runners/snpemodel_pyx.pyx
  15. 9
      selfdrive/modeld/runners/thneedmodel.pxd
  16. 14
      selfdrive/modeld/runners/thneedmodel_pyx.pyx

@ -354,6 +354,7 @@ selfdrive/manager/process.py
selfdrive/manager/test/__init__.py
selfdrive/manager/test/test_manager.py
selfdrive/modeld/.gitignore
selfdrive/modeld/__init__.py
selfdrive/modeld/SConscript
selfdrive/modeld/modeld.cc
@ -364,6 +365,10 @@ selfdrive/modeld/modeld
selfdrive/modeld/navmodeld
selfdrive/modeld/dmonitoringmodeld
selfdrive/modeld/models/__init__.py
selfdrive/modeld/models/*.pxd
selfdrive/modeld/models/*.pyx
selfdrive/modeld/models/commonmodel.cc
selfdrive/modeld/models/commonmodel.h
@ -392,6 +397,10 @@ selfdrive/modeld/thneed/thneed_common.cc
selfdrive/modeld/thneed/thneed_qcom2.cc
selfdrive/modeld/thneed/serialize.cc
selfdrive/modeld/runners/__init__.py
selfdrive/modeld/runners/*.pxd
selfdrive/modeld/runners/*.pyx
selfdrive/modeld/runners/snpemodel.cc
selfdrive/modeld/runners/snpemodel.h
selfdrive/modeld/runners/thneedmodel.cc

@ -1,7 +1,8 @@
import os
Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'transformations')
Import('env', 'envCython', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'transformations')
lenv = env.Clone()
lenvCython = envCython.Clone()
libs = [cereal, messaging, common, visionipc, gpucommon,
'OpenCL', 'SNPE', 'capnp', 'zmq', 'kj', 'yuv']
@ -53,8 +54,28 @@ else:
del common_src[common_src.index('runners/snpemodel.cc')]
for pathdef, fn in {'TRANSFORM': 'transforms/transform.cl', 'LOADYUV': 'transforms/loadyuv.cl', 'ONNXRUNNER': 'runners/onnx_runner.py'}.items():
path = File(fn).abspath
lenv['CXXFLAGS'].append(f'-D{pathdef}_PATH=\\"{path}\\"')
for xenv in (lenv, lenvCython):
xenv['CXXFLAGS'].append(f'-D{pathdef}_PATH=\\"{File(fn).abspath}\\"')
if (use_thneed and arch == "larch64") or GetOption('pc_thneed'):
lenvCython['CFLAGS'].append("-DUSE_THNEED")
lenvCython['CXXFLAGS'].append("-DUSE_THNEED")
common_frameworks = []
common_libs = envCython["LIBS"] + [gpucommon, common, 'zmq']
if arch == "Darwin":
common_frameworks.append('OpenCL')
else:
common_libs.append('OpenCL')
onnxmodel_lib = lenv.Library('onnxmodel', ['runners/onnxmodel.cc'])
snpemodel_lib = lenv.Library('snpemodel', ['runners/snpemodel.cc'])
commonmodel_lib = lenv.Library('commonmodel', common_src)
lenvCython.Program('runners/runmodel_pyx.so', 'runners/runmodel_pyx.pyx', LIBS=common_libs, FRAMEWORKS=common_frameworks)
lenvCython.Program('runners/onnxmodel_pyx.so', 'runners/onnxmodel_pyx.pyx', LIBS=[onnxmodel_lib, *common_libs], FRAMEWORKS=common_frameworks)
lenvCython.Program('runners/snpemodel_pyx.so', 'runners/snpemodel_pyx.pyx', LIBS=[snpemodel_lib, *common_libs], FRAMEWORKS=common_frameworks)
lenvCython.Program('models/commonmodel_pyx.so', 'models/commonmodel_pyx.pyx', LIBS=[commonmodel_lib, *common_libs], FRAMEWORKS=common_frameworks)
common_model = lenv.Object(common_src)

@ -0,0 +1,23 @@
# distutils: language = c++
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 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 extern from "selfdrive/modeld/models/commonmodel.h":
cppclass ModelFrame:
int buf_size
ModelFrame(cl_device_id, cl_context)
float * prepare(cl_mem, int, int, int, int, mat3, cl_mem*)
cdef extern from "selfdrive/modeld/runners/runmodel.h":
cdef int USE_CPU_RUNTIME
cdef int USE_GPU_RUNTIME
cdef int USE_DSP_RUNTIME

@ -0,0 +1,13 @@
# distutils: language = c++
from cereal.visionipc.visionipc cimport cl_mem
from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext
cdef class CLContext(BaseCLContext):
pass
cdef class CLMem:
cdef cl_mem * mem;
@staticmethod
cdef create(void*)

@ -0,0 +1,46 @@
# distutils: language = c++
# cython: c_string_encoding=ascii
import numpy as np
cimport numpy as cnp
from libc.string cimport memcpy
from cereal.visionipc.visionipc cimport cl_mem
from cereal.visionipc.visionipc_pyx cimport VisionBuf, CLContext as BaseCLContext
from .commonmodel cimport CL_DEVICE_TYPE_DEFAULT, cl_get_device_id, cl_create_context
from .commonmodel cimport USE_CPU_RUNTIME, USE_GPU_RUNTIME, USE_DSP_RUNTIME
from .commonmodel cimport mat3, ModelFrame as cppModelFrame
class Runtime:
CPU = USE_CPU_RUNTIME
GPU = USE_GPU_RUNTIME
DSP = USE_DSP_RUNTIME
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)
cdef class CLMem:
@staticmethod
cdef create(void * cmem):
mem = CLMem()
mem.mem = <cl_mem*> cmem
return mem
cdef class ModelFrame:
cdef cppModelFrame * frame
def __cinit__(self, CLContext context):
self.frame = new cppModelFrame(context.device_id, context.context)
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(<cnp.float32_t[:self.frame.buf_size]> data)

@ -0,0 +1,9 @@
# distutils: language = c++
from libcpp.string cimport string
from cereal.visionipc.visionipc cimport cl_context
cdef extern from "selfdrive/modeld/runners/onnxmodel.h":
cdef cppclass ONNXModel:
ONNXModel(string, float*, size_t, int, bool, cl_context)

@ -0,0 +1,14 @@
# distutils: language = c++
# cython: c_string_encoding=ascii
from libcpp cimport bool
from libcpp.string cimport string
from .onnxmodel cimport ONNXModel as cppONNXModel
from selfdrive.modeld.models.commonmodel_pyx cimport CLContext
from selfdrive.modeld.runners.runmodel_pyx cimport RunModel
from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel
cdef class ONNXModel(RunModel):
def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context):
self.model = <cppRunModel *> new cppONNXModel(path, &output[0], len(output), runtime, use_tf8, context.context)

@ -0,0 +1,10 @@
# distutils: language = c++
from libcpp.string cimport string
cdef extern from "selfdrive/modeld/runners/runmodel.h":
cdef cppclass RunModel:
void addInput(string, float*, int)
void setInputBuffer(string, float*, int)
void * getCLBuffer(string)
void execute()

@ -0,0 +1,6 @@
# distutils: language = c++
from .runmodel cimport RunModel as cppRunModel
cdef class RunModel:
cdef cppRunModel * model

@ -0,0 +1,32 @@
# distutils: language = c++
# cython: c_string_encoding=ascii
from libcpp.string cimport string
from libc.string cimport memcpy
from selfdrive.modeld.models.commonmodel_pyx cimport CLMem
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()

@ -0,0 +1,9 @@
# distutils: language = c++
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)

@ -0,0 +1,14 @@
# distutils: language = c++
# cython: c_string_encoding=ascii
from libcpp cimport bool
from libcpp.string cimport string
from .snpemodel cimport SNPEModel as cppSNPEModel
from selfdrive.modeld.models.commonmodel_pyx cimport CLContext
from selfdrive.modeld.runners.runmodel_pyx cimport RunModel
from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel
cdef class SNPEModel(RunModel):
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)

@ -0,0 +1,9 @@
# distutils: language = c++
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)

@ -0,0 +1,14 @@
# distutils: language = c++
# cython: c_string_encoding=ascii
from libcpp cimport bool
from libcpp.string cimport string
from .thneedmodel cimport ThneedModel as cppThneedModel
from selfdrive.modeld.models.commonmodel_pyx cimport CLContext
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 = <cppRunModel *> new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context)
Loading…
Cancel
Save