@@ -23,12 +23,14 @@ public Limelight(Drivetrain drivetrain) {
2323
2424 shooterMap = new InterpolatingDoubleTreeMap (); // add values after testing
2525 // key is distance (meters), value is angle (rads)
26- // ASSUMING SHOOTING AT 4000 RPM
27- shooterMap .put (2.0 , .005 );
26+ shooterMap .put (2.06 , .01 );
2827 shooterMap .put (3.05 , 0.26 );
29- shooterMap .put (1.39 , -.18 );
3028 shooterMap .put (2.5 , 0.23 );
29+ shooterMap .put (1.39 , -0.18 );
30+ shooterMap .put (3.45 , 0.3 );
31+ shooterMap .put (3.1 , 0.3 );
3132
33+ // ASSUMING SHOOTING AT 4000 RPM
3234 // changing speed multipliers for auto intaking note
3335 SmartDashboard .putNumber ("forward speed multiplier" , 1.5 );
3436 SmartDashboard .putNumber ("strafe speed multiplier" , 1.5 );
@@ -45,6 +47,7 @@ public Limelight(Drivetrain drivetrain) {
4547 positionTolerance [2 ]);
4648 SmartDashboard .putNumber ("apriltag align vel tolerance" ,
4749 velocityTolerance [2 ]);
50+
4851 }
4952
5053 @ Override
@@ -65,23 +68,31 @@ public void periodic() {
6568 }
6669
6770 public double getTXDeg (String limelightName ) {
68- return (limelightName == INTAKE_LL_NAME ) ? LimelightHelpers .getTX (INTAKE_LL_NAME ) : -LimelightHelpers .getTY (SHOOTER_LL_NAME );
71+ return (limelightName == INTAKE_LL_NAME )
72+ ? LimelightHelpers .getTX (INTAKE_LL_NAME )
73+ : -LimelightHelpers .getTY (SHOOTER_LL_NAME );
6974 }
7075
7176 public double getTYDeg (String limelightName ) {
72- return (limelightName == INTAKE_LL_NAME ) ? LimelightHelpers .getTY (INTAKE_LL_NAME ) : LimelightHelpers .getTX (SHOOTER_LL_NAME );
77+ return (limelightName == INTAKE_LL_NAME )
78+ ? LimelightHelpers .getTY (INTAKE_LL_NAME )
79+ : LimelightHelpers .getTX (SHOOTER_LL_NAME );
7380 }
7481
7582 public double getDistanceToSpeakerMeters () {
76- if (LimelightHelpers .getFiducialID (SHOOTER_LL_NAME ) == RED_SPEAKER_CENTER_TAG_ID
77- || LimelightHelpers .getFiducialID (SHOOTER_LL_NAME ) == BLUE_SPEAKER_CENTER_TAG_ID ) {
83+ if (LimelightHelpers
84+ .getFiducialID (SHOOTER_LL_NAME ) == RED_SPEAKER_CENTER_TAG_ID
85+ || LimelightHelpers
86+ .getFiducialID (SHOOTER_LL_NAME ) == BLUE_SPEAKER_CENTER_TAG_ID ) {
7887 Rotation2d angleToGoal = Rotation2d .fromDegrees (MOUNT_ANGLE_DEG_SHOOTER )
79- .plus (Rotation2d .fromDegrees (getTYDeg (SHOOTER_LL_NAME ))); //because limelight is mounted horizontally
80- double distance = (SPEAKER_CENTER_HEIGHT_METERS - HEIGHT_FROM_GROUND_METERS_SHOOTER ) / angleToGoal .getTan ();
88+ .plus (Rotation2d .fromDegrees (getTYDeg (SHOOTER_LL_NAME ))); // because limelight is mounted
89+ // horizontally
90+ double distance =
91+ (SPEAKER_CENTER_HEIGHT_METERS - HEIGHT_FROM_GROUND_METERS_SHOOTER )
92+ / angleToGoal .getTan ();
8193 // SmartDashboard.putNumber("limelight distance", distance);
8294 return distance ;
83- }
84- else {
95+ } else {
8596 // SmartDashboard.putNumber("limelight distance", -1);
8697 return -1 ;
8798 }
@@ -102,16 +113,21 @@ public double getDistanceToNoteMeters() {
102113 }
103114
104115 public double getArmAngleToShootSpeakerRad () {
105- double armRestingHeightToSubwooferMeters = HEIGHT_FROM_RESTING_ARM_TO_SPEAKER_METERS ;
106- double horizontalDistanceMeters = getDistanceToSpeakerMeters () + SIDEWAYS_OFFSET_TO_OUTTAKE_MOUTH ;
107- return END_EFFECTOR_BASE_ANGLE_RADS - Math .atan (armRestingHeightToSubwooferMeters / horizontalDistanceMeters );
116+ double armRestingHeightToSubwooferMeters =
117+ HEIGHT_FROM_RESTING_ARM_TO_SPEAKER_METERS ;
118+ double horizontalDistanceMeters =
119+ getDistanceToSpeakerMeters () + SIDEWAYS_OFFSET_TO_OUTTAKE_MOUTH ;
120+ return END_EFFECTOR_BASE_ANGLE_RADS - Math
121+ .atan (armRestingHeightToSubwooferMeters / horizontalDistanceMeters );
108122 }
109123
110124
111125 public double getRotateAngleRadMT2 () {
112- Pose3d targetPoseRobotSpace = LimelightHelpers .getTargetPose3d_RobotSpace (SHOOTER_LL_NAME ); // pose of the target
126+ Pose3d targetPoseRobotSpace =
127+ LimelightHelpers .getTargetPose3d_RobotSpace (SHOOTER_LL_NAME ); // pose of the target
113128
114- double targetX = targetPoseRobotSpace .getX (); // the forward offset between the center of the robot and target
129+ double targetX = targetPoseRobotSpace .getX (); // the forward offset between the center of the
130+ // robot and target
115131 double targetZ = -targetPoseRobotSpace .getZ (); // the sideways offset
116132
117133 double targetOffsetRads =
@@ -121,7 +137,8 @@ public double getRotateAngleRadMT2() {
121137 }
122138
123139 public double getDistanceToSpeakerMetersMT2 () {
124- Pose3d targetPoseRobotSpace = LimelightHelpers .getTargetPose3d_RobotSpace (SHOOTER_LL_NAME );
140+ Pose3d targetPoseRobotSpace =
141+ LimelightHelpers .getTargetPose3d_RobotSpace (SHOOTER_LL_NAME );
125142
126143 double x = targetPoseRobotSpace .getX ();
127144 double z = targetPoseRobotSpace .getZ ();
@@ -137,4 +154,4 @@ public double getOptimizedArmAngleRadsMT2() {
137154 public boolean seesTag () {
138155 return LimelightHelpers .getTV (SHOOTER_LL_NAME );
139156 }
140- }
157+ }
0 commit comments