Claw, Gantry, and Lift
This commit is contained in:
parent
a4ee7223c3
commit
c73434ad26
|
@ -74,7 +74,6 @@ public abstract class AutoBase extends LinearOpMode {
|
|||
propRight();
|
||||
break;
|
||||
}
|
||||
|
||||
moveToBackstage();
|
||||
prepareToScore();
|
||||
scorePreloadedPixel();
|
||||
|
@ -129,7 +128,7 @@ public abstract class AutoBase extends LinearOpMode {
|
|||
delta = APRIL_TAG_RIGHT_DELTA;
|
||||
break;
|
||||
}
|
||||
double distance = this.robot.getCamera().getDistanceToAprilTag(2, 25, 5);
|
||||
double distance = this.robot.getCamera().getDistanceToAprilTag(this.alliance == CenterStageCommon.Alliance.Blue ? 2:5, 25, 5);
|
||||
Vector2d target = new Vector2d(this.robot.getDrive().getPoseEstimate().getX() + (distance - SCORING_DISTANCE_FROM_APRIL_TAG), this.robot.getDrive().getPoseEstimate().getY() + delta);
|
||||
TrajectorySequenceBuilder builder = this.robot.getTrajectorySequenceBuilder();
|
||||
builder.lineToConstantHeading(target);
|
||||
|
|
|
@ -18,8 +18,8 @@ import org.opencv.core.Point;
|
|||
|
||||
@Config
|
||||
public class Camera {
|
||||
public static float PROP_REJECTION_VERTICAL_UPPER = 175;
|
||||
public static float PROP_REJECTION_VERTICAL_LOWER = 300;
|
||||
public static float PROP_REJECTION_VERTICAL_UPPER = 250;
|
||||
public static float PROP_REJECTION_VERTICAL_LOWER = 370;
|
||||
private PropDetectionPipeline prop;
|
||||
private AprilTagProcessor aprilTag;
|
||||
private VisionPortal visionPortal;
|
||||
|
|
|
@ -66,8 +66,8 @@ public class RobotConfig {
|
|||
|
||||
// Vision
|
||||
public static double CAMERA_OFFSET_X = 0f;
|
||||
public static double DETECTION_AREA_MIN = 0.02f;
|
||||
public static double DETECTION_AREA_MAX = 0.3f;
|
||||
public static double DETECTION_AREA_MIN = 0.01f;
|
||||
public static double DETECTION_AREA_MAX = 0.2f;
|
||||
public static double DETECTION_LEFT_X = 0;
|
||||
public static double DETECTION_CENTER_X = .5;
|
||||
public static double DETECTION_RIGHT_X = 1;
|
||||
|
|
Loading…
Reference in New Issue