Skip to content

Commit

Permalink
samples: update mecheye_python_samples to SDK 2.0.2
Browse files Browse the repository at this point in the history
  • Loading branch information
Lianchangle666 authored and lipengfei0451 committed Feb 17, 2023
1 parent 8727c32 commit c14d944
Show file tree
Hide file tree
Showing 26 changed files with 539 additions and 1,225 deletions.
95 changes: 66 additions & 29 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,34 +5,69 @@ This repository contains Python samples for Mech-Eye SDK.
## Installation

### Ubuntu

1. Clone this repository to a specific folder.
2. Install [Mech-Eye API for Ubuntu](https://www.mech-mind.com/download/camera-sdk.html).
2. Install [Mech-Eye API for Ubuntu](https://www.mech-mind.com/download/softwaredownloading.html).
3. Install Mech-Eye API python wrapper by pip3.

```Python
pip3 install MechEyeAPI
```
```Python
sudo pip3 install MechEyeAPI
```

4. (Optional) Install OpenCV and Open3D if you will run the samples marked with `(OpenCV)` and `(Open3D)` below.
* Install OpenCV:

```Python
sudo apt-get install libopencv-dev
sudo apt-get install python3-opencv
```

* Install Open3D:

```Python
python3 -m pip install --upgrade pip
sudo pip install open3d
```

4. Open and run one of the samples.
5. Open and run one of the samples.

```Python
python3 ConnectAndCaptureImage.py
```
```Python
cd ~/mecheye_python_samples/source/Basic
python3 ConnectAndCaptureImage.py
```

> Note:: When writing your own program, use the import command to import Mech-Eye API first. Please import Mech-Eye API before importing Open3D.

### Windows

> Attention
>
> Please check if the following two directories are added to the **Path** environment variable:
>
> - xxx\\AppData\\Local\Programs\Python\\Python36\\
> - xxx\\AppData\\Local\Programs\Python\\Python36\\Scripts\\

1. Clone this repository to a specific folder.
2. Install [Mech-Eye SDK for Windows](https://www.mech-mind.com/download/camera-sdk.html).
2. Install [Mech-Eye SDK for Windows](https://www.mech-mind.com/download/softwaredownloading.html).
3. Install Mech-Eye API python wrapper by pip.

```Python
pip install MechEyeAPI
```
4. Open and run one of the samples.
```Python
pip install MechEyeAPI
```

4. (Optional) Install OpenCV if you will run the samples marked with `(OpenCV)` below.

```Python
pip install opencv-python
pip install opencv-contrib-python
```

5. Open and run one of the samples.

```Python
python ConnectAndCaptureImage.py
```
```Python
cd xxx\mecheye_python_samples\source\Basic
python ConnectAndCaptureImage.py
```


## Sample List
Expand All @@ -42,36 +77,38 @@ Samples are divided into five categories, **Basic**, **Advanced**, **Util**, **L
- **Basic**: camera connection and basic capturing functions.
- **Advanced**: advanced capturing functions.
- **Util**: obtain information from a camera and set camera parameters.
- **Laser**: for Laser/LSR series cameras only.
- **Laser**: for Laser, LSR and DEEP series cameras only.
- **UHP**: for UHP series cameras only.

The samples marked with `(Open3D)` require [open3d](https://pypi.org/project/open3d/) to be installed via pip.
The samples marked with `(Open3D)` require [open3d](https://pypi.org/project/open3d/) to be installed via pip (On Windows, installing Mech-Eye SDK will also install Open3D).
The samples marked with `(OpenCV)` require [opencv-python](https://pypi.org/project/opencv-python/) and [opencv-contrib-python](https://pypi.org/project/opencv-contrib-python/) to be installed via pip.

- **Basic**
- [ConnectToCamera](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/ConnectToCamera.py)
Connect to a Mech-Eye Industrial 3D Camera.
- [ConnectAndCaptureImage](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/ConnectAndCaptureImage.py)
Connect to a camera and obtain 2D image, depth map and 3D image.
Connect to a camera and obtain the 2D image, depth map and point cloud data.
- [CaptureColorMap](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/CaptureColorMap.py) `(OpenCV)`
Obtain 2D image in OpenCV format from a camera.
Obtain and save the 2D image in OpenCV format from a camera.
- [CaptureDepthMap](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/CaptureDepthMap.py) `(OpenCV)`
Obtain depth map in OpenCV format from a camera.
Obtain and save the depth map in OpenCV format from a camera.
- [CapturePointCloud](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/CapturePointCloud.py) `(Open3D)`
Obtain untextured and textured point clouds (PCL format) generated from images captured with a single exposure time.
Obtain and save untextured and textured point clouds generated from images captured with a single exposure time.
- [CaptureHDRPointCloud](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/CaptureHDRPointCloud.py) `(Open3D)`
Obtain untextured and textured point clouds (PCL format) generated from images captured with multiple exposure times.
Obtain and save untextured and textured point clouds generated from images captured with multiple exposure times.
- [CapturePointCloudROI](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/CapturePointCloudROI.py) `(Open3D)`
Obtain untextured and textured point clouds (PCL format) of the objects in the ROI from a camera.
Obtain and save untextured and textured point clouds of the objects in the ROI from a camera.
- [CapturePointCloudFromTextureMask](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Basic/CapturePointCloudFromTextureMask.py) `(Open3D)`
Construct and save untextured and textured point clouds generated from a depth map and masked 2D image.
- **Advanced**
- [CaptureCloudFromDepth](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Advanced/CaptureCloudFromDepth.py) `(Open3D)`
Construct point clouds from depth map and 2D image captured from a camera.
Construct and save point clouds from the depth map and 2D image obtained from a camera.
- [CaptureSequentiallyMultiCamera](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Advanced/CaptureSequentiallyMultiCamera.py)
Obtain 2D image, depth map and 3D images sequentially from multiple cameras.
Obtain and save 2D images, depth maps and point clouds sequentially from multiple cameras.
- [CaptureSimultaneouslyMultiCamera](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Advanced/CaptureSimultaneouslyMultiCamera.py)
Obtain 2D image, depth map and 3D images simultaneously from multiple cameras.
Obtain and save 2D images, depth maps and point clouds simultaneously from multiple cameras.
- [CaptureTimedAndPeriodically](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Advanced/CaptureTimedAndPeriodically.py)
Obtain 2D image, depth map and 3D images periodically for the specified duration from a camera.
Obtain and save 2D images, depth maps and point clouds periodically for the specified duration from a camera.
- **Util**
- [GetCameraIntri](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Util/GetCameraIntri.py)
Get and print a camera's intrinsic parameters.
Expand All @@ -82,7 +119,7 @@ The samples marked with `(OpenCV)` require [opencv-python](https://pypi.org/proj
- [SetParameters](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Util/SetParameters.py)
Set specified parameters to a camera.
- [SetUserSets](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Util/SetUserSets.py)
Functions related to parameter groups, such as getting the names of available parameter groups, switching parameter group, and save the current parameter values to a specific parameter group. The parameter group feature allows user to save and quickly apply a set of parameter values.
Perform functions related to parameter groups, such as getting the names of available parameter groups, switching parameter group, and save the current parameter values to a specific parameter group. The parameter group feature allows user to save and quickly apply a set of parameter values.
- **Laser**
- [SetLaserFramePartitionCount](https://github.com/MechMindRobotics/mecheye_python_samples/tree/master/source/Laser/SetLaserFramePartitionCount.py)
Divide the projector FOV into partitions and project structured light in one partition at a time. The output of the entire FOV is composed from images of all partitions.
Expand Down
84 changes: 14 additions & 70 deletions source/Advanced/CaptureCloudFromDepth.py
Original file line number Diff line number Diff line change
@@ -1,100 +1,44 @@
import sys, os
BASE_DIR = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
sys.path.append(BASE_DIR)

from source import Common
from MechEye import Device
import open3d as o3d
import numpy as np


def show_error(status):
if status.ok():
return
print("Error Code : {}".format(status.code()),
",Error Description: {}".format(status.description()))


def print_device_info(num, info):
print(" Mech-Eye device index: {}\n".format(str(num)),
"Camera Model Name: {}\n".format(info.model()),
"Camera ID: {}\n".format(info.id()),
"Camera IP: {}\n".format(info.ip()),
"Hardware Version: {}\n".format(info.hardware_version()),
"Firmware Version: {}\n".format(info.firmware_version()),
"...............................................")

import open3d as o3d

class CaptureCloudFromDepth(object):
def __init__(self):
self.device = Device()

def find_camera_list(self):
print("Find Mech-Eye devices...")
self.device_list = self.device.get_device_list()
if len(self.device_list) == 0:
print("No Mech-Eye device found.")
quit()
for i, info in enumerate(self.device_list):
print_device_info(i, info)

def choose_camera(self):
while True:
user_input = input(
"Please enter the device index you want to connect: ")
if user_input.isdigit() and len(self.device_list) > int(user_input) and int(user_input) >= 0:
self.index = int(user_input)
break
print("Input invalid!")

def connect_device_info(self):
status = self.device.connect(self.device_list[self.index])
if not status.ok():
show_error(status)
quit()
print("Connected to the Mech-Eye device successfully.")

color = self.device.capture_color()
color_data = color.data()
def capture_cloud_from_depth(self):
depth = self.device.capture_depth()
depth_data = depth.data()
device_intrinsic = self.device.get_device_intrinsic().depth_camera_intrinsic()

point_cloud_xyz = o3d.geometry.PointCloud()
points_xyz = np.zeros(
(depth.width() * depth.height(), 3), dtype=np.float64)
points_xyz = np.zeros((depth.width() * depth.height(), 3), dtype=np.float64)

width = depth.width()
print("Depth map element size is: {}".format(depth_data.size))
for i, d in enumerate(depth_data):
for j, dd in enumerate(d):
points_xyz[width * i + j][0] = (j - device_intrinsic.camera_matrix_cx()
) * dd / device_intrinsic.camera_matrix_fx()
points_xyz[width * i + j][1] = (i - device_intrinsic.camera_matrix_cy()
) * dd / device_intrinsic.camera_matrix_fy()
points_xyz[width * i + j][0] = (j - device_intrinsic.camera_matrix_cx()) * dd / device_intrinsic.camera_matrix_fx()
points_xyz[width * i + j][1] = (i - device_intrinsic.camera_matrix_cy()) * dd / device_intrinsic.camera_matrix_fy()
points_xyz[width * i + j][2] = dd

point_cloud_xyz.points = o3d.utility.Vector3dVector(points_xyz)
o3d.visualization.draw_geometries([point_cloud_xyz])
o3d.io.write_point_cloud("PointCloudXYZ.ply", point_cloud_xyz)
print("Point cloud saved to path PointCloudXYZ.ply")

point_cloud_xyz_rgb = o3d.geometry.PointCloud()
point_cloud_xyz_rgb.points = o3d.utility.Vector3dVector(points_xyz)
points_rgb = np.zeros(
(depth.width() * depth.height(), 3), dtype=np.float64)

pos = 0
for dd in np.nditer(color_data):
points_rgb[int(pos / 3)][int(2 - (pos % 3))] = dd / 255
pos = pos + 1

point_cloud_xyz_rgb.colors = o3d.utility.Vector3dVector(points_rgb)
o3d.visualization.draw_geometries([point_cloud_xyz_rgb])
o3d.io.write_point_cloud("PointCloudXYZRGB.ply", point_cloud_xyz_rgb)
print("Color point cloud saved to path PointCloudXYZRGB.ply")

self.device.disconnect()
print("Disconnected from the Mech-Eye device successfully.")

def main(self):
self.find_camera_list()
self.choose_camera()
self.connect_device_info()
Common.find_camera_list(self)
if Common.choose_camera_and_connect(self):
self.capture_cloud_from_depth()


if __name__ == '__main__':
Expand Down
55 changes: 12 additions & 43 deletions source/Advanced/CaptureSequentiallyMultiCamera.py
Original file line number Diff line number Diff line change
@@ -1,49 +1,15 @@
import sys, os
BASE_DIR = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__))))
sys.path.append(BASE_DIR)
from MechEye import Device


def show_error(status):
if status.ok():
return
print("Error Code : {}".format(status.code()),
",Error Description: {}".format(status.description()))


def print_device_info(num, info):
print(" Mech-Eye device index: {}\n".format(str(num)),
"Camera Model Name: {}\n".format(info.model()),
"Camera ID: {}\n".format(info.id()),
"Camera IP: {}\n".format(info.ip()),
"Hardware Version: {}\n".format(info.hardware_version()),
"Firmware Version: {}\n".format(info.firmware_version()),
"...............................................")
from source import Common


class CaptureSequentiallyMultiCamera(object):
def __init__(self):
self.device = Device()

def find_camera_list(self):
print("Find Mech-Eye devices...")
self.device_list = self.device.get_device_list()
if len(self.device_list) == 0:
print("No Mech-Eye device found.")
quit()
for i, info in enumerate(self.device_list):
print_device_info(i, info)

def choose_camera(self):
self.indices = set()
while True:
user_input = input(
"Please enter the device index you want to connect. Enter a c to terminate adding devices: ")
if user_input == "c":
break
elif user_input.isdigit() and len(self.device_list) > int(user_input) and int(user_input) >= 0:
self.indices.add(int(user_input))
else:
print("Input invalid!")

def connect_device_info(self):
def connect_device_and_capture(self):
for index in self.indices:
device = Device()
error_status = device.connect(self.device_list[index])
Expand All @@ -52,7 +18,7 @@ def connect_device_info(self):
quit()

device_info = device.get_device_info()
print("Camera {} start capturing.".format(device_info.id()))
print("Camera {} start capturing.".format(device_info.id))

device.capture_color()
device.capture_depth()
Expand All @@ -63,9 +29,12 @@ def connect_device_info(self):
print("Disconnected from the Mech-Eye device successfully.")

def main(self):
self.find_camera_list()
self.choose_camera()
self.connect_device_info()
Common.find_camera_list(self)
Common.choose_multi_camera(self)
if len(self.indices) != 0:
self.connect_device_and_capture()
else:
print("No camera was selected.")


if __name__ == '__main__':
Expand Down
Loading

0 comments on commit c14d944

Please sign in to comment.