Fixed floor position issue
This commit is contained in:
@ -4,8 +4,8 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class RobotConstants {
|
public class RobotConstants {
|
||||||
public final static double clawOpen = 0.5;
|
public final static double clawClose = 0.8;
|
||||||
public final static double clawClose = 0.05;
|
public final static double clawOpen = 0.05;
|
||||||
|
|
||||||
public final static double armFloor = 0.7;
|
public final static double armFloor = 0.7;
|
||||||
public final static double armSubmarine = 0.55;
|
public final static double armSubmarine = 0.55;
|
||||||
@ -20,8 +20,7 @@ public class RobotConstants {
|
|||||||
public final static double wristSpeciemen = 0.1;
|
public final static double wristSpeciemen = 0.1;
|
||||||
|
|
||||||
|
|
||||||
public final static int liftToFloorPos = 350;
|
public final static int liftToFloorPos = 550;
|
||||||
public final static int liftToSubmarinePos = 350;
|
|
||||||
public final static int liftToLowBucketPos = 2650;
|
public final static int liftToLowBucketPos = 2650;
|
||||||
public final static int liftToHighRung = 2100;
|
public final static int liftToHighRung = 2100;
|
||||||
public final static int dropToHighRung = 1675;
|
public final static int dropToHighRung = 1675;
|
||||||
|
@ -6,12 +6,8 @@ import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftPower;
|
|||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToFloorPos;
|
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToFloorPos;
|
||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighBucketPos;
|
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighBucketPos;
|
||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToLowBucketPos;
|
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToLowBucketPos;
|
||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToSubmarinePos;
|
|
||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighRung;
|
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighRung;
|
||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighRungAttach;
|
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighRungAttach;
|
||||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.dropToHighRung;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
@ -60,7 +56,7 @@ public class LiftActionsSubsystem {
|
|||||||
}
|
}
|
||||||
|
|
||||||
public Action toFloorPosition() {
|
public Action toFloorPosition() {
|
||||||
return new MoveToPosition(liftToSubmarinePos, LiftState.FLOOR);
|
return new MoveToPosition(liftToFloorPos, LiftState.FLOOR);
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action toHighRung() {
|
public Action toHighRung() {
|
||||||
@ -72,15 +68,15 @@ public class LiftActionsSubsystem {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
public Action toZeroPosition() {
|
public Action toZeroPosition() {
|
||||||
return new MoveToPosition(0, LiftState.FLOOR);
|
return new MoveToPosition(0, LiftState.FLOOR);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
public Action toHighRungAttach() {
|
public Action toHighRungAttach() {
|
||||||
return new MoveToPosition(liftToHighRungAttach, LiftState.HIGH_RUNG);
|
return new MoveToPosition(liftToHighRungAttach, LiftState.HIGH_RUNG);
|
||||||
}
|
}
|
||||||
|
|
||||||
public Action toLowBucketPosition() {
|
public Action toLowBucketPosition() {
|
||||||
return new MoveToPosition(liftToLowBucketPos, LiftState.LOW_BUCKET);
|
return new MoveToPosition(liftToLowBucketPos, LiftState.LOW_BUCKET);
|
||||||
|
|
||||||
|
Reference in New Issue
Block a user