Localização com MegaTag
- Certifique-se de que um mapa de campo esteja carregado em seu Limelight.
- Configure o pipeline 0 como um Pipeline Apriltag e ative a funcionalidade 3D
- Configure a pose do seu Limelight em relação ao centro do seu robô na interface do Limelight
- Veja o código abaixo. Nós só incorporamos as estimativas do Limelight quando mais de uma tag está visível. Definimos o desvio padrão da rotação medida para um número grande porque podemos confiar em nosso IMU para nos dar a orientação correta do robô.
- Sempre lemos a medição botpose_wpiblue porque as ferramentas comuns de planejamento de trajetória adotaram uma estratégia de origem de campo sempre no canto azul.
- Use megatag 2 se possível.
Veja o projeto de exemplo completo aqui
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; //defina como false para usar MegaTag1
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) // se nossa velocidade angular for maior que 720 graus por segundo, ignore as atualizações de visão
{
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);
}
}
}