דלג לתוכן הראשי

איתור רובוט עם MegaTag2

MegaTag2, שהוצג בשנת 2024, הוא מאתר מבוסס AprilTag מדויק וחד-משמעי לרובוטים ניידים. הוא נבנה עם המטרות הבאות:

  • לבטל את בעיית העמימות בתנוחה ולהגביר את העמידות כנגד רעשי תמונה/פינות.
  • לספק הערכות תנוחה מצוינות בהינתן תג יחיד, ללא קשר לפרספקטיבה.
  • להגביר את העמידות כנגד אי-דיוקים בהצבה הפיזית של AprilTag
  • להפחית את כמות הסינון הנדרשת לתוצאות טובות של הערכת תנוחה

MegaTag2 מספק תוצאות מצוינות בכל מרחק בהינתן תג יחיד. משמעות הדבר היא שאפשר להתמקד רק בתגים שהם גם רלוונטיים וגם בתוך הסבולת, ולסנן את כל התגים האחרים. אם תג אינו במיקום הנכון, סנן אותו עם תכונת הסינון הדינמי שהוצגה יחד עם MegaTag2.

int[] validIDs = {3,4};
LimelightHelpers.SetFiducialIDFiltersOverride("limelight", validIDs);

בניגוד ל-MT1, MT2 מניח שאתה יודע את כיוון הרובוט (yaw). באופן אופציונלי, MegaTag2 מקבל אוריינטציה מלאה של הרובוט ומהירויות זוויתיות.

דרישות:

  • תנוחת הרובוט של ה-Limelight שלך הוגדרה בממשק הווב או דרך ה-API
  • מפת שדה (.fmap) הועלתה
  • LimelightHelpers.SetRobotOrientation(robotYawInDegrees,0,0,0,0,0) נקרא בכל פריים בקוד בצד הרובוט
  • SetRobotOrientation מניח מקור ממורכז (ראה את יוצר המפות) או בפינה הכחולה. חיובי בכיוון נגד כיוון השעון, 0 מעלות -> פונה לקיר הברית האדומה ב-FRC.

מפתחות NetworkTables:

  • botpose_orb_wpiblue
  • botpose_orb_wpired
  • botpose_orb

מפתחות JSON:

  • botpose_orb_wpiblue
  • botpose_orb_wpired
  • botpose_orb
  • (לכל מטרת fiducial) t6r_fs_orb - תנוחת הרובוט במרחב השדה באמצעות megatag2 על סמך תג זה בלבד (ללא multitag)

שים לב להבדל בין MegaTag2 (רובוט אדום) ו-Megatag (רובוט כחול) במקרה זה של תג יחיד עם עמימות גבוהה


  • גליל זהב / רובוט אדום: תנוחת botpose של Megatag2 ללא סינון
  • גלילים צהובים: תנוחות botpose של Megatag2 לתג יחיד ללא סינון

  • גליל לבן/רובוט כחול: תנוחת MegaTag1 Botpose
  • גליל ירוק: תנוחת רובוט אינדיבידואלית לכל תג (MT1)
  • גליל כחול: ממוצע של תנוחות רובוט אינדיבידואליות לכל תג (MT1)

info

בשנת 2024, רוב המערכת האקולוגית של WPILib עברה למערכת קואורדינטות עם מקור יחיד. בשנת 2023, מקור מערכת הקואורדינטות שלך השתנה בהתבסס על צבע הברית שלך.

עבור 2024 ואילך, מקור מערכת הקואורדינטות שלך צריך להיות תמיד המקור "הכחול". קבוצות FRC צריכות תמיד להשתמש ב-botpose_orb_wpiblue עבור פונקציונליות הקשורה לתנוחה

שימוש במעריך התנוחה של WPILib

  LimelightHelpers.SetRobotOrientation("limelight", m_poseEstimator.getEstimatedPosition().getRotation().getDegrees(), 0, 0, 0, 0, 0);
LimelightHelpers.PoseEstimate mt2 = LimelightHelpers.getBotPoseEstimate_wpiBlue_MegaTag2("limelight");

// אם המהירות הזוויתית שלנו גדולה מ-360 מעלות לשנייה, התעלם מעדכוני ראייה
if(Math.abs(m_gyro.getRate()) > 360)
{
doRejectUpdate = true;
}
if(mt2.tagCount == 0)
{
doRejectUpdate = true;
}
if(!doRejectUpdate)
{
m_poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(.7,.7,9999999));
m_poseEstimator.addVisionMeasurement(
mt2.pose,
mt2.timestampSeconds);
}

הגדרת תנוחת הרובוט של ה-Limelight שלך

LL Forward, LL Right, ו-LL Up מייצגים מרחקים לאורך וקטורי הקדימה, ימינה ולמעלה של הרובוט אם היית מגלם את הרובוט. (במטרים). LL Roll, Pitch, ו-Yaw מייצגים את הסיבוב של ה-Limelight שלך במעלות. אתה יכול לשנות ערכים אלה ולצפות במודל התלת-ממדי של ה-Limelight משתנה בצופה התלת-ממדי. Limelight משתמש בתצורה זו באופן פנימי כדי לעבור מתנוחת המטרה במרחב המצלמה -> תנוחת הרובוט במרחב השדה.

שימוש ב-IMU המובנה של Limelight 4 עם "imumode_set" / SetIMUMode()

ל-Limelight 4 יש IMU מובנה. אתה יכול להשתמש בזה עם MT2 כדי לקבל הערכות תנוחה מדויקות יותר בזמן פנייה. עליך לזרוע את האוריינטציה הראשונית של ה-IMU לפני שזה יעבוד. זה נקרא "זריעה". ברגע שה-limelight שלך יודע את האוריינטציה הראשונית של הרובוט שלך, הוא יוכל לעדכן את האוריינטציה של הרובוט שלך באופן עצמאי כדי לבצע חישובי MT2.

כדי להשתמש ב-IMU של LL4, כרגע ה-LL שלך חייב להיות מותקן במצב "נוף" (landscape).

הזרימה נראית כך:

  1. קרא ל-SetRobotOrientation() עם ה-IMU "החיצוני" שלך כמו Pigeon או NavX. אתה יכול להמשיך לקרוא לשיטה זו לעתים קרובות ככל שתרצה.
  2. קרא ל-SetIMUMode() כדי להגדיר כיצד ה-Limelight שלך משתמש בנתוני IMU מ-IMU פנימיים וחיצוניים.
  3. באופן כללי, השתמש במצב 1 בזמן שהרובוט שלך ממתין לתחילת תקופת האוטונומי. עבור למצב 2 בזמן שהרובוט מופעל או בזמן שהוא מופעל ופונה.

איפוס / זריעה

  • כדי לאפס את ה-yaw המשולב של הרובוט ב-IMU הפנימי ל-yaw שהוגש באמצעות SetRobotOrientation(), הגדר את מצב ה-IMU של ה-Limelight שלך ל-1 עם LimelightHelpers.SetIMUMode().
  • בזמן זריעה, MegaTag2 ימשיך להשתמש בערך ה-yaw שהוגש באמצעות SetRobotOrientation().

שימוש ב-IMU הפנימי עם MegaTag2

כדי לאפשר ל-LL4 להשתמש ב-IMU הפנימי שלו לאיתור MT2, הגדר את מצב ה-IMU של ה-Limelight שלך ל-2 עם LimelightHelpers.SetIMUMode().

מצבי IMU:

  • 0 - השתמש ב-yaw של IMU חיצוני שהוגש באמצעות SetRobotOrientation() לאיתור MT2. ה-IMU הפנימי נעלם לחלוטין.
  • 1 - השתמש ב-yaw של IMU חיצוני שהוגש באמצעות SetRobotOrientation(), והגדר את ה-yaw המשולב של ה-IMU הפנימי של LL4 כך שיתאים לערך ה-yaw שהוגש.
  • 2 - השתמש ב-IMU פנימי לאיתור MT2.
  • 3 -