Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
340 changes: 340 additions & 0 deletions Docs/2_Architecture/2.10_KitbotSim.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,340 @@
# Kitbot Sim Tutorial

## Intro

Writing code is plenty of fun on its own, but its rough having to wait for mechanical to be done to test it.
When we only have 2-3 weeks of time (which we have to share with drive practice!) after the robot is built before our first competition, we need to be able to test before the robot is ready.
Luckily, we have a handy piece of code that to refactor to be simulateable!
In this tutorial we are going to rework your kitbot code to be easy to simulate and expand on.
In the end your code should be able to do this:

[Video of robot in sim](https://drive.google.com/file/d/1AD0OLK8Lt1dHbn5YYZ8rYc_6_0wbLPJf/view?usp=sharing)

## Code Walkthrough

You'll notice that a lot of this looks similar to the real classes that you added in Lesson [2.8](2.8_KitbotAKitRefactor.md).
This is intentional!
We want our simulated behavior to be as similar to real-life behavior as possible, otherwise our simulation would not be very valuable.
For the most part, writing this will consist of substituting stuff like simulated motors for real motors.

Let's add another IO Implementation.
Like the real IO class, this file will define the `updateInputs()` and `setVolts()` methods, but implement them differently (through sim).
Since we aren't writing this for real hardware, we are going to make `DrivetrainIOSim`.

Make a new `DrivetrainIOSim` class that implements `DrivetrainIO` the [same way](2.8_KitbotAKitRefactor.md#drivetrainioreal) you did for `DrivetrainIOReal`.

```Java
public class DrivetrainIOSim implements DrivetrainIO {

@Override
public void updateInputs(DrivetrainIOInputs inputs) {
// TODO Auto-generated method stub

}

@Override
public void setVolts(double left, double right) {
// TODO Auto-generated method stub

}
}
```

Some of these fields we can get directly from a simulated motor.
TalonFX comes with built-in simulation support, so we can treat it like a regular motor for the most part.
Add them the same way you did for `DrivetrainIOReal`.

```Java
TalonFX leftTalon = new TalonFX(DrivetrainSubsystem.LEFT_TALON_ID);
TalonFX rightTalon = new TalonFX(DrivetrainSubsystem.RIGHT_TALON_ID);
```

To get the simulated outputs we can call `talon.getSimState()` and store the results in a variable.
Do this in `updateInputs`.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
var leftSimState = leftTalon.getSimState();
var rightSimState = rightTalon.getSimState();
// Snip
}
```

Now you can call `simState.getMotorVoltage()` to get the voltage for each motor.
Do this for the `left-` and `rightOutputVolts`.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
// Snip
inputs.leftOutputVolts = leftSimState.getMotorVoltage();
inputs.rightOutputVolts = rightSimState.getMotorVoltage();
// Snip
}
```

We can also get the current from each of the motor's sim states.
There are two types of current we can measure: `TorqueCurrent` and `SupplyCurrent`.
`SupplyCurrent` is like the available current for the motor, and is what the breaker measures.
`TorqueCurrent` is the amount of current the motor is actually using, and is important for heat management.
`TorqueCurrent` is more useful for our purposes since it shows the actual current usage of the motor.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
// Snip
inputs.leftCurrentAmps = leftSimState.getTorqueCurrent();
inputs.leftTempCelsius = 0.0;
inputs.rightCurrentAmps = rightSimState.getTorqueCurrent();
inputs.rightTempCelsius = 0.0;
}
```

This information is useless without having a way to set the motor voltage.
Copy the `VoltageOut` objects from `DrivetrainIOReal` below the `TalonFX`s.

```Java
TalonFX leftTalon = new TalonFX(DrivetrainSubsystem.LEFT_TALON_ID);
TalonFX rightTalon = new TalonFX(DrivetrainSubsystem.RIGHT_TALON_ID);

VoltageOut leftVoltage = new VoltageOut(0);
VoltageOut rightVoltage = new VoltageOut(0);
```

Then copy the `setVolts` method from `DrivetrainIOReal`.

```Java
@Override
public void setVolts(double left, double right) {
leftTalon.setControl(leftVoltage.withOutput(left));
rightTalon.setControl(rightVoltage.withOutput(right));
}
```

Finally, we need to add a physics sim.
This will take these motor voltages and figure out how the mechanisms might actually behave using a mathematical model.
WPILib provides the `DifferentialDrivetrainSim` class for this.
This class has the `createKitbotSim()` static method to provide a convenient way to set this up with the physical constants for a kitbot.

Start by creating a new `DifferentialDrivetrainSim` called `physicsSim` under the `VoltageOut`s.

```Java
DifferentialDrivetrainSim physicsSim = DifferentialDrivetrainSim.createKitbotSim(
null,
null,
null,
null);
```

The first value in this constructor is the motor for the sim.
Let's assume we're using Falcons and use `KitbotMotor.kDoubleFalcon500PerSide` to generate the constants for this.
This model assumes we have 2 motors on each side of the drivetrain, although we only programmed one.
For a sim this doesn't matter, but for a real robot we would need to add follower motors.
We are going to ignore that for this tutorial.

```Java
DifferentialDrivetrainSim physicsSim = DifferentialDrivetrainSim.createKitbotSim(
KitbotMotor.kDoubleFalcon500PerSide,
null,
null,
null);
```

The second parameter is the gearing of the drivetrain.
This is something we normally would ask mechanical for.
In this case, since the drivetrain is simulated, we can use the standard 8p45 gearbox.

```Java
DifferentialDrivetrainSim physicsSim = DifferentialDrivetrainSim.createKitbotSim(
KitbotMotor.kDoubleFalcon500PerSide,
KitbotGearing.k8p45,
null,
null);
```

The third parameter is the size of the wheels.
By default the kitbot comes with 6 inch wheels.

```Java
DifferentialDrivetrainSim physicsSim = DifferentialDrivetrainSim.createKitbotSim(
KitbotMotor.kDoubleFalcon500PerSide,
KitbotGearing.k8p45,
KitbotWheelSize.kSixInch,
null);
```

The final parameter is the "measurement standard deviations".
This is a way for us to add uncertainty to our simulated model in a way that matches real sensor noise.
For this exercise we can ignore it and leave it as null.

Now we have a fully set up physics sim.
On real robots we often have to be more careful when finding these physical constants, since they aren't usually so standard, but the kitbot is nice and easy.
Make sure to work with mechanical to find these constants in season.

Next we need to actually use the physics sim.
In `updateInputs` add a call to `physicsSim.update()`.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
physicsSim.update(0.020);

var leftSimState = leftTalon.getSimState();
var rightSimState = rightTalon.getSimState();
// Snip
}
```

This method runs the simulation for the number of seconds passed in.
We use 20 milliseconds, which is the default loop time of the rio.

Next we need up update the inputs to the sim based on the motor voltages.
Call `physicsSim.setInputs()` with the motor sim state voltages.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
physicsSim.update(0.020);

var leftSimState = leftTalon.getSimState();
var rightSimState = rightTalon.getSimState();

physicsSim.setInputs(leftSimState.getMotorVoltage(), rightSimState.getMotorVoltage());
// Snip
}
```

We're almost done with `DrivetrainIOSim`!
Now we just need to update the rest of the IOInputs based on the simulator.
Start by making the wheel speeds update with the `physicsSim.getLeftVelocityMetersPerSecond`.
Then update the wheel positions with `physicsSim.getLeftPositionMeters`.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
// Snip
inputs.leftVelocityMetersPerSecond = physicsSim.getLeftVelocityMetersPerSecond();
inputs.rightVelocityMetersPerSecond = physicsSim.getRightVelocityMetersPerSecond();

inputs.leftPositionMeters = physicsSim.getLeftPositionMeters();
inputs.rightPositionMeters = physicsSim.getRightPositionMeters();
// Snip
}
```

Theres one more thing we should do to help make this sim realistic.
When our motors are running the voltage of the battery will "sag" or drop.
This can reduce our motor's output in the extreme case.
To simulate this use `simState.setSupplyVoltage(RoboRioSim.getVInVoltage())`.
`setSupplyVoltage` will control how much voltage is available to the motor simulation.
`RoboRioSim.getVInVoltage()` will record how much battery our motors should be using, and the effect that will have on the battery.

```Java
@Override
public void updateInputs(DrivetrainIOInputs inputs) {
physicsSim.update(0.020);

var leftSimState = leftTalon.getSimState();
leftSimState.setSupplyVoltage(RoboRioSim.getVInVoltage());

var rightSimState = rightTalon.getSimState();
rightSimState.setSupplyVoltage(RoboRioSim.getVInVoltage());
// Snip
}
```

Now we're done with the `DrivetrainIOSim` class! 🎉

Let's add a way to switch between using a `DrivetrainIOReal` or a `DrivetrainIOSim` depending on if the robot is real or simulated.
The `Robot.isReal()` method will return whether or not the robot is currently running in real life or not so we can use that to select which object to use.
Replace the `io` assignment with the following line:

```Java
public class DrivetrainSubsystem extends SubsystemBase {
DrivetrainIO io = Robot.isReal() ? new DrivetrainIOReal() : new DrivetrainIOSim();
}
```
This will now select the correct io object to create, and will now work in sim.

But it won't have any way to track the position of the drivebase.
Remember that we can use odometry to track the position of a drivebase.
We can create a new `DifferentialDriveOdometry` object in `DrivetrainSubsystem` to handle this.

```Java
public class DrivetrainSubsystem extends SubsystemBase {
DrivetrainIO io = Robot.isReal() ? new DrivetrainIOReal() : new DrivetrainIOSim();
DrivetrainIOInputsAutoLogged inputs = new DrivetrainIOInputsAutoLogged();

DifferentialDriveOdometry odometry = new DifferentialDriveOdometry(new Rotation2d(), 0, 0);
// Snip
}
```

We will need to update this every processor loop.
Normally we would have a gyro to track the heading (rotation) of the drive base, and we'd update the odometry object with its values instead.
However, in simulation we don't have an easy way to make a gyro that behaves how we would expect.
Instead, we can use the following line to fudge it:

```Java
odometry.getPoseMeters().getRotation()
.plus(
Rotation2d.fromRadians(
(inputs.leftSpeedMetersPerSecond - inputs.rightSpeedMetersPerSecond)
* 0.020 / Units.inchesToMeters(26)))
```

This line is using a small piece of math to calculate what the new rotation should be based off of our wheel speeds.
You don't need to know how this works in particular, just know it's a bit of a hack.

We are going to wrap this in an `odometry.update()` call.
We only want this to run in simulation, since if it's in real life we'll just use the gyro data, so we'll also wrap this in a check for if the robot is in simulation.

```Java
@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Drivetrain", inputs);


if (Robot.isSimulation) {
odometry.update(
odometry.getPoseMeters().getRotation()
// Use differential drive kinematics to find the rotation rate based on the wheel speeds and distance between wheels
.plus(Rotation2d.fromRadians((inputs.leftVelocityMetersPerSecond - inputs.rightVelocityMetersPerSecond)
* 0.020 / Units.inchesToMeters(26))),
inputs.leftPositionMeters, inputs.rightPositionMeters);
}
}
```

Finally, we need to send the odometry pose to the logger so we can visualize it.
We do this using `Logger.recordOutput()` and `odometry.getPoseMeters()`.

```Java
@Override
public void periodic() {
// Snip
Logger.recordOutput("Drivetrain Pose", odometry.getPoseMeters());
}
```

This should be everything you need to have a full drivebase simulation!

### Running the Simulation

To run a robot code simulation, click on the WPILib icon in the top right corner.
Then find or search for "Simulate Robot Code" and press it.
Once the code builds, it will prompt you to choose between using the driver station and sim gui.
Choose the sim gui.

The sim gui is perfectly serviceable for testing, but we can do better.
AdvantageScope supports connecting to a simulation to visualize IO.
When you open AdvantageScope, hit "file", then "Connect to Simulator".
This lets you visualize data from the simulator in the same way as you would with a real robot.
You can use the 3d field visualization to have a fun way to show the robot on the field.

To drive the robot, add "keyboard 0" to "joystick 0" in the sim gui.
You might have to change your keyboard settings in the sim gui to make it properly emulate a joystick.
Then make sure to set the mode to teleop.
You can also check your setup against a teammate or lead's.
2 changes: 1 addition & 1 deletion Docs/2_Architecture/2.1_WPILib.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ Many of these libraries will have their own articles here as well as their own d

### Must read/watch

- Read through our [electrical reference sheet](../General/ElectronicsCrashCourse.md)
- Read through our [electrical reference sheet](2.2_ElectronicsCrashCourse.md)
- In an ideal world, we never have to touch the electrical system.
In reality, often we end up finding problems with electrical early in the season.
Therefore it is important to know what we are working with to debug and fix the robot.
Expand Down
1 change: 1 addition & 0 deletions Docs/2_Architecture/2.2_ElectronicsCrashCourse.md
Original file line number Diff line number Diff line change
Expand Up @@ -280,6 +280,7 @@ Instead, we use "current zeroing".
This involves slowly powering a mechanism into a hardstop with a known position (like an elevator being all the way down).
When the current draw of the motor spikes, we know that the motor is "stalling", or using power but not moving.
This tells us that we are at the hardstop in the same way that a limit switch would.
Think of it as walking towards a wall blindfolded with your hands outstretched- when you get to a point where you're not getting anywhere and are exerting a lot of force in front of you , you'll know you're at the wall.

### IMU

Expand Down
4 changes: 2 additions & 2 deletions Docs/2_Architecture/2.3_CommandBased.md
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ For example, we might want something to happen while a condition is true (`while
Some large Commands are better represented by several Commands and some Triggers!

Subsystems, commands, and triggers are the building blocks of the robot's overall "superstructure".
This will be covered in more detail in the [Superstructure article.](2.10_Superstructure.md)
This will be covered in more detail in the [Superstructure article.](2.11_Superstructure.md)

### Resources

Expand All @@ -52,7 +52,7 @@ This will be covered in more detail in the [Superstructure article.](2.10_Supers

### Exercises

- Make basic KitBot code using the Command-Based skeleton. You can follow [this](2.5_KitbotExampleWalkthrough.md) tutorial.
- Make basic KitBot code using the Command-Based skeleton. You can follow [this](2.5_KitbotIntro.md) tutorial.

### Notes

Expand Down
Loading