diff --git a/.gitignore b/.gitignore index 9d4be70..a1ed748 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,3 @@ -/venv/ -/.idea/ -/.vscode/ -*.xml +/cmake-build-debug/ +/calibration_images/ +/.idea/ \ No newline at end of file diff --git a/ArucoTag/ArucoTag_PanneauxSolaire.png b/ArucoTag/ArucoTag_PanneauxSolaire.png deleted file mode 100644 index bd7e2d8..0000000 Binary files a/ArucoTag/ArucoTag_PanneauxSolaire.png and /dev/null differ diff --git a/ArucoTag/ArucoTag_PurpleFlower.png b/ArucoTag/ArucoTag_PurpleFlower.png deleted file mode 100644 index 2ef2e29..0000000 Binary files a/ArucoTag/ArucoTag_PurpleFlower.png and /dev/null differ diff --git a/ArucoTag/ArucoTag_WhiteFlower.png b/ArucoTag/ArucoTag_WhiteFlower.png deleted file mode 100644 index a02254d..0000000 Binary files a/ArucoTag/ArucoTag_WhiteFlower.png and /dev/null differ diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..4e0270d --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,34 @@ +cmake_minimum_required(VERSION 3.27) +project(detection_pot) + +set(CMAKE_CXX_STANDARD 17) + +find_package( OpenCV REQUIRED ) +include_directories( ${OpenCV_INCLUDE_DIRS} ) + +set(COMMON_SOURCES + utils/utils.h +) + +set(calibrationSources + ${COMMON_SOURCES} + calibration.cpp +) + +add_executable(calibration ${calibrationSources}) + +target_link_libraries( calibration ${OpenCV_LIBS} ) + +# Project 2 sources and executable +set(arucoDetectionSources + ${COMMON_SOURCES} + arucoDetector.cpp + utils/ArucoTag.cpp + utils/ArucoTag.h + utils/ArucoDetector.cpp + utils/ArucoDetector.h +) + +add_executable(arucoDetector ${arucoDetectionSources}) + +target_link_libraries( arucoDetector ${OpenCV_LIBS} ) \ No newline at end of file diff --git a/Pot-plante.tfrecord b/Pot-plante.tfrecord deleted file mode 100644 index e758d36..0000000 Binary files a/Pot-plante.tfrecord and /dev/null differ diff --git a/Pot-plante_label_map.pbtxt b/Pot-plante_label_map.pbtxt deleted file mode 100644 index 7c8cc54..0000000 --- a/Pot-plante_label_map.pbtxt +++ /dev/null @@ -1,30 +0,0 @@ -item { - name: "plante_dans_pot_couchee", - id: 1, - display_name: "plante_dans_pot_couchee" -} -item { - name: "plante_dans_pot_debout", - id: 2, - display_name: "plante_dans_pot_debout" -} -item { - name: "plante_fragile_couchee", - id: 3, - display_name: "plante_fragile_couchee" -} -item { - name: "plante_fragile_debout", - id: 4, - display_name: "plante_fragile_debout" -} -item { - name: "pot_vide_couche", - id: 5, - display_name: "pot_vide_couche" -} -item { - name: "pot_vide_debout", - id: 6, - display_name: "pot_vide_debout" -} diff --git a/README.md b/README.md deleted file mode 100644 index 8424211..0000000 --- a/README.md +++ /dev/null @@ -1,8 +0,0 @@ -# Detection de pot | Coupe de france de robotique - -### Description -Ce repo correspond a la detection de pot de fleur pour la coupe de france de robotique 2023 -Réaliser par la team Modelec ! - -### Tech -opencv: python v4.8 diff --git a/WIN_20231123_18_41_25_Pro.jpg b/WIN_20231123_18_41_25_Pro.jpg deleted file mode 100644 index 08ee2d7..0000000 Binary files a/WIN_20231123_18_41_25_Pro.jpg and /dev/null differ diff --git a/aruco.py b/aruco.py deleted file mode 100644 index e667ce4..0000000 --- a/aruco.py +++ /dev/null @@ -1,137 +0,0 @@ -import cv2 as cv -import cv2.aruco as aruco -import numpy as np - -# Focal de la cam -# Calculer la focal avec le fichier get_the_focal.py -# FOCAL_LENGTH = 1444 # Téléphone Maxime pixel 7 pro -FOCAL_LENGTH = 1470 -# FOCAL_LENGTH = 600 - -arucoTagMapping = { - 47: ["Panneau solaire", 3.62], - 36: ["Fleur blanche", 2], - 13: ["FLeur violette", 2] -} - -# Charger une image depuis la caméra (0 pour la caméra par défaut, généralement la webcam) -cap = cv.VideoCapture(0) - -# Définir le dictionnaire ArUco -aruco_dict = aruco.getPredefinedDictionary(aruco.DICT_4X4_50) - -# Créer le détecteur ArUco -parameters = aruco.DetectorParameters() - -# -detector = aruco.ArucoDetector(aruco_dict, parameters) - -while True: - - # Lire une image depuis la caméra - ret, frame = cap.read() - - # Convertir l'image en niveaux de gris - gray = cv.cvtColor(frame, cv.COLOR_BGR2GRAY) - - # Détecter les marqueurs ArUco - corners, ids, rejectedImgPoints = detector.detectMarkers(gray) - - # Dessiner les résultats - if ids is not None: - # aruco.drawDetectedMarkers(frame, corners, ids) - - for i in range(len(ids)): - - if len(corners) > 0: - ids = ids.flatten() - for (markerCorner, markerID) in zip(corners, ids): - - if markerID not in arucoTagMapping: - continue - - try: - tagCorners = markerCorner.reshape((4, 2)) - except: - print("Error with the corners") - continue - - (topLeft, topRight, bottomRight, bottomLeft) = tagCorners - - topRight = (int(topRight[0]), int(topRight[1])) - topLeft = (int(topLeft[0]), int(topLeft[1])) - bottomRight = (int(bottomRight[0]), int(bottomRight[1])) - bottomLeft = (int(bottomLeft[0]), int(bottomLeft[1])) - - center_x = int((topLeft[0] + topRight[0] + bottomRight[0] + bottomLeft[0]) / 4) - center_y = int((topLeft[1] + topRight[1] + bottomRight[1] + bottomLeft[1]) / 4) - - # Calculate the apparent width in pixels - P = np.sqrt((topRight[0] - topLeft[0]) ** 2 + (topRight[1] - topLeft[1]) ** 2) - - # Calculate the distance to the Aruco tag - D = (arucoTagMapping[markerID][1] * FOCAL_LENGTH) / P - - tag_position_x = (topRight[0] + topLeft[0]) / 2 - tag_position_y = (topRight[1] + bottomRight[1]) / 2 - - image_width = frame.shape[1] - image_height = frame.shape[0] - - # Calcul de l'angle horizontal par rapport au centre de l'image - angle_to_tag_horizontal = np.arctan2(tag_position_x - (image_width / 2), - image_width / (2 * np.tan(np.radians(60)))) - - # Conversion de l'angle en degrés - angle_to_tag_horizontal_deg = np.degrees(angle_to_tag_horizontal) - - # Calculate the difference in the x and y coordinates - dx = topRight[0] - topLeft[0] - dy = topRight[1] - topLeft[1] - - # Calculate the angle in radians - angle_radians = np.arctan2(dy, dx) - - # Convert the angle to degrees - angle_degrees = np.degrees(angle_radians) - - # Print the rotation angle of the ArUco tag - sens_du_tag = "" - if -15 < angle_degrees < 15: - sens_du_tag = "debout" - elif 15 < angle_degrees < 60: - sens_du_tag = "penche a droite" - elif 60 < angle_degrees < 110: - sens_du_tag = "tombe a droite" - elif 110 < angle_degrees < 180: - sens_du_tag = "a l'envers" - elif -180 < angle_degrees < -110: - sens_du_tag = "a l'envers" - elif -110 < angle_degrees < -60: - sens_du_tag = "tombe a gauche" - elif -60 < angle_degrees < -15: - sens_du_tag = "penche a gauche" - - # Affichage des informations - cv.putText(frame, f"{arucoTagMapping[markerID][0]}, id : {markerID}", (topLeft[0], topLeft[1] - 90), - cv.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 255), 3) - distance_str = "{:.2f}".format(D) - cv.putText(frame, f"Distance : {distance_str} cm", (topLeft[0], topLeft[1] - 60), - cv.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 255), 3) - angle_str = "{:.2f}".format(angle_to_tag_horizontal_deg) - cv.putText(frame, f"Angle horizontale : {angle_str} degrees", (topLeft[0], topLeft[1] - 30), - cv.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 255), 3) - cv.putText(frame, f"Le tag est {sens_du_tag}", (topLeft[0], topLeft[1]), - cv.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 255), 3) - - # print(f"{arucoTagMapping[markerID][0]} : {angle_to_tag_horizontal_deg} degrees, {D} cm") - # Afficher l'image - cv.imshow('Frame', frame) - - # Sortir de la boucle si la touche 'q' est enfoncée - if cv.waitKey(1) & 0xFF == ord('q'): - break - -# Libérer la capture et fermer la fenêtre -cap.release() -cv.destroyAllWindows() diff --git a/arucoDetector.cpp b/arucoDetector.cpp new file mode 100644 index 0000000..6ff7f0b --- /dev/null +++ b/arucoDetector.cpp @@ -0,0 +1,57 @@ +#include + +#include "utils/ArucoDetector.h" + +int main(int argc, char *argv[]) +{ + // Settup argument parser + + if (argc < 3) { + std::cout << "Usage: " << argv[0] << "