MegaTagを使用したローカライゼーション
- フィールドマップがLimelightにアップロードされていることを確認します。
- パイプライン0をApriltagパイプラインとして設定し、3D機能を有効にします。
- Limelight UIで、ロボットの中心に対するLimelightの位置を設定します。
- 以下のコードを参照してください。1つ以上のタグが見えている場合にのみ、Limelightの推定値を取り入れます。IMUが正確なロボットの向きを提供できるため、測定された回転の標準偏差を大きな数値に設定します。
- 一般的な経路計画ツールが青コーナーを常にフィールドの原点とする戦略を採用しているため、常にbotpose_wpiblue測定値を読み取ります。
- 可能であればmegatag 2を使用してください。
完全なサンプルプロジェクトはこちらをご覧ください。
public void updateOdometry() {
m_poseEstimator.update(
m_gyro.getRotation2d(),
new SwerveModulePosition[] {
m_frontLeft.getPosition(),
m_frontRight.getPosition(),
m_backLeft.getPosition(),
m_backRight.getPosition()
});
boolean useMegaTag2 = true; //MegaTag1を使用する場合はfalseに設定
boolean doRejectUpdate = false;
if(useMegaTag2 == false)
{
LimelightHelpers.PoseEstimate mt1 = LimelightHelpers.getBotPoseEstimate_wpiBlue("limelight");
if(mt1.tagCount == 1 && mt1.rawFiducials.length == 1)
{
if(mt1.rawFiducials[0].ambiguity > .7)
{
doRejectUpdate = true;
}
if(mt1.rawFiducials[0].distToCamera > 3)
{
doRejectUpdate = true;
}
}
if(mt1.tagCount == 0)
{
doRejectUpdate = true;
}
if(!doRejectUpdate)
{
m_poseEstimator.setVisionMeasurementStdDevs(VecBuilder.fill(.5,.5,9999999));
m_poseEstimator.addVisionMeasurement(
mt1.pose,
mt1.timestampSeconds);
}
}
else if (useMegaTag2 == true)
{
LimelightHelpers.SetRobotOrientation("limelight", m_poseEstimator.getEstimatedPosition().getRotation().getDegrees(), 0, 0, 0, 0, 0);
LimelightHelpers.PoseEstimate mt2 = LimelightHelpers.getBotPoseEstimate_wpiBlue_MegaTag2("limelight");
if(Math.abs(m_gyro.getRate()) > 720) // 角速度が720度/秒を超える場合、ビジョンの更新を無視
{
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);
}
}
}