@@ -388,24 +388,46 @@ void aruco_detector::ArucoDetectorNode::imageCallback(const sensor_msgs::msg::Im
388388 for (size_t i = 0 ; i < marker_ids.size (); i++)
389389 {
390390 int id = marker_ids[i];
391+ if (id == 0 ){
392+ continue ;
393+ }
394+ id_detection_counter_[id]+=1 ;
395+
391396 bool new_id = false ;
392397 static std::string time = ros2TimeToString (msg->header .stamp );
393- if (std::find (ids_detected_.begin (), ids_detected_.end (), id) == ids_detected_.end ()) {
394- ids_detected_.push_back (id);
398+
399+ // If the id is not already in ids_detected_, add it
400+ if (std::find (ids_detected_once_.begin (), ids_detected_once_.end (), id) == ids_detected_once_.end ()) {
401+ ids_detected_once_.push_back (id);
395402 new_id = true ;
396- }
397- if (new_id) {
398- // Define the directory path
399- std::string directory = " detected-aruco-markers/" ;
400-
403+ // Define the directory path
404+ if (new_id){
405+ std::string directory = " detected-aruco-markers-stream/" ;
406+
401407 // Check if the directory exists, if not, create it
402408 if (!std::filesystem::exists (directory)) {
403409 std::filesystem::create_directory (directory);
404410 }
405-
411+
406412 // Write to the file in the specified directory
407- writeIntsToFile (directory + " detected_markers" + time + " .csv" , ids_detected_);
413+ writeIntsToFile (directory + " detected_markers" + time + " .csv" , ids_detected_once_);
414+ }
415+ }
416+ // Check if this id has been detected five times
417+ if (id_detection_counter_[id] == 5 ) {
418+ ids_detected_secure_.push_back (id);
419+ // Define the directory path
420+ std::string directory_secure = " detected-aruco-markers-unique/" ;
421+
422+ // Check if the directory_secure exists, if not, create it
423+ if (!std::filesystem::exists (directory_secure)) {
424+ std::filesystem::create_directory (directory_secure);
425+ }
426+
427+ // Write to the file in the specified directory_secure
428+ writeIntsToFile (directory_secure + " detected_markers" + time + " .csv" , ids_detected_secure_);
408429 }
430+
409431 cv::Vec3d rvec = rvecs[i];
410432 cv::Vec3d tvec = tvecs[i];
411433 tf2::Quaternion quat = rvec_to_quat (rvec);
0 commit comments