/*----------------------------------------------------------------------------*/ /* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ /* Open Source Software - may be modified and shared by FRC teams. The code */ /* must be accompanied by the FIRST BSD license file in the root directory of */ /* the project. */ /*----------------------------------------------------------------------------*/ package frc.robot; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.Talon; import edu.wpi.first.wpilibj.Timer; /** * The VM is configured to automatically run this class, and to call the * functions corresponding to each mode, as described in the TimedRobot * documentation. If you change the name of this class or the package after * creating this project, you must also update the build.gradle file in the * project. */ public class Robot extends TimedRobot { private Talon leftMotor, rightMotor; private Encoder leftEncoder, rightEncoder; private double leftPower, rightPower; private Timer autoTimer; private boolean autoDone; /** * This function is run when the robot is first started up and should be * used for any initialization code. */ @Override public void robotInit() { // Quadrature encoder has A and B channels connected to DIO0,1, DIO2,3 leftEncoder = new Encoder(0, 1); rightEncoder = new Encoder(2, 3, true); // right side turns in opposite direction // Peanut wheels are 7.5" in diameter // Encoders provide 1 count per degree of rotation leftEncoder.setDistancePerPulse((3.141592*7.5)/360); rightEncoder.setDistancePerPulse((3.141592*7.5)/360); // PWM motor controllers connected to PWM0, PWM1 leftMotor = new Talon(0); rightMotor = new Talon(1); // right motor turns in opposite direction rightMotor.setInverted(true); // timer to manage autonomous direction updates autoTimer = new Timer(); } /** * This function is called every robot packet, no matter the mode. Use * this for items like diagnostics that you want ran during disabled, * autonomous, teleoperated and test. * * <p>This runs after the mode specific periodic functions, but before * LiveWindow and SmartDashboard integrated updating. */ @Override public void robotPeriodic() { SmartDashboard.putNumber("Left Distance", leftEncoder.getDistance()); SmartDashboard.putNumber("Right Distance", rightEncoder.getDistance()); SmartDashboard.putNumber("Left Power", leftPower); SmartDashboard.putNumber("Right Power", rightPower); } /** * Initialize the motor powers and start the timer we created so we can * periodically adjust the motor power to keep the robot going straight */ @Override public void autonomousInit() { // Reset encoder counts to 0 leftEncoder.reset(); rightEncoder.reset(); // start motors turning forward at 20% power leftPower = 0.20; leftMotor.set(leftPower); rightPower = 0.20; rightMotor.set(rightPower); autoTimer.start(); autoDone = false; } /** * This function is called regularly during autonomous. * Periodically adjust the motor powers and stop if we've gone the desired distance. */ @Override public void autonomousPeriodic() { if (!autoDone) { // adjust motor power every 1/4 second to keep us going straight if (autoTimer.hasPeriodPassed(0.125)) { // if we're going straight, leftDistance == rightDistance // otherwise, compute the error and adjust the motor powers to minimize it double error = leftEncoder.getDistance() - rightEncoder.getDistance(); double kP = 0.005; // proportion of error used to correct motor power // adjust motor power to try to keep left/right distances same leftPower -= kP*error; // positive error means left is going too fast rightPower += kP*error; // right motor spins opposite direction of left leftMotor.set(leftPower); rightMotor.set(rightPower); } if ((leftEncoder.getDistance() > 36.0) || (rightEncoder.getDistance() > 36.0)) { leftMotor.stopMotor(); rightMotor.stopMotor(); autoDone = true; } } } /** * This function is called periodically during operator control. */ @Override public void teleopPeriodic() { } /** * This function is called periodically during test mode. */ @Override public void testPeriodic() { } }
Last modified 6 years ago
Last modified on Nov 12, 2019, 7:51:45 PM