Adding changes to cython files to pass static analysis

pull/31491/head
Milan Medic 1 year ago
parent 52d3ea22f4
commit 9a0eb73319
  1. 6
      common/params_pyx.pyx
  2. 3
      common/transformations/transformations.pxd
  3. 18
      common/transformations/transformations.pyx
  4. 1
      selfdrive/boardd/boardd_api_impl.pyx
  5. 2
      selfdrive/modeld/models/commonmodel_pyx.pxd
  6. 4
      selfdrive/modeld/models/commonmodel_pyx.pyx
  7. 3
      selfdrive/modeld/runners/runmodel_pyx.pyx

@ -29,11 +29,13 @@ cdef extern from "common/params.h":
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
@ -59,7 +61,6 @@ cdef class Params:
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
@ -67,7 +68,6 @@ cdef class Params:
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): def get_bool(self, key, bool block=False):

@ -1,4 +1,4 @@
#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":
@ -21,7 +21,6 @@ cdef extern from "orientation.hpp":
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) Quaternion euler2quat(Vector3)

@ -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)

@ -14,6 +14,7 @@ cdef extern from "panda.h":
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))

@ -7,7 +7,7 @@ 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,14 +10,17 @@ 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):
@ -25,6 +28,7 @@ cdef class 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

@ -2,16 +2,17 @@
# 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

Loading…
Cancel
Save