예제 #1
0
  public static void init() {
    // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
    driveLeftSpeedController = new Talon(9);
    LiveWindow.addActuator("Drive", "Left Speed Controller", (Talon) driveLeftSpeedController);

    driveRightSpeedController = new Talon(8);
    LiveWindow.addActuator("Drive", "Right Speed Controller", (Talon) driveRightSpeedController);

    driveRobotDrive21 = new RobotDrive(driveLeftSpeedController, driveRightSpeedController);

    driveRobotDrive21.setSafetyEnabled(true);
    driveRobotDrive21.setExpiration(0.1);
    driveRobotDrive21.setSensitivity(0.5);
    driveRobotDrive21.setMaxOutput(1.0);

    driveLeftEncoder = new Encoder(2, 3, false, EncodingType.k4X);
    LiveWindow.addSensor("Drive", "LeftEncoder", driveLeftEncoder);
    driveLeftEncoder.setDistancePerPulse(1.0);
    driveLeftEncoder.setPIDSourceType(PIDSourceType.kRate);
    driveRightEncoder = new Encoder(0, 1, false, EncodingType.k4X);
    LiveWindow.addSensor("Drive", "RightEncoder", driveRightEncoder);
    driveRightEncoder.setDistancePerPulse(1.0);
    driveRightEncoder.setPIDSourceType(PIDSourceType.kRate);

    // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
  }
예제 #2
0
  public static void init() {
    // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
    driveTrainLeftFront = new Talon(0);
    LiveWindow.addActuator("DriveTrain", "Left Front", (Talon) driveTrainLeftFront);

    driveTrainLeftRear = new Talon(1);
    LiveWindow.addActuator("DriveTrain", "Left Rear", (Talon) driveTrainLeftRear);

    driveTrainRightFront = new Talon(2);
    LiveWindow.addActuator("DriveTrain", "Right Front", (Talon) driveTrainRightFront);

    driveTrainRightRear = new Talon(3);
    LiveWindow.addActuator("DriveTrain", "Right Rear", (Talon) driveTrainRightRear);

    driveTrainHolonomicDrive =
        new RobotDrive(
            driveTrainLeftFront, driveTrainLeftRear, driveTrainRightFront, driveTrainRightRear);

    driveTrainHolonomicDrive.setSafetyEnabled(false);
    driveTrainHolonomicDrive.setExpiration(0.1);
    driveTrainHolonomicDrive.setSensitivity(0.5);
    driveTrainHolonomicDrive.setMaxOutput(1.0);

    driveTrainHolonomicDrive.setInvertedMotor(RobotDrive.MotorType.kFrontRight, true);
    driveTrainHolonomicDrive.setInvertedMotor(RobotDrive.MotorType.kRearRight, true);
    driveTrainGyro = new AnalogGyro(0);
    LiveWindow.addSensor("DriveTrain", "Gyro", driveTrainGyro);
    driveTrainGyro.setSensitivity(0.007);
    forkliftMotor = new Talon(4);
    LiveWindow.addActuator("Forklift", "Motor", (Talon) forkliftMotor);

    forkliftEncoder = new Encoder(0, 1, false, EncodingType.k4X);
    LiveWindow.addSensor("Forklift", "Encoder", forkliftEncoder);
    forkliftEncoder.setDistancePerPulse(0.012);
    forkliftEncoder.setPIDSourceType(PIDSourceType.kDisplacement);
    toteCaptureLeftWheel = new Talon(8);
    LiveWindow.addActuator("Tote Capture", "Left Wheel", (Talon) toteCaptureLeftWheel);

    toteCaptureRightWheel = new Talon(9);
    LiveWindow.addActuator("Tote Capture", "Right Wheel", (Talon) toteCaptureRightWheel);

    containerCaptureMotor = new Talon(10);
    LiveWindow.addActuator("Container Capture", "Motor", (Talon) containerCaptureMotor);

    // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS

    powerDistributionPanel = new PowerDistributionPanel();
  }
예제 #3
0
  public void robotInit() {
    j1 = new Joystick(1);
    j2 = new Joystick(0);
    shooter = new Victor(2);
    shooter2 = new Victor(4);
    intake = new Victor(3);
    right = new Victor(0);
    left = new Victor(1);
    rd = new RobotDrive(left, right);
    light = new DigitalInput(3);
    count = 0;

    comp = new Compressor();
    inup = new DoubleSolenoid(0, 1);
    inup2 = new DoubleSolenoid(2, 3);

    gyro = new AnalogGyro(0);
    gyro.setSensitivity(.007);
    gyro.calibrate();
    gyro.reset();

    enc = new Encoder(1, 2, true, Encoder.EncodingType.k4X);
    enc.setDistancePerPulse(.11977); // circumference of wheel/200 (PPR)
    enc.setPIDSourceType(PIDSourceType.kDisplacement);
    enc.reset();

    out =
        new PIDOutput() {
          @Override
          public void pidWrite(double out) {
            rd.setLeftRightMotorOutputs(out, out);
          }
        };

    controller = new PIDController(.007, 0, 0, enc, out);
    controller.setAbsoluteTolerance(.25);
    controller.disable();

    gcontroller = new PIDController(kp, ki, kd, gyro, out);
    gcontroller.setAbsoluteTolerance(ktol);
    gcontroller.disable();

    timerStart = -1;
    timeToCancel = -1;
  }
예제 #4
0
  public static void init() {
    // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS
    climbingClimbingArmExtensionMotor = new VictorSP(7);
    LiveWindow.addActuator(
        "Climbing", "ClimbingArmExtensionMotor", (VictorSP) climbingClimbingArmExtensionMotor);

    climbingClimbingWinchMotor = new Talon(6);
    LiveWindow.addActuator("Climbing", "ClimbingWinchMotor", (Talon) climbingClimbingWinchMotor);

    climbingArmRotatationSolenoid = new DoubleSolenoid(0, 0, 1);
    LiveWindow.addActuator("Climbing", "ArmRotatationSolenoid", climbingArmRotatationSolenoid);

    climbingClimbingArmExtensionEncoder = new Encoder(4, 5, false, EncodingType.k4X);
    LiveWindow.addSensor(
        "Climbing", "ClimbingArmExtensionEncoder", climbingClimbingArmExtensionEncoder);
    climbingClimbingArmExtensionEncoder.setDistancePerPulse(1.0);
    climbingClimbingArmExtensionEncoder.reset();
    climbingClimbingArmExtensionEncoder.setPIDSourceType(PIDSourceType.kRate);
    ballIntakeSweeperBarRotationMotor = new Relay(0);
    ballIntakeSweeperBarRotationMotor.setSafetyEnabled(false);
    LiveWindow.addActuator(
        "BallIntake", "SweeperBarRotationMotor", ballIntakeSweeperBarRotationMotor);

    ballIntakeSweeperBarPositionSolenoid = new DoubleSolenoid(0, 2, 3);
    LiveWindow.addActuator(
        "BallIntake", "SweeperBarPositionSolenoid", ballIntakeSweeperBarPositionSolenoid);

    drivetrainRightDrivetrainEncoder = new Encoder(0, 1, false, EncodingType.k4X);
    LiveWindow.addSensor("Drivetrain", "RightDrivetrainEncoder", drivetrainRightDrivetrainEncoder);
    drivetrainRightDrivetrainEncoder.setDistancePerPulse(1.0);
    drivetrainRightDrivetrainEncoder.setPIDSourceType(PIDSourceType.kRate);
    drivetrainLeftDrivetrainEncoder = new Encoder(2, 3, false, EncodingType.k4X);
    LiveWindow.addSensor("Drivetrain", "LeftDrivetrainEncoder", drivetrainLeftDrivetrainEncoder);
    drivetrainLeftDrivetrainEncoder.setDistancePerPulse(1.0);
    drivetrainLeftDrivetrainEncoder.setPIDSourceType(PIDSourceType.kRate);
    drivetrainBackRightMotor = new VictorSP(0);
    LiveWindow.addActuator("Drivetrain", "BackRightMotor", (VictorSP) drivetrainBackRightMotor);

    drivetrainBackLeftMotor = new VictorSP(1);
    LiveWindow.addActuator("Drivetrain", "BackLeftMotor", (VictorSP) drivetrainBackLeftMotor);

    drivetrainFrontRightMotor = new VictorSP(2);
    LiveWindow.addActuator("Drivetrain", "FrontRightMotor", (VictorSP) drivetrainFrontRightMotor);

    drivetrainFrontLeftMotor = new VictorSP(3);
    LiveWindow.addActuator("Drivetrain", "FrontLeftMotor", (VictorSP) drivetrainFrontLeftMotor);

    drivetrainDrivetrainMotors =
        new RobotDrive(
            drivetrainFrontLeftMotor,
            drivetrainBackLeftMotor,
            drivetrainFrontRightMotor,
            drivetrainBackRightMotor);

    drivetrainDrivetrainMotors.setSafetyEnabled(true);
    drivetrainDrivetrainMotors.setExpiration(0.1);
    drivetrainDrivetrainMotors.setSensitivity(0.5);
    drivetrainDrivetrainMotors.setMaxOutput(1.0);
    drivetrainDrivetrainMotors.setInvertedMotor(RobotDrive.MotorType.kFrontLeft, true);
    drivetrainDrivetrainMotors.setInvertedMotor(RobotDrive.MotorType.kRearLeft, true);
    drivetrainDrivetrainMotors.setInvertedMotor(RobotDrive.MotorType.kFrontRight, true);
    drivetrainDrivetrainMotors.setInvertedMotor(RobotDrive.MotorType.kRearRight, true);
    powerDistributionPowerDistributionPanel = new PowerDistributionPanel(0);
    LiveWindow.addSensor(
        "PowerDistribution", "PowerDistributionPanel", powerDistributionPowerDistributionPanel);

    // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS

    drivetrainDrivetrainMotors.setSafetyEnabled(false);
  }