Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add flywheel bang-bang controller example #4071

Merged
merged 12 commits into from
Aug 5, 2023
Original file line number Diff line number Diff line change
Expand Up @@ -209,9 +209,12 @@
"mainclass": "Main",
"commandversion": 2
},
{"name": "Mechanism2d",
{
"name": "Mechanism2d",
"description": "An example usage of Mechanism2d to display mechanism states on a dashboard.",
"tags": ["Mechanism2d"],
"tags": [
"Mechanism2d"
],
"foldername": "mechanism2d",
"gradlebase": "java",
"mainclass": "Main",
Expand Down Expand Up @@ -793,5 +796,19 @@
"gradlebase": "java",
"commandversion": 2,
"mainclass": "Main"
},
{
"name": "Flywheel BangBangController",
"description": "A sample program to demonstrate the use of a BangBangController with a flywheel to control RPM",
"tags": [
"Flywheel",
"Simulation",
"Sensors",
"Joystick"
],
"foldername": "flywheelbangbangcontroller",
"gradlebase": "java",
"commandversion": 2,
"mainclass": "Main"
}
]
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package edu.wpi.first.wpilibj.examples.flywheelbangbangcontroller;

import edu.wpi.first.wpilibj.RobotBase;

/**
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
* you are doing, do not modify this file except to change the parameter class to the startRobot
* call.
*/
public final class Main {
private Main() {}

/**
* Main initialization function. Do not perform any initialization here.
*
* <p>If you change your main robot class, change the parameter type.
*/
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package edu.wpi.first.wpilibj.examples.flywheelbangbangcontroller;

import edu.wpi.first.math.controller.BangBangController;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
* This is a sample program to demonstrate the use of a BangBangController with a flywheel to
* control RPM.
*/
public class Robot extends TimedRobot {
private static final int kMotorPort = 0;
private static final int kEncoderAChannel = 0;
private static final int kEncoderBChannel = 1;

private final MotorController m_flywheelMotor = new PWMSparkMax(kMotorPort);
private final Encoder m_encoder = new Encoder(kEncoderAChannel, kEncoderBChannel);

// Create Bang Bang controler
private final BangBangController m_bangBangControler = new BangBangController();

private final Joystick m_joystick = new Joystick(0); // Joystick to control setpoint
private static final double k_maxSetpointValue = 6000; // Max value for joystick control

// Simulation classes help us simulate our robot

private static final double kFlywheelMomentOfInertia =
0.5 * Units.lbsToKilograms(1.5) * Math.pow(Units.inchesToMeters(4), 2); // 1/2*M*R^2

// Reduction between motors and encoder, as output over input. If the flywheel
// spins slower than the motors, this number should be greater than one.
private static final double kFlywheelGearing = 1.0;

private final FlywheelSim m_flywheelSim =
new FlywheelSim(DCMotor.getNEO(1), kFlywheelGearing, kFlywheelMomentOfInertia);
private final EncoderSim m_encoderSim = new EncoderSim(m_encoder);

@Override
public void robotInit() {
// Add bang bang controler to SmartDashboard and networktables.
SmartDashboard.putData(m_bangBangControler);
}

@Override
public void teleopPeriodic() {
// Scale setpoint value between 0 and maxSetpointValue
double setpoint = Math.max(0, m_joystick.getRawAxis(0) * k_maxSetpointValue);

// Set setpoint and measurement of the bang bang controller
double bangOutput = m_bangBangControler.calculate(m_encoder.getRate(), setpoint);
calcmogul marked this conversation as resolved.
Show resolved Hide resolved

// Update motor output (Either 0 or 1)
m_flywheelMotor.set(bangOutput);
}

/** Update our simulation. This should be run every robot loop in simulation. */
@Override
public void simulationPeriodic() {
// To update our simulation, we set motor voltage inputs, update the
// simulation, and write the simulated velocities to our simulated encoder
m_flywheelSim.setInputVoltage(m_flywheelMotor.get() * RobotController.getInputVoltage());
m_flywheelSim.update(0.02);
m_encoderSim.setRate(m_flywheelSim.getAngularVelocityRPM());
}
}