Start adding lookup table for shooter

main
FRCTeam3009 2024-03-26 17:50:01 -07:00
parent b9076851f7
commit 7eb68c50b1
4 changed files with 488 additions and 433 deletions

View File

@ -1,3 +1,5 @@
import wpimath.units
# Front Left Swerve
FLDrive = 43
FLAngle = 20
@ -40,12 +42,12 @@ Climber = 35
LEDs = 2
Servo = 0
ServoClosed = 0.35
ServoClosed = 0.23
ServoOpen = 0.0
buddyServo = 3
buddyServoClosed = 0.5
buddyServoOpen = 0.9
buddyServoClosed = 1.0
buddyServoOpen = 0.0
pitchServo = 1
# servo angles
@ -77,4 +79,10 @@ speakerAngle = shooterAngleMin
autoDefaultDistance = 2.4 # meters
maxDistanceSpeakerShot = 5.2 # meters
minDistanceSpeakerShot = 2.18 # meters
minDistanceSpeakerShot = 2.18 # meters
shooterPitch = 68
shooterSpeed = 0.65
subwooferDistance = wpimath.units.inchesToMeters(34.17) # Literal distance the subwoofer sticks out
subwooferDistanceOffset = wpimath.units.inchesToMeters(34.17 + 11.0) # Closest we can actually reach

View File

@ -52,8 +52,8 @@ class MyRobot(wpilib.TimedRobot):
self.kAmpAndStage = self.kAmptags + self.kStagetags
self.kDefaultScoopScale = 0.5
self.kDefaultMiddleRampScale = 1.0
self.kSubwooferDistance = wpimath.units.inchesToMeters(36.17)
self.kSubwooferStopDistance = wpimath.units.inchesToMeters(self.kSubwooferDistance + 11.0)
self.kSubwooferDistance = constants.subwooferDistance
self.kSubwooferStopDistance = constants.subwooferDistanceOffset
self.lastOdometryPose = wpimath.geometry.Pose2d()
@ -67,6 +67,10 @@ class MyRobot(wpilib.TimedRobot):
self.smartdashboard.putNumber("servo open", constants.ServoOpen)
self.smartdashboard.putNumber("servo closed", constants.ServoClosed)
self.smartdashboard.putNumber("pitchShooter", constants.shooterPitch)
self.smartdashboard.putNumber("speedShooter", constants.shooterSpeed)
self.smartdashboard.putNumber("distance", 10000)
pathPlanner.autonomousDropdown(self.smartdashboard)
self.NoteCam = self.nt.getTable("limelight-front")
@ -222,11 +226,15 @@ class MyRobot(wpilib.TimedRobot):
self.smartdashboard.putBoolean("hasNote", self.shooter.hasNote())
self.smartdashboard.putNumber("autoMode", 0)
self.driveTrain.publishDashboardStates(self.smartdashboard)
constants.ServoOpen = self.smartdashboard.getNumber("servo open", constants.ServoOpen)
constants.ServoClosed = self.smartdashboard.getNumber("servo closed", constants.ServoClosed)
constants.shooterPitch = self.smartdashboard.getNumber("pitchShooter", constants.shooterPitch)
constants.shooterSpeed = self.smartdashboard.getNumber("speedShooter", constants.shooterSpeed)
self.smartdashboard.putNumberArray("startpose", self.startPose)
ATagCamTargetSeen = self.ATagCam.getNumber("tv",0)
@ -321,9 +329,25 @@ class MyRobot(wpilib.TimedRobot):
elif self.controls.speakerPitch():
self.set_shooter_angle(constants.speakerAngle)
speakerspeed = shooter.Shooter.speakerspeed_far
# TODO determine if we need to change speed for shallow angle
# TODO set this to the correct pitch which is the first in the dictionary
else:
self.aTagPitch()
tags = self.get_target_list()
tag = self.filter_target_list(tags, self.kSpeakerTags)
distance = 0
if tag is not None:
distance = tag["t6t_rs"][2]
self.smartdashboard.putNumber("distance", distance)
# TODO
angle = constants.shooterPitch
self.set_shooter_angle(angle)
# TODO
speakerspeed = constants.shooterSpeed
sa = shooter.lookUpAngleSpeed(distance)
sa.speed
sa.angle
# TODO auto adjust speakerspeed based on distance away from april tag
@ -344,7 +368,7 @@ class MyRobot(wpilib.TimedRobot):
if self.controls.buddyBar():
average = (constants.buddyServoClosed + constants.buddyServoOpen) / 2
if self.buddyServo.get() < average:
if self.buddyServo.get() > average:
self.buddyServo.set(constants.buddyServoOpen)
else:
self.buddyServo.set(constants.buddyServoClosed)
@ -387,21 +411,7 @@ class MyRobot(wpilib.TimedRobot):
if self.timer.hasElapsed(0.5):
self.timer.reset()
def aTagPitch(self):
tags = self.get_target_list()
tag = self.filter_target_list(tags, self.kSpeakerTags)
if tag is None:
return
distance = tag["t6t_rs"][2]
height = wpimath.units.inchesToMeters(constants.speakerHeight)
radians = math.atan2(height, distance)
angle = wpimath.units.radiansToDegrees(radians)
self.set_shooter_angle(angle)
def MoveToPose2d(self, pose: wpimath.geometry.Pose2d):
trajectory = pose.relativeTo(self.lastOdometryPose)

View File

@ -1,6 +1,8 @@
import rev
from wpimath.controller import SimpleMotorFeedforwardMeters
import SparkMotor
import constants
import wpimath.units
import wpilib
class Shooter:
speakerspeed_close = 0.65 #0.8 #0.62
@ -13,9 +15,11 @@ class Shooter:
self.topMotor = rev.CANSparkMax(topId, rev._rev.CANSparkLowLevel.MotorType.kBrushless)
self.bottomMotor = rev.CANSparkMax(bottomId, rev._rev.CANSparkLowLevel.MotorType.kBrushless)
self.middleRamp = rev.CANSparkMax(middleId, rev._rev.CANSparkLowLevel.MotorType.kBrushless)
self.middleRamp = rev.CANSparkMax(middleId, rev._rev.CANSparkLowLevel.MotorType.kBrushless)
self.topspark = SparkMotor.SparkMotor(self.topMotor)
self.bottomMotorspark = SparkMotor.SparkMotor(self.bottomMotor)
#self.topspark._Motor_Pid_.setP(0.003)
#self.bottomMotorspark._Motor_Pid_.setP(0.003)
self.middleRampSpark = SparkMotor.SparkMotor(self.middleRamp)
self.noteSensorBottom = noteSensorBottom
self.noteSensorTop = noteSensorTop
@ -29,12 +33,15 @@ class Shooter:
return (self.noteSensorBottom.get() or self.noteSensorTop.get())
def fire(self, value, override, reverseOverride):
self.rpmTimer = wpilib.Timer()
seen = self.hasNote()
if reverseOverride:
self.intakeScoopSpark._Motor_Pid_.setReference(-self.kMaxRpm, rev.CANSparkMax.ControlType.kVelocity)
self.middleRampSpark._Motor_Pid_.setReference(-self.kMaxRpm/2, rev.CANSparkMax.ControlType.kVelocity)
self.bottomMotorspark._Motor_Pid_.setReference(-self.kMaxRpm/6, rev.CANSparkMax.ControlType.kVelocity)
self.topspark._Motor_Pid_.setReference(self.kMaxRpm/6, rev.CANSparkMax.ControlType.kVelocity)
self.bottomMotorspark._Motor_Pid_.setReference(-self.kMaxRpm/6, rev.CANSparkMax.ControlType.kVelocity, arbFeedforward=0.02)
self.topspark._Motor_Pid_.setReference(self.kMaxRpm/6, rev.CANSparkMax.ControlType.kVelocity, arbFeedforward=0.02)
return
if override:
@ -67,7 +74,9 @@ class Shooter:
toprpm = self.topspark.encoder.getVelocity()
bottomrpm = self.bottomMotorspark.encoder.getVelocity()
if bottomrpm >= rpm and toprpm <= -1 * rpm:
rpmBufferUp = rpm + 250
rpmBufferDown = rpm - 250
if bottomrpm >= rpmBufferDown and bottomrpm < rpmBufferUp and toprpm <= -1 * rpmBufferDown and toprpm > -1 * rpmBufferUp:
self.middleRampSpark._Motor_Pid_.setReference(self.kMaxRpm, rev.CANSparkMax.ControlType.kVelocity)
else:
self.middleRampSpark._Motor_Pid_.setReference(0, rev.CANSparkMax.ControlType.kVelocity)
@ -87,4 +96,32 @@ class Shooter:
self.intakeScoopSpark._Motor_Pid_.setReference(self.kMaxRpm, rev.CANSparkMax.ControlType.kVelocity)
self.middleRampSpark._Motor_Pid_.setReference(self.kMaxRpm * self.scoopScale, rev.CANSparkMax.ControlType.kVelocity)
self.bottomMotorspark._Motor_Pid_.setReference(0, rev.CANSparkMax.ControlType.kVelocity)
self.topspark._Motor_Pid_.setReference(0, rev.CANSparkMax.ControlType.kVelocity)
self.topspark._Motor_Pid_.setReference(0, rev.CANSparkMax.ControlType.kVelocity)
class speedAngle:
def __init__(self, speed, angle):
self.speed = speed
self.angle = angle
angleSpeed = {
constants.subwooferDistanceOffset: speedAngle(0.65, 64), # Shortest distance
2.17: speedAngle(60, .78),
2.6: speedAngle(55, .78),
2.85: speedAngle(54, .72),
3.24: speedAngle(47, .74),
3.52: speedAngle(46, .74),
wpimath.units.inchesToMeters(180): speedAngle(0.8, 46),
}
def lookUpAngleSpeed(distance):
distancesList = angleSpeed.keys()
closestKey = constants.subwooferDistanceOffset
closestAbs = 100000000000
for variable in distancesList:
absDistance = abs(variable - distance)
if absDistance < closestAbs:
closestKey = variable
closestAbs = absDistance
return angleSpeed[closestKey]

View File

@ -12,279 +12,6 @@
"titleType": 0,
"tiles": {
"0,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/servo open",
"_title": "servo open",
"_glyph": 148,
"_showGlyph": false
}
},
"1,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/servo closed",
"_title": "servo closed",
"_glyph": 148,
"_showGlyph": false
}
},
"2,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/odometryX",
"_title": "odometryX",
"_glyph": 148,
"_showGlyph": false
}
},
"3,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-front_Interface",
"_title": "limelight-front_Interface",
"_glyph": 148,
"_showGlyph": false
}
},
"4,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-front_PipelineName",
"_title": "limelight-front_PipelineName",
"_glyph": 148,
"_showGlyph": false
}
},
"5,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-front_Stream",
"_title": "limelight-front_Stream",
"_glyph": 148,
"_showGlyph": false
}
},
"6,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-back_PipelineName",
"_title": "limelight-back_PipelineName",
"_glyph": 148,
"_showGlyph": false
}
},
"7,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-back_Stream",
"_title": "limelight-back_Stream",
"_glyph": 148,
"_showGlyph": false
}
},
"8,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-back_Interface",
"_title": "limelight-back_Interface",
"_glyph": 148,
"_showGlyph": false
}
},
"9,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/odometryY",
"_title": "odometryY",
"_glyph": 148,
"_showGlyph": false
}
},
"0,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/rotation",
"_title": "rotation",
"_glyph": 148,
"_showGlyph": false
}
},
"1,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/FL_Velocity",
"_title": "FL_Velocity",
"_glyph": 148,
"_showGlyph": false
}
},
"2,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/FR_Velocity",
"_title": "FR_Velocity",
"_glyph": 148,
"_showGlyph": false
}
},
"3,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/RL_Velocity",
"_title": "RL_Velocity",
"_glyph": 148,
"_showGlyph": false
}
},
"4,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/RR_Velocity",
"_title": "RR_Velocity",
"_glyph": 148,
"_showGlyph": false
}
},
"5,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/chassis_speeds_vx",
"_title": "chassis_speeds_vx",
"_glyph": 148,
"_showGlyph": false
}
},
"6,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/chassis_speeds_vy",
"_title": "chassis_speeds_vy",
"_glyph": 148,
"_showGlyph": false
}
},
"7,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/chassis_speeds_omega",
"_title": "chassis_speeds_omega",
"_glyph": 148,
"_showGlyph": false
}
},
"8,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/note sensor top",
"_title": "note sensor top",
"_glyph": 148,
"_showGlyph": false
}
},
"9,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/note sensor bottom",
"_title": "note sensor bottom",
"_glyph": 148,
"_showGlyph": false
}
},
"0,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/note sensor front",
"_title": "note sensor front",
"_glyph": 148,
"_showGlyph": false
}
},
"1,2": {
"size": [
1,
1
@ -297,7 +24,7 @@
"_showGlyph": false
}
},
"2,2": {
"1,0": {
"size": [
1,
1
@ -310,7 +37,7 @@
"_showGlyph": false
}
},
"3,2": {
"2,0": {
"size": [
1,
1
@ -323,6 +50,279 @@
"_showGlyph": false
}
},
"3,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/servo open",
"_title": "servo open",
"_glyph": 148,
"_showGlyph": false
}
},
"4,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/servo closed",
"_title": "servo closed",
"_glyph": 148,
"_showGlyph": false
}
},
"5,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/pitchShooter",
"_title": "pitchShooter",
"_glyph": 148,
"_showGlyph": false
}
},
"6,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/speedShooter",
"_title": "speedShooter",
"_glyph": 148,
"_showGlyph": false
}
},
"7,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/distance",
"_title": "distance",
"_glyph": 148,
"_showGlyph": false
}
},
"8,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/autonomousmode/value",
"_title": "autonomousmode/value",
"_glyph": 148,
"_showGlyph": false
}
},
"9,0": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-back_PipelineName",
"_title": "limelight-back_PipelineName",
"_glyph": 148,
"_showGlyph": false
}
},
"0,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-back_Stream",
"_title": "limelight-back_Stream",
"_glyph": 148,
"_showGlyph": false
}
},
"1,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-back_Interface",
"_title": "limelight-back_Interface",
"_glyph": 148,
"_showGlyph": false
}
},
"2,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight_PipelineName",
"_title": "limelight_PipelineName",
"_glyph": 148,
"_showGlyph": false
}
},
"3,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight_Interface",
"_title": "limelight_Interface",
"_glyph": 148,
"_showGlyph": false
}
},
"4,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight_Stream",
"_title": "limelight_Stream",
"_glyph": 148,
"_showGlyph": false
}
},
"5,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-front_Interface",
"_title": "limelight-front_Interface",
"_glyph": 148,
"_showGlyph": false
}
},
"6,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-front_PipelineName",
"_title": "limelight-front_PipelineName",
"_glyph": 148,
"_showGlyph": false
}
},
"7,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/limelight-front_Stream",
"_title": "limelight-front_Stream",
"_glyph": 148,
"_showGlyph": false
}
},
"8,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/pot",
"_title": "pot",
"_glyph": 148,
"_showGlyph": false
}
},
"9,1": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/odometryX",
"_title": "odometryX",
"_glyph": 148,
"_showGlyph": false
}
},
"0,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/odometryY",
"_title": "odometryY",
"_glyph": 148,
"_showGlyph": false
}
},
"1,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/odometryR",
"_title": "odometryR",
"_glyph": 148,
"_showGlyph": false
}
},
"2,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/FL_Velocity",
"_title": "FL_Velocity",
"_glyph": 148,
"_showGlyph": false
}
},
"3,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/FR_Velocity",
"_title": "FR_Velocity",
"_glyph": 148,
"_showGlyph": false
}
},
"4,2": {
"size": [
1,
@ -330,8 +330,8 @@
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/trajectoryX",
"_title": "trajectoryX",
"_source0": "network_table:///SmartDashboard/RL_Velocity",
"_title": "RL_Velocity",
"_glyph": 148,
"_showGlyph": false
}
@ -343,8 +343,8 @@
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/trajectoryY",
"_title": "trajectoryY",
"_source0": "network_table:///SmartDashboard/RR_Velocity",
"_title": "RR_Velocity",
"_glyph": 148,
"_showGlyph": false
}
@ -356,13 +356,117 @@
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/trajectoryR",
"_title": "trajectoryR",
"_source0": "network_table:///SmartDashboard/chassis_speeds_vx",
"_title": "chassis_speeds_vx",
"_glyph": 148,
"_showGlyph": false
}
},
"7,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/chassis_speeds_vy",
"_title": "chassis_speeds_vy",
"_glyph": 148,
"_showGlyph": false
}
},
"8,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/chassis_speeds_omega",
"_title": "chassis_speeds_omega",
"_glyph": 148,
"_showGlyph": false
}
},
"9,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/note sensor top",
"_title": "note sensor top",
"_glyph": 148,
"_showGlyph": false
}
},
"0,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/note sensor bottom",
"_title": "note sensor bottom",
"_glyph": 148,
"_showGlyph": false
}
},
"1,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/note sensor front",
"_title": "note sensor front",
"_glyph": 148,
"_showGlyph": false
}
},
"2,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/speakerspeed",
"_title": "speakerspeed",
"_glyph": 148,
"_showGlyph": false
}
},
"3,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/ampspeed",
"_title": "ampspeed",
"_glyph": 148,
"_showGlyph": false
}
},
"4,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/trapspeed",
"_title": "trapspeed",
"_glyph": 148,
"_showGlyph": false
}
},
"5,3": {
"size": [
1,
1
@ -377,46 +481,7 @@
"Colors/Color when false": "#8B0000FF"
}
},
"8,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/DriveX",
"_title": "DriveX",
"_glyph": 148,
"_showGlyph": false
}
},
"9,2": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/DriveY",
"_title": "DriveY",
"_glyph": 148,
"_showGlyph": false
}
},
"0,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/DriveR",
"_title": "DriveR",
"_glyph": 148,
"_showGlyph": false
}
},
"1,3": {
"6,3": {
"size": [
1,
1
@ -429,85 +494,7 @@
"_showGlyph": false
}
},
"2,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/autonomousmode/value",
"_title": "autonomousmode/value",
"_glyph": 148,
"_showGlyph": false
}
},
"3,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/pot",
"_title": "pot",
"_glyph": 148,
"_showGlyph": false
}
},
"4,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/odometryR",
"_title": "odometryR",
"_glyph": 148,
"_showGlyph": false
}
},
"5,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/speakerspeed",
"_title": "speakerspeed",
"_glyph": 148,
"_showGlyph": false
}
},
"6,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/ampspeed",
"_title": "ampspeed",
"_glyph": 148,
"_showGlyph": false
}
},
"7,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/trapspeed",
"_title": "trapspeed",
"_glyph": 148,
"_showGlyph": false
}
},
"8,3": {
"size": [
1,
1
@ -520,7 +507,7 @@
"_showGlyph": false
}
},
"9,3": {
"8,3": {
"size": [
1,
1
@ -532,6 +519,19 @@
"_glyph": 148,
"_showGlyph": false
}
},
"9,3": {
"size": [
1,
1
],
"content": {
"_type": "Text View",
"_source0": "network_table:///SmartDashboard/field/robot/width",
"_title": "field/robot/width",
"_glyph": 148,
"_showGlyph": false
}
}
}
}
@ -665,9 +665,9 @@
}
],
"windowGeometry": {
"x": 0.0,
"y": 0.0,
"width": 1536.0,
"height": 816.0
"x": -7.199999809265137,
"y": -7.199999809265137,
"width": 1550.4000244140625,
"height": 830.4000244140625
}
}