Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions pyzed/camera.pxd
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

from libcpp cimport bool
from libcpp.pair cimport pair
from libcpp.vector cimport vector

cimport pyzed.defines as defines
cimport pyzed.core as core
Expand Down Expand Up @@ -239,6 +240,9 @@ cdef extern from 'sl/Camera.hpp' namespace 'sl':
@staticmethod
types.ERROR_CODE sticktoCPUCore(int cpu_core)

@staticmethod
vector[types.DeviceProperties] getDeviceList()

bool saveDepthAs(Camera &zed, defines.DEPTH_FORMAT format, types.String name, float factor)
bool savePointCloudAs(Camera &zed, defines.POINT_CLOUD_FORMAT format, types.String name,
bool with_color)
Expand Down
38 changes: 30 additions & 8 deletions pyzed/camera.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,9 @@ cdef class PyInitParameters:
else:
raise TypeError("Argument is not of right type.")

def __dealloc__(self):
del self.init

def save(self, str filename):
filename_save = filename.encode()
return self.init.save(types.String(<char*> filename_save))
Expand Down Expand Up @@ -255,6 +258,9 @@ cdef class PyRuntimeParameters:
else:
raise TypeError()

def __dealloc__(self):
del self.runtime

def save(self, str filename):
filename_save = filename.encode()
return self.runtime.save(types.String(<char*> filename_save))
Expand Down Expand Up @@ -301,6 +307,9 @@ cdef class PyTrackingParameters:
self.tracking = new TrackingParameters(init_pos.transform, _enable_memory, types.String())
else:
raise TypeError("Argument init_pos must be initialized first with PyTransform().")

def __dealloc__(self):
del self.tracking

def save(self, str filename):
filename_save = filename.encode()
Expand Down Expand Up @@ -350,6 +359,9 @@ cdef class PySpatialMappingParameters:
else:
raise TypeError()

def __dealloc__(self):
del self.spatial

def set_resolution(self, resolution=PyRESOLUTION.PyRESOLUTION_HIGH):
if isinstance(resolution, PyRESOLUTION):
self.spatial.set(<MAPPING_RESOLUTION> resolution.value)
Expand Down Expand Up @@ -701,7 +713,6 @@ cdef class PyZEDCamera:
filename = area_file_path.encode()
self.camera.disableTracking(types.String(<char*> filename))


def reset_tracking(self, core.PyTransform path):
return types.PyERROR_CODE(self.camera.resetTracking(path.transform))

Expand Down Expand Up @@ -750,15 +761,27 @@ cdef class PyZEDCamera:
def disable_recording(self):
self.camera.disableRecording()

def get_sdk_version(self):
return self.camera.getSDKVersion().get().decode()
def get_sdk_version(cls):
return cls.camera.getSDKVersion().get().decode()

def is_zed_connected(self):
return self.camera.isZEDconnected()
def is_zed_connected(cls):
return cls.camera.isZEDconnected()

def stickto_cpu_core(self, int cpu_core):
return types.PyERROR_CODE(self.camera.sticktoCPUCore(cpu_core))
def stickto_cpu_core(cls, int cpu_core):
return types.PyERROR_CODE(cls.camera.sticktoCPUCore(cpu_core))

def get_device_list(cls):
vect_ = cls.camera.getDeviceList()
vect_python = []
for i in range(vect_.size()):
prop = types.PyDeviceProperties()
prop.camera_state = vect_[i].camera_state
prop.id = vect_[i].id
prop.path = vect_[i].path.get().decode()
prop.camera_model = vect_[i].camera_model
prop.serial_number = vect_[i].serial_number
vect_python.append(prop)
return vect_python

def save_camera_depth_as(PyZEDCamera zed, format, str name, factor=1):
if isinstance(format, defines.PyDEPTH_FORMAT) and factor <= 65536:
Expand All @@ -767,7 +790,6 @@ def save_camera_depth_as(PyZEDCamera zed, format, str name, factor=1):
else:
raise TypeError("Arguments must be of PyDEPTH_FORMAT type and factor not over 65536.")


def save_camera_point_cloud_as(PyZEDCamera zed, format, str name, with_color=False):
if isinstance(format, defines.PyPOINT_CLOUD_FORMAT):
name_save = name.encode()
Expand Down
6 changes: 6 additions & 0 deletions pyzed/mesh.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,9 @@ cdef class PyMeshFilterParameters:
def __cinit__(self):
self.meshFilter = new MeshFilterParameters(MESH_FILTER_LOW)

def __dealloc__(self):
del self.meshFilter

def set(self, filter=PyFILTER.PyFILTER_LOW):
if isinstance(filter, PyFILTER):
self.meshFilter.set(filter.value)
Expand Down Expand Up @@ -147,6 +150,9 @@ cdef class PyChunk:
cdef class PyMesh:
def __cinit__(self):
self.mesh = new Mesh()

def __dealloc__(self):
del self.mesh

@property
def chunks(self):
Expand Down
20 changes: 18 additions & 2 deletions pyzed/types.pxd
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ cdef extern from "sl/types.hpp" namespace "sl":
ERROR_CODE_NO_GPU_DETECTED,
ERROR_CODE_LAST

String errorCode2str(ERROR_CODE err)
String toString(ERROR_CODE o)

void sleep_ms(int time)

Expand All @@ -70,16 +70,32 @@ cdef extern from "sl/types.hpp" namespace "sl":
MODEL_LAST

String model2str(MODEL model)
String toString(MODEL o)

cdef cppclass String 'sl::String':
ctypedef enum CAMERA_STATE:
CAMERA_STATE_AVAILABLE,
CAMERA_STATE_NOT_AVAILABLE,
CAMERA_STATE_LAST

String toString(CAMERA_STATE o)

cdef cppclass String 'sl::String':
String()
String(const char *data)
void set(const char *data)
const char *get() const
bool empty() const
string std_str() const

cdef cppclass DeviceProperties:
DeviceProperties()
CAMERA_STATE camera_state
int id
String path
MODEL camera_model
unsigned int serial_number

String toString(DeviceProperties o)

cdef cppclass Vector2[T]:
int size()
Expand Down
79 changes: 75 additions & 4 deletions pyzed/types.pyx
Original file line number Diff line number Diff line change
Expand Up @@ -57,26 +57,97 @@ class PyERROR_CODE(enum.Enum):
PyERROR_CODE_LAST = ERROR_CODE_LAST

def __str__(self):
return to_str(errorCode2str(self.value)).decode()
return to_str(toString(<ERROR_CODE>self.value)).decode()

def __repr__(self):
return to_str(errorCode2str(self.value)).decode()
return to_str(toString(<ERROR_CODE>self.value)).decode()

class PyMODEL(enum.Enum):
PyMODEL_ZED = MODEL_ZED
PyMODEL_ZED_M = MODEL_ZED_M
PyMODEL_LAST = MODEL_LAST

def __str__(self):
return to_str(model2str(self.value)).decode()
return to_str(toString(<MODEL>self.value)).decode()

def __repr__(self):
return to_str(model2str(self.value)).decode()
return to_str(toString(<MODEL>self.value)).decode()

class PyCAMERA_STATE(enum.Enum):
PyCAMERA_STATE_AVAILABLE = CAMERA_STATE_AVAILABLE
PyCAMERA_STATE_NOT_AVAILABLE = CAMERA_STATE_NOT_AVAILABLE
PyCAMERA_STATE_LAST = CAMERA_STATE_LAST

def __str__(self):
return to_str(toString(<CAMERA_STATE>self.value)).decode()

def __repr__(self):
return to_str(toString(<CAMERA_STATE>self.value)).decode()

def c_sleep_ms(int time):
sleep_ms(time)

cdef class PyDeviceProperties:
cdef DeviceProperties c_device_properties

def __cinit__(self):
self.c_device_properties = DeviceProperties()

@property
def camera_state(self):
return self.c_device_properties.camera_state
@camera_state.setter
def camera_state(self, camera_state):
if isinstance(camera_state, PyCAMERA_STATE):
self.c_device_properties.camera_state = (<CAMERA_STATE> camera_state.value)
elif isinstance(camera_state, int):
self.c_device_properties.camera_state = (<CAMERA_STATE> camera_state)
else:
raise TypeError("Argument is not of PyCAMERA_STATE type.")

@property
def id(self):
return self.c_device_properties.id
@id.setter
def id(self, id):
self.c_device_properties.id = id

@property
def path(self):
if not self.c_device_properties.path.empty():
return self.c_device_properties.path.get().decode()
else:
return ""
@path.setter
def path(self, str path):
path_ = path.encode()
self.c_device_properties.path = (String(<char*> path_))

@property
def camera_model(self):
return self.c_device_properties.camera_model
@camera_model.setter
def camera_model(self, camera_model):
if isinstance(camera_model, PyMODEL):
self.c_device_properties.camera_model = (<MODEL> camera_model.value)
elif isinstance(camera_model, int):
self.c_device_properties.camera_model = (<MODEL> camera_model)
else:
raise TypeError("Argument is not of PyMODEL type.")

@property
def serial_number(self):
return self.c_device_properties.serial_number
@serial_number.setter
def serial_number(self, serial_number):
self.c_device_properties.serial_number = serial_number

def __str__(self):
return to_str(toString(self.c_device_properties)).decode()

def __repr__(self):
return to_str(toString(self.c_device_properties)).decode()


cdef class PyMatrix3f:
def __cinit__(self):
Expand Down