JeVoisBase
1.22
JeVois Smart Embedded Machine Vision Toolkit Base Modules
|
|
Simple example of object detection using ORB keypoints followed by 6D pose estimation in Python. More...
Public Member Functions | |
__init__ (self) | |
Constructor. | |
loadCameraCalibration (self, w, h) | |
Load camera calibration from JeVois share directory. | |
detect (self, imggray, outimg=None) | |
Detect objects using keypoints. | |
estimatePose (self, hlist) | |
Estimate 6D pose of each of the quadrilateral objects in hlist: | |
sendAllSerial (self, w, h, hlist, rvecs, tvecs) | |
Send serial messages, one per object. | |
drawDetections (self, outimg, hlist, rvecs=None, tvecs=None) | |
Draw all detected objects in 3D. | |
processNoUSB (self, inframe) | |
Process function with no USB output. | |
process (self, inframe, outframe) | |
Process function with USB output. | |
Public Attributes | |
fname | |
owm | |
ohm | |
wintop | |
winleft | |
winw | |
winh | |
distth | |
timer | |
camMatrix | |
distCoeffs | |
detector | |
refkp | |
refdes | |
refcorners | |
wincorners | |
matcher | |
Simple example of object detection using ORB keypoints followed by 6D pose estimation in Python.
This module implements an object detector using ORB keypoints using OpenCV in Python. Its main goal is to also demonstrate full 6D pose recovery of the detected object, in Python, as well as locating in 3D a sub-element of the detected object (here, a window within a larger textured wall). See ObjectDetect for more info about object detection using keypoints. This module is available with JeVois v1.6.3 and later.
The algorithm consists of 5 phases:
For more information about ORB keypoint detection and matching in OpenCV, see, e.g., https://docs.opencv.org/3.4.0/d1/d89/tutorial_py_orb.html
This module is provided for inspiration. It has no pretension of actually solving the FIRST Robotics Power Up (sm) vision problem in a complete and reliable way. It is released in the hope that FRC teams will try it out and get inspired to develop something much better for their own robot.
Note how, contrary to FirstVision, DemoArUco, etc, the green parallelepiped is drawn going into the object instead of sticking out of it, as it is depicting a tunnel at the window location.
This module is for now specific to the "exchange" of the FIRST Robotics 2018 Power Up (sm) challenge. See https://www.firstinspires.org/resource-library/frc/competition-manual-qa-system
The exchange is a large textured structure with a window at the bottom into which robots should deliver foam cubes.
A reference picture of the whole exchange (taken from the official rules) is in JEVOIS:/modules/JeVois/PythonObject6D/images/reference.png on your JeVois microSD card. It will be processed when the module starts. No additional training procedure is needed.
If you change the reference image, you should also edit:
self.owm
and self.ohm
to the width ahd height, in meters, of the actual physical object in your picture. Square pixels are assumed, so make sure the aspect ratio of your PNG image matches the aspect ratio in meters given by variables self.owm
and self.ohm
in the code.self.wintop
, self.winleft
, self.winw
, self.winh
to the location of the top-left corner, in meters and relative to the top-left corner of the whole reference object, of a window of interest (the tunnel into which the cubes should be delivered), and width and height, in meters, of the window.TODO: Add support for multiple images and online training as in ObjectDetect
There are a number of limitations and caveats to this module:
Definition at line 110 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.__init__ | ( | self | ) |
Constructor.
Definition at line 113 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.detect | ( | self, | |
imggray, | |||
outimg = None |
|||
) |
Detect objects using keypoints.
Definition at line 147 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.process(), PythonObject6D.PythonObject6D.process(), FirstPython.FirstPython.processNoUSB(), and PythonObject6D.PythonObject6D.processNoUSB().
PythonObject6D.PythonObject6D.drawDetections | ( | self, | |
outimg, | |||
hlist, | |||
rvecs = None , |
|||
tvecs = None |
|||
) |
Draw all detected objects in 3D.
Definition at line 290 of file PythonObject6D.py.
References jevois::CameraCalibration.camMatrix, FirstPython.FirstPython.camMatrix, PythonObject6D.PythonObject6D.camMatrix, jevois::CameraCalibration.distCoeffs, FirstPython.FirstPython.distCoeffs, FirstVision::SinglePoseEstimationParallel.distCoeffs, PythonObject6D.PythonObject6D.distCoeffs, PythonObject6D.PythonObject6D.winh, and PythonObject6D.PythonObject6D.winw.
Referenced by FirstPython.FirstPython.process(), and PythonObject6D.PythonObject6D.process().
PythonObject6D.PythonObject6D.estimatePose | ( | self, | |
hlist | |||
) |
Estimate 6D pose of each of the quadrilateral objects in hlist:
Definition at line 242 of file PythonObject6D.py.
References jevois::CameraCalibration.camMatrix, FirstPython.FirstPython.camMatrix, PythonObject6D.PythonObject6D.camMatrix, jevois::CameraCalibration.distCoeffs, FirstPython.FirstPython.distCoeffs, FirstVision::SinglePoseEstimationParallel.distCoeffs, PythonObject6D.PythonObject6D.distCoeffs, PythonObject6D.PythonObject6D.winh, and PythonObject6D.PythonObject6D.winw.
Referenced by FirstPython.FirstPython.process(), PythonObject6D.PythonObject6D.process(), FirstPython.FirstPython.processNoUSB(), and PythonObject6D.PythonObject6D.processNoUSB().
PythonObject6D.PythonObject6D.loadCameraCalibration | ( | self, | |
w, | |||
h | |||
) |
Load camera calibration from JeVois share directory.
Definition at line 136 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.process(), PythonObject6D.PythonObject6D.process(), FirstPython.FirstPython.processNoUSB(), and PythonObject6D.PythonObject6D.processNoUSB().
PythonObject6D.PythonObject6D.process | ( | self, | |
inframe, | |||
outframe | |||
) |
Process function with USB output.
Definition at line 389 of file PythonObject6D.py.
References ObjectMatcher.detect(), BlobDetector.detect(), FirstVision.detect(), FirstPython.FirstPython.detect(), PythonObject6D.PythonObject6D.detect(), ARtoolkit.drawDetections(), ArUco.drawDetections(), QRcode.drawDetections(), Yolo.drawDetections(), ArUco.drawDetections(), QRcode.drawDetections(), ARtoolkit.drawDetections(), FirstVision.drawDetections(), FirstPython.FirstPython.drawDetections(), PythonObject6D.PythonObject6D.drawDetections(), FirstPython.FirstPython.estimatePose(), PythonObject6D.PythonObject6D.estimatePose(), FirstVision.estimatePose(), FirstPython.FirstPython.loadCameraCalibration(), PythonObject6D.PythonObject6D.loadCameraCalibration(), jevois::Engine.loadCameraCalibration(), FirstVision.sendAllSerial(), FirstPython.FirstPython.sendAllSerial(), PythonObject6D.PythonObject6D.sendAllSerial(), AprilTag.AprilTag.timer, FirstPython.FirstPython.timer, PyClassificationDNN.PyClassificationDNN.timer, PyCoralClassify.PyCoralClassify.timer, PyCoralDetect.PyCoralDetect.timer, PyCoralSegment.PyCoralSegment.timer, PyDetectionDNN.PyDetectionDNN.timer, PyDMTX.PyDMTX.timer, PyEmotion.PyEmotion.timer, PyFaceMesh.PyFaceMesh.timer, PyHandDetector.PyHandDetector.timer, PyLicensePlate.PyLicensePlate.timer, PyObjectron.PyObjectron.timer, PyPoseDetector.PyPoseDetector.timer, PySceneText.PySceneText.timer, PySelfie.PySelfie.timer, PythonObject6D.PythonObject6D.timer, PythonOpenCV.PythonOpenCV.timer, PythonParallel.PythonParallel.timer, PythonSandbox.PythonSandbox.timer, and PythonTest.PythonTest.timer.
PythonObject6D.PythonObject6D.processNoUSB | ( | self, | |
inframe | |||
) |
Process function with no USB output.
Definition at line 364 of file PythonObject6D.py.
References ObjectMatcher.detect(), BlobDetector.detect(), FirstVision.detect(), FirstPython.FirstPython.detect(), PythonObject6D.PythonObject6D.detect(), FirstPython.FirstPython.estimatePose(), PythonObject6D.PythonObject6D.estimatePose(), FirstVision.estimatePose(), FirstPython.FirstPython.loadCameraCalibration(), PythonObject6D.PythonObject6D.loadCameraCalibration(), jevois::Engine.loadCameraCalibration(), FirstVision.sendAllSerial(), FirstPython.FirstPython.sendAllSerial(), PythonObject6D.PythonObject6D.sendAllSerial(), AprilTag.AprilTag.timer, FirstPython.FirstPython.timer, PyClassificationDNN.PyClassificationDNN.timer, PyCoralClassify.PyCoralClassify.timer, PyCoralDetect.PyCoralDetect.timer, PyCoralSegment.PyCoralSegment.timer, PyDetectionDNN.PyDetectionDNN.timer, PyDMTX.PyDMTX.timer, PyEmotion.PyEmotion.timer, PyFaceMesh.PyFaceMesh.timer, PyHandDetector.PyHandDetector.timer, PyLicensePlate.PyLicensePlate.timer, PyObjectron.PyObjectron.timer, PyPoseDetector.PyPoseDetector.timer, PySceneText.PySceneText.timer, PySelfie.PySelfie.timer, PythonObject6D.PythonObject6D.timer, PythonOpenCV.PythonOpenCV.timer, PythonParallel.PythonParallel.timer, PythonSandbox.PythonSandbox.timer, and PythonTest.PythonTest.timer.
PythonObject6D.PythonObject6D.sendAllSerial | ( | self, | |
w, | |||
h, | |||
hlist, | |||
rvecs, | |||
tvecs | |||
) |
Send serial messages, one per object.
Definition at line 266 of file PythonObject6D.py.
References FirstPython.FirstPython.ohm, PythonObject6D.PythonObject6D.ohm, FirstPython.FirstPython.owm, and PythonObject6D.PythonObject6D.owm.
Referenced by FirstPython.FirstPython.process(), PythonObject6D.PythonObject6D.process(), FirstPython.FirstPython.processNoUSB(), and PythonObject6D.PythonObject6D.processNoUSB().
PythonObject6D.PythonObject6D.camMatrix |
Definition at line 138 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.drawDetections(), PythonObject6D.PythonObject6D.drawDetections(), FirstPython.FirstPython.estimatePose(), and PythonObject6D.PythonObject6D.estimatePose().
PythonObject6D.PythonObject6D.detector |
Definition at line 153 of file PythonObject6D.py.
Referenced by AprilTag.AprilTag.processGUI(), PySceneText.PySceneText.processGUI(), AprilTag.AprilTag.processNoUSB(), and AprilTag.AprilTag.setDic().
PythonObject6D.PythonObject6D.distCoeffs |
Definition at line 138 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.drawDetections(), PythonObject6D.PythonObject6D.drawDetections(), FirstPython.FirstPython.estimatePose(), and PythonObject6D.PythonObject6D.estimatePose().
PythonObject6D.PythonObject6D.distth |
Definition at line 129 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.fname |
Definition at line 115 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.matcher |
Definition at line 176 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.ohm |
Definition at line 119 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.drawDetections(), FirstPython.FirstPython.estimatePose(), FirstPython.FirstPython.sendAllSerial(), and PythonObject6D.PythonObject6D.sendAllSerial().
PythonObject6D.PythonObject6D.owm |
Definition at line 118 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.drawDetections(), FirstPython.FirstPython.estimatePose(), FirstPython.FirstPython.sendAllSerial(), and PythonObject6D.PythonObject6D.sendAllSerial().
PythonObject6D.PythonObject6D.refcorners |
Definition at line 162 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.refdes |
Definition at line 158 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.refkp |
Definition at line 158 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.timer |
Definition at line 132 of file PythonObject6D.py.
Referenced by FirstPython.FirstPython.process(), PyClassificationDNN.PyClassificationDNN.process(), PyCoralClassify.PyCoralClassify.process(), PyCoralDetect.PyCoralDetect.process(), PyCoralSegment.PyCoralSegment.process(), PyDetectionDNN.PyDetectionDNN.process(), PyDMTX.PyDMTX.process(), PythonObject6D.PythonObject6D.process(), PythonOpenCV.PythonOpenCV.process(), PythonParallel.PythonParallel.process(), PythonSandbox.PythonSandbox.process(), AprilTag.AprilTag.processGUI(), PyCoralClassify.PyCoralClassify.processGUI(), PyCoralDetect.PyCoralDetect.processGUI(), PyCoralSegment.PyCoralSegment.processGUI(), PyFaceMesh.PyFaceMesh.processGUI(), PyHandDetector.PyHandDetector.processGUI(), PyLicensePlate.PyLicensePlate.processGUI(), PyObjectron.PyObjectron.processGUI(), PyPoseDetector.PyPoseDetector.processGUI(), PySceneText.PySceneText.processGUI(), PySelfie.PySelfie.processGUI(), PythonOpenCV.PythonOpenCV.processGUI(), PythonSandbox.PythonSandbox.processGUI(), PythonTest.PythonTest.processGUI(), FirstPython.FirstPython.processNoUSB(), PythonObject6D.PythonObject6D.processNoUSB(), and PythonSandbox.PythonSandbox.processNoUSB().
PythonObject6D.PythonObject6D.wincorners |
Definition at line 163 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.winh |
Definition at line 126 of file PythonObject6D.py.
Referenced by PythonObject6D.PythonObject6D.drawDetections(), and PythonObject6D.PythonObject6D.estimatePose().
PythonObject6D.PythonObject6D.winleft |
Definition at line 124 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.wintop |
Definition at line 123 of file PythonObject6D.py.
PythonObject6D.PythonObject6D.winw |
Definition at line 125 of file PythonObject6D.py.
Referenced by PythonObject6D.PythonObject6D.drawDetections(), and PythonObject6D.PythonObject6D.estimatePose().