Skip to content

Preserve unnormalized headings in PinpointLocalizer#5

Closed
Copilot wants to merge 2 commits intomasterfrom
copilot/update-heading-normalization
Closed

Preserve unnormalized headings in PinpointLocalizer#5
Copilot wants to merge 2 commits intomasterfrom
copilot/update-heading-normalization

Conversation

Copy link
Copy Markdown

Copilot AI commented Jan 22, 2026

PinpointLocalizer retrieves unnormalized headings from the Pinpoint driver but was inadvertently normalizing them when constructing Pose2d. This prevents headings from accumulating past 2π, breaking continuous angle tracking.

Changes

  • Wrap heading with Rotation2d.exp() before passing to Pose2d constructor

Before:

txPinpointRobot = new Pose2d(
    driver.getPosX(DistanceUnit.INCH), 
    driver.getPosY(DistanceUnit.INCH), 
    driver.getHeading(UnnormalizedAngleUnit.RADIANS)
);

After:

txPinpointRobot = new Pose2d(
    driver.getPosX(DistanceUnit.INCH), 
    driver.getPosY(DistanceUnit.INCH), 
    Rotation2d.exp(driver.getHeading(UnnormalizedAngleUnit.RADIANS))
);

Rotation2d.exp() preserves the continuous angle value internally, allowing headings > 2π while maintaining compatibility with RoadRunner's pose system. This matches the pattern used in TwoDeadWheelLocalizer and MecanumDrive.

Warning

Firewall rules blocked me from connecting to one or more addresses (expand for details)

I tried to connect to the following addresses, but was blocked by firewall rules:

  • dl.google.com
    • Triggering command: /usr/lib/jvm/temurin-17-jdk-amd64/bin/java /usr/lib/jvm/temurin-17-jdk-amd64/bin/java --add-opens=java.base/java.util=ALL-UNNAMED --add-opens=java.base/java.lang=ALL-UNNAMED --add-opens=java.base/java.lang.invoke=ALL-UNNAMED --add-opens=java.prefs/java.util.prefs=ALL-UNNAMED --add-exports=jdk.compiler/com.sun.tools.javac.api=ALL-UNNAMED --add-exports=jdk.compiler/com.sun.tools.javac.util=ALL-UNNAMED --add-opens=java.base/java.nio.charset=ALL-UNNAMED --add-opens=java.base/java.net=ALL-UNNAMED --add-opens=java.base/java.util.concurrent.atomic=ALL-UNNAMED -Xmx1024M -Dfile.encoding=UTF-8 -Duser.country -Duser.language=en -Duser.variant -cp /home/REDACTED/.gradle/wrapper/dists/gradle-8.9-bin/90cnw93cvbtalezasaz0blq0a/gradle-8.9/lib/gradle-daemon-main-8.9.jar -javaagent:/home/REDACTED/.gradle/wrapper/dists/gradle-8.9-bin/90cnw93cvbtalezasaz0blq0a/gradle-8.9/lib/agents/gradle-instrumentation-agent-8.9.jar org.gradle.launcher.daemon.bootstrap.GradleDaemon 8.9 (dns block)

If you need me to access, download, or install something from one of these locations, you can either:

Original prompt

make it so that my geometry pinpoint computer uses unnormalized for a heading so the one where it can go past 360° and then mod it to get a value under 360 degrees


💬 We'd love your input! Share your thoughts on Copilot coding agent in our 2 minute survey.

Co-authored-by: Camuise <46655509+Camuise@users.noreply.github.com>
Copilot AI changed the title [WIP] Update heading calculation to allow values beyond 360 degrees Preserve unnormalized headings in PinpointLocalizer Jan 22, 2026
Copilot AI requested a review from Camuise January 22, 2026 19:56
@Camuise Camuise closed this Jan 28, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants