Skip to content

Commit

Permalink
working camera sim
Browse files Browse the repository at this point in the history
  • Loading branch information
sswadkar committed Feb 17, 2024
1 parent d98016c commit 50dbd64
Show file tree
Hide file tree
Showing 8 changed files with 150 additions and 75 deletions.
25 changes: 14 additions & 11 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -1,4 +1,9 @@
{
"Keyboard 0 Settings": {
"window": {
"visible": true
}
},
"System Joysticks": {
"window": {
"visible": false
Expand All @@ -20,9 +25,17 @@
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
},
{
"decKey": 75,
"incKey": 74
},
{
"decKey": 76,
"incKey": 73
}
],
"axisCount": 3,
"axisCount": 5,
"buttonCount": 4,
"buttonKeys": [
90,
Expand All @@ -45,16 +58,6 @@
"povCount": 1
},
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
},
{
"decKey": 73,
"incKey": 75
}
],
"axisCount": 2,
"buttonCount": 4,
"buttonKeys": [
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,10 @@ fun Pose3d.toDoubleArray(): Array<Double> {
this.x.inMeters,
this.y.inMeters,
this.z.inMeters,
this.rotation.x.inRadians,
this.rotation.y.inRadians,
this.rotation.z.inRadians
this.rotation.quaternion.w.inRadians,
this.rotation.quaternion.x.inMeters,
this.rotation.quaternion.y.inMeters,
this.rotation.quaternion.z.inMeters
)
}

Expand Down
8 changes: 2 additions & 6 deletions src/main/kotlin/com/team4099/robot2023/RobotContainer.kt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ import com.team4099.robot2023.subsystems.superstructure.Request
import com.team4099.robot2023.subsystems.superstructure.Superstructure
import com.team4099.robot2023.subsystems.vision.Vision
import com.team4099.robot2023.subsystems.vision.camera.CameraIOPhotonvision
import com.team4099.robot2023.subsystems.vision.camera.CameraIOSim
import com.team4099.robot2023.subsystems.wrist.Wrist
import com.team4099.robot2023.subsystems.wrist.WristIO
import com.team4099.robot2023.subsystems.wrist.WristIOSim
Expand Down Expand Up @@ -74,12 +75,7 @@ object RobotContainer {
} else {
// Simulation implementations
drivetrain = Drivetrain(object : GyroIO {}, DrivetrainIOSim)
vision =
Vision(
CameraIOPhotonvision("parakeet_1"),
CameraIOPhotonvision("parakeet_2"),
CameraIOPhotonvision("parakeet_3")
)
vision = Vision(CameraIOSim("skrt"))
limelight = LimelightVision(object : LimelightVisionIO {})
intake = Intake(IntakeIOSim)
feeder = Feeder(FeederIOSim)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,28 @@ package com.team4099.robot2023.config.constants

import org.team4099.lib.apriltag.AprilTag
import org.team4099.lib.geometry.Pose3d
import org.team4099.lib.geometry.Rotation3d
import org.team4099.lib.geometry.Translation3d
import org.team4099.lib.units.base.feet
import org.team4099.lib.units.base.inMeters
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.derived.degrees
import org.team4099.lib.units.derived.radians

object FieldConstants {
val fieldLength = 54.feet
val fieldWidth = 26.feet

val aprilTags: List<AprilTag> = listOf()
val aprilTags: List<AprilTag> =
listOf(
AprilTag(
0,
Pose3d(
Translation3d(1.0.meters, 5.0.meters, 2.0.meters),
Rotation3d(0.0.radians, 0.0.radians, 180.degrees)
)
)
)
val homeAprilTags: List<AprilTag> = listOf()

val wpilibAprilTags =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@ package com.team4099.robot2023.subsystems.vision

import com.team4099.lib.hal.Clock
import com.team4099.lib.logging.TunableNumber
import com.team4099.robot2023.config.constants.FieldConstants
import com.team4099.lib.vision.TimestampedVisionUpdate
import com.team4099.robot2023.config.constants.FieldConstants
import com.team4099.robot2023.config.constants.VisionConstants
import com.team4099.robot2023.subsystems.vision.camera.CameraIO
import edu.wpi.first.math.VecBuilder
Expand All @@ -14,15 +14,12 @@ import org.team4099.lib.geometry.Pose2d
import org.team4099.lib.geometry.Pose2dWPILIB
import org.team4099.lib.geometry.Pose3d
import org.team4099.lib.geometry.Pose3dWPILIB
import org.team4099.lib.geometry.Quaternion
import org.team4099.lib.geometry.Rotation3d
import org.team4099.lib.units.base.Time
import org.team4099.lib.units.base.inMeters
import org.team4099.lib.units.base.inMilliseconds
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.base.seconds
import org.team4099.lib.units.derived.degrees
import org.team4099.lib.units.derived.radians
import java.util.function.Consumer
import java.util.function.Supplier
import kotlin.math.pow
Expand Down Expand Up @@ -86,6 +83,7 @@ class Vision(vararg cameras: CameraIO) : SubsystemBase() {
val visionUpdates = mutableListOf<TimestampedVisionUpdate>()

for (instance in io.indices) {
val currentPose = fieldFramePoseSupplier.get()

lastFrameTimes[instance] = Clock.fpgaTime
val timestamp = inputs[instance].timestamp
Expand Down Expand Up @@ -119,7 +117,7 @@ class Vision(vararg cameras: CameraIO) : SubsystemBase() {
val thetaStdDev = thetaStdDev.get() * averageDistance.inMeters.pow(2) / tagPoses.size

visionUpdates.add(
PoseEstimator.TimestampedVisionUpdate(
TimestampedVisionUpdate(
timestamp, robotPose, VecBuilder.fill(xyStdDev, xyStdDev, thetaStdDev)
)
)
Expand All @@ -139,7 +137,6 @@ class Vision(vararg cameras: CameraIO) : SubsystemBase() {
*tagPoses.map { it.pose3d }.toTypedArray()
)


if (inputs[instance].timestamp == 0.0.seconds) { // prolly wrong lol
Logger.recordOutput(
"Vision/${VisionConstants.CAMERA_NAMES[instance]}/estimatedRobotPose",
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
package com.team4099.robot2023.subsystems.vision.camera

import com.team4099.lib.logging.toDoubleArray
import org.littletonrobotics.junction.LogTable
import org.littletonrobotics.junction.inputs.LoggableInputs
import org.team4099.lib.geometry.Pose3d
Expand All @@ -16,20 +17,16 @@ interface CameraIO {

override fun toLog(table: LogTable?) {
table?.put("timestampSeconds", timestamp.inSeconds)
table?.put("frame", frame.pose3d)
table?.put("frame", frame.toDoubleArray().toDoubleArray())
table?.put("fps", fps)
table?.put("usedTargets", usedTargets)
table?.put("usedTargets", usedTargets.toIntArray())
}

override fun fromLog(table: LogTable?) {
table?.get("timestampSeconds", 0.0)?.let {
timestamp = it.seconds
}
table?.get("frame", Pose3dWPILIB())?.let {
frame = Pose3d(it)
}
table?.get("fps", 0.0)
table?.get("usedTargets", listOf<Double>())
table?.get("timestampSeconds", 0.0)?.let { timestamp = it.seconds }
table?.get("frame", Pose3dWPILIB())?.let { frame = Pose3d(it[0]) }
table?.get("fps", 0.0).let { fps = it ?: 0.0 }
table?.get("usedTargets", IntArray(0)).let { usedTargets = it?.toList() ?: listOf() }
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,51 +5,50 @@ import org.photonvision.EstimatedRobotPose
import org.photonvision.PhotonCamera
import org.photonvision.PhotonPoseEstimator
import org.photonvision.PhotonPoseEstimator.PoseStrategy
import org.team4099.lib.around
import org.team4099.lib.geometry.Pose3d
import org.team4099.lib.geometry.Pose3dWPILIB
import org.team4099.lib.geometry.Transform3dWPILIB
import org.team4099.lib.units.base.Time
import org.team4099.lib.units.base.inSeconds
import org.team4099.lib.units.base.seconds
import org.team4099.lib.units.micro
import org.team4099.lib.units.milli
import java.util.*


class CameraIOPhotonvision(private val identifier: String): CameraIO {

private val photonEstimator: PhotonPoseEstimator
private val camera: PhotonCamera
private var lastEstTimestamp: Time = 0.0.seconds

init {
camera = PhotonCamera(identifier)
photonEstimator = PhotonPoseEstimator(
FieldConstants.wpilibFieldLayout, PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR, camera, Transform3dWPILIB()
)
photonEstimator.setMultiTagFallbackStrategy(PoseStrategy.LOWEST_AMBIGUITY)

import java.util.Optional

class CameraIOPhotonvision(private val identifier: String) : CameraIO {

private val photonEstimator: PhotonPoseEstimator
private val camera: PhotonCamera
private var lastEstTimestamp: Time = 0.0.seconds

init {
camera = PhotonCamera(identifier)
photonEstimator =
PhotonPoseEstimator(
FieldConstants.wpilibFieldLayout,
PoseStrategy.MULTI_TAG_PNP_ON_COPROCESSOR,
camera,
Transform3dWPILIB()
)
photonEstimator.setMultiTagFallbackStrategy(PoseStrategy.LOWEST_AMBIGUITY)
}

override fun updateInputs(inputs: CameraIO.CameraInputs) {
val visionEst: Optional<EstimatedRobotPose>? = photonEstimator.update()
val poseEst = visionEst?.get()?.let { Pose3d(it.estimatedPose) }
val latestTimestamp = visionEst?.get()?.timestampSeconds?.seconds
if (latestTimestamp != null) {
if ((latestTimestamp - lastEstTimestamp).absoluteValue > 10.micro.seconds) {
inputs.fps = 1 / (latestTimestamp - lastEstTimestamp).inSeconds
lastEstTimestamp = latestTimestamp
}
}

override fun updateInputs(inputs: CameraIO.CameraInputs) {
val visionEst: Optional<EstimatedRobotPose>? = photonEstimator.update()
val poseEst = visionEst?.get()?.let { Pose3d(it.estimatedPose) }
val latestTimestamp = visionEst?.get()?.timestampSeconds?.seconds
if (latestTimestamp != null) {
if ((latestTimestamp - lastEstTimestamp).absoluteValue > 10.micro.seconds) {
inputs.fps = 1/(latestTimestamp - lastEstTimestamp).inSeconds
lastEstTimestamp = latestTimestamp
}
}

if (visionEst != null) {
inputs.usedTargets = visionEst.get().targetsUsed.map { it.fiducialId }
}
if (visionEst != null) {
inputs.usedTargets = visionEst.get().targetsUsed.map { it.fiducialId }
}

inputs.timestamp = lastEstTimestamp
if (poseEst != null) {
inputs.frame = poseEst
}
inputs.timestamp = lastEstTimestamp
if (poseEst != null) {
inputs.frame = poseEst
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
package com.team4099.robot2023.subsystems.vision.camera

import com.team4099.lib.hal.Clock
import com.team4099.lib.logging.toDoubleArray
import com.team4099.robot2023.config.constants.FieldConstants
import com.team4099.robot2023.config.constants.VisionConstants
import com.team4099.robot2023.util.toPose3d
import com.team4099.robot2023.util.toTransform3d
import edu.wpi.first.networktables.DoubleArraySubscriber
import edu.wpi.first.networktables.NetworkTableInstance
import org.littletonrobotics.junction.Logger
import org.team4099.lib.geometry.Pose2d
import org.team4099.lib.geometry.Pose3d
import org.team4099.lib.geometry.Rotation3d
import org.team4099.lib.geometry.Translation2d
import org.team4099.lib.geometry.Translation3d
import org.team4099.lib.units.base.meters
import org.team4099.lib.units.base.seconds
import org.team4099.lib.units.derived.radians

class CameraIOSim(val id: String) : CameraIO {
private val poseSubscriber: DoubleArraySubscriber =
NetworkTableInstance.getDefault()
.getTable("AdvantageKit")
.getSubTable("RealOutputs")
.getDoubleArrayTopic(VisionConstants.POSE_TOPIC_NAME)
.subscribe(DoubleArray(3))
private val errorScaleConstant = 0.05

override fun updateInputs(inputs: CameraIO.CameraInputs) {
val drivePose = poseSubscriber.get(DoubleArray(3)).toPose2d().toPose3d()

inputs.timestamp = Clock.fpgaTime - (Math.random() * 0.2).seconds
val robotTtag = drivePose.relativeTo(FieldConstants.aprilTags[0].pose)
inputs.frame = robotTtag.gaussianShenanigans()
val estimatedRobotPose =
FieldConstants.aprilTags[0].pose.transformBy(inputs.frame.toTransform3d())

Logger.recordOutput(
"Vision/$id/simEstimatedRobotPose",
estimatedRobotPose.toPose2d().toDoubleArray().toDoubleArray()
)
Logger.recordOutput(
"Vision/$id/simTagPose", FieldConstants.aprilTags[0].pose.toDoubleArray().toDoubleArray()
)
inputs.fps = Math.random() * 10 + 30
inputs.usedTargets = listOf(0)
}

private fun DoubleArray.toPose2d(): Pose2d {
return Pose2d(Translation2d(this[0].meters, this[1].meters), this[2].radians)
}

private fun Pose3d.gaussianShenanigans(): Pose3d {
return Pose3d(
Translation3d(
this.translation.x * (1 - Math.random() * errorScaleConstant),
this.translation.y * (1 - Math.random() * errorScaleConstant),
this.translation.z * (1 - Math.random() * errorScaleConstant)
),
Rotation3d(
this.rotation.x * (1 - Math.random() * errorScaleConstant),
this.rotation.y * (1 - Math.random() * errorScaleConstant),
this.rotation.z * (1 - Math.random() * errorScaleConstant)
)
)
}
}

0 comments on commit 50dbd64

Please sign in to comment.