All pages
Powered by GitBook
1 of 4

Loading...

Loading...

Loading...

Loading...

Simulation

Simulation Basics

Testing is an important part of building solid software, and programming robots is no different. When writing code for an FRC robot, testing often involves a fully assembled robot and dedicated time for the Programming team to experiment on it, both of which can be hard to come by at times. When time with the robot is valuable, it's important that your code works how you expect it to on the first try. That's where simulation comes in.

Simulating your robot code allows you to control every input and view every output of your robot code in a simulated environment, letting you put your "robot" in scenarios to see that it does what you want. A simple usage might be to make sure your controls aren't inverted, and a more complicated application may be physics simulating an entire autonomous routine or running automated unit tests on every build. With (quite a lot of) work, you could even practice driving entire matches before the robot is even built.

The basic flow of the simulation is shown in the diagram below, where your code does its thing and all the simulation magic can happen behind the scenes. Your inputs and setup on the GUI are fed right to your code as if the robot was actually there, allowing you to test simple systems without adding anything at all. To test more complicated systems or run physics simulations, you can add some simulation specific code to address the simulation directly and allow you to further customize your control over the simulation.

Simulation is something that can help every team, from the first-time programmers who want to make sure something works as expected to the high-level teams who want to run physics simulations and test complicated algorithms. The more work you put into developing your simulations, the more complex and detailed they can become. That being said, getting started is simple and you can see immediate results with little to no code.

REVLib Simulation Feature Overview

SparkSim Features

Automatic GUI Generation

As your simulation runs, GUI elements will be added to the Devices tab as they are called, with specific dialogues for each sensor and tool.

WPILib Physics Model Integration

Every device simulation object includes a .iterate method designed for easy integration with WPILib's Physics models and tools.

Control Over Native Spark Object

Nearly every attribute of the Spark object is directly addressable via the SparkSim object, allowing you to tailor your simulations to any scenario.

Simulated Fault Manager

By creating a SimFaultManager object, you are given the ability to throw each possible fault individually, either through the GUI or programmatically with the object.

Algorithms and Features

Closed Loop Control

Position, velocity, current, MAXMotion Position Control, and MAXMotion Velocity Control algorithms have been translated into the simulation. All feedforward terms are fully supported.

MAXMotion Simulation

Both MAXMotion Position Control and MAXMotion Velocity Control are able to be fully simulated.

Voltage Compensation Algorithm

The Voltage Compensation algorithm from the Sparks has been ported to the simulation.

Current Limiting Algorithm

The Smart Current Limiting algorithm from the Sparks has been ported to the simulation.

Encoder, Sensor, and Limit Switch Simulation

All auxiliary devices are able to be fully controlled, through their individual simulation objects. Selected sensors will automatically be updated by the SparkSim.iterate() method. For more details on how to set these device simulations up, see Simulating Additional Sensors and Auxiliary Devices.

Simulation Getting Started

WPILib Simulation Tools

In WPILib VSCode, running a robot code simulation is easy: click the WPILib icon in the top right corner of the UI and select 'Simulate Robot Code'. This will compile your code and launch the Simulation GUI, which displays controls and data during your simulation.

You may be prompted to enable Desktop support for your project, especially if you are using C++, or you may need to manually enable it if features don't work as expected. This can be changed by clicking the WPILib logo and selecting 'Change Desktop Support Enabled Setting'.

The Simulation GUI

Once your simulation is running, you'll be prompted to use the Simulation GUI or the normal driver station for simulation control. The Sim GUI has many helpful interfaces all in one place, like the NetworkTables GUI and Other Devices display, so that's what we'll cover here.

To access the Other Devices display, shown on the right, open it via Hardware > Other Devices at the top of the screen. These drop down interfaces are generated by your code and will contain the list of applicable devices, without any simulation-specific code needed.

The GUI in the center contains the NetworkTables, the one at the top left controls enable/disable state, and the one at the bottom left controls joystick order. These give you basic control over the simulation and how you want to interface with it and outputs like you'd see during a match. You can even use a keyboard to emulate a controller if you don't have one! For more information on other elements, see the WPILib Docs.

Simulating Spark MAX and Flex devices

Without any simulation-specific code, your Spark devices will still offer some simulation features. Parameters and settings will be able to be set and retrieved, the setpoint and control mode can be set, and the simulation GUI will reflect all of these changes. However, additional code is required to update the applied output or position/velocity and to access the more complex features of the simulation.

As shown below, both the Spark Flex and Spark MAX have Sim classes, which give you full control over the devices and give you access to the methods needed to update the output of the simulated motor controllers.

// create the DCMotor objects to specify the motor type
DCMotor maxGearbox = DCMotor.getNEO(1);
// multiple motors attached to the same gearbox in follower mode should be
// simulated as one motor
DCMotor flexGearbox = DCMotor.getNeoVortex(2);

// create the normal Spark MAX object
SparkMax max = new SparkMAX(10, MotorType.kBrushless);
// create the Spark MAX sim object
SparkMaxSim maxSim = new SparkMaxSim(max, maxGearbox);

// create the normal Spark Flex object
SparkFlex flex = new SparkFlex(11, MotorType.kBrushless);
// create the Spark Flex sim object
SparkFlexSim flexSim = new SparkFlexSim(flex, flexGearbox);
using namespace frc;
using namespace rev::spark;

// create the DCMotor objects to specify the motor type
DCMotor maxGearbox = DCMotor::NEO(1);
// multiple motors attached to the same gearbox in follower mode should be
// simulated as one motor
DCMotor flexGearbox = DCMotor::NeoVortex(2);

// create the normal Spark MAX object
SparkMax max{10, SparkMax::MotorType::kBrushless};
// create the Spark MAX sim object
SparkMaxSim maxSim{&max, &maxGearbox};

// create the normal Spark Flex object
SparkFlex flex{11, SparkFlex::MotorType::kBrushless};
// create the Spark Flex sim object
SparkFlexSim flexSim{&flex, &flexGearbox};

With these Spark sim objects, you can read and write many fields within the simulation, like manually setting the position, velocity, or motor temperature. The values you set will be visible in the sim GUI and will also be returned by the native functions to get these values in your robot code.

Making Them Move

These Spark sim objects also have a method, called .iterate, that will simulate many of the features of the motor controller and allow you to simulate the motion of the motor with the help of a WPILib physics simulation.

WPILib Physics Models

WPILib offers a number of premade physics models of common FRC systems. These will help us simulate the motion of a motor, as they handle the underlying physics of the load of the motor. Selecting a model and filling out the appropriate fields to describe your physical system will make the simulation as close to real life as possible. These values can be calculated from a CAD model, or measured on a robot.

Putting them together

During a simulation, the physics model takes in the voltage applied to the motor and returns the velocity with which the motor is rotating. The Spark sim's .iterate method takes in the velocity of the motor from the physics model, the bus voltage (supply voltage to the controller), and the time interval for calculations (0.02 seconds, unless you want to track time differently), and updates all the fields of the Spark sim and native Spark to reflect the new state. An example with a simulated arm and a Spark Flex is shown below, but the Spark MAX behavior is the same and the Arm system could be substituted for another WPILib model.

public void simulationPeriodic() {
    // In this method, we update our simulation of what our arm is doing
    // First, we set our "inputs" (voltages)
    m_armSim.setInput(m_motorSim.getAppliedOutput() * RoboRioSim.getVInVoltage());

    // Next, we update it. The standard loop time is 20ms.
    m_armSim.update(0.02);

    // Now, we update the Spark Flex
    flexSim.iterate(
        Units.radiansPerSecondToRotationsPerMinute( // motor velocity, in RPM
            m_armSim.getVelocityRadPerSec()),
        RoboRioSim.getVInVoltage(), // Simulated battery voltage, in Volts
        0.02); // Time interval, in Seconds

    // SimBattery estimates loaded battery voltages
    // This should include all motors being simulated
    RoboRioSim.setVInVoltage(
        BatterySim.calculateDefaultBatteryLoadedVoltage(m_armSim.getCurrentDrawAmps()));

    // Update any external GUI displays or values as desired
    // For example, a Mechanism2d Arm based on the simulated arm angle
    m_arm.setAngle(Units.radiansToDegrees(m_armSim.getAngleRads()));
}
using namespace frc;

void Arm::SimulationPeriodic() {
    // In this method, we update our simulation of what our arm is doing
    // First, we set our "inputs" (voltages)
    m_armSim.SetInput(
        Vectord<1>{flexSim.getAppliedOutput() * RobotController::GetInputVoltage()});

    // Next, we update it. The standard loop time is 20ms.
    m_armSim.update(0.020);

    // Now, we update the Spark Flex
    flexSim.iterate(
        units::revolutions_per_minute_t( // motor velocity, in RPM
            m_armSim.getVelocity()).to<double>(),
        RoboRioSim.getVInVoltage(), // Simulated battery voltage, in Volts
        0.02); // Time interval, in Seconds

    // SimBattery estimates loaded battery voltages
    // This should include all motors being simulated
    sim::RoboRioSim::SetVInVoltage(
        sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()}));

    // Update any external GUI displays or values as desired
    // For example, a Mechanism2d Arm based on the simulated arm angle
    m_arm->SetAngle(m_armSim.GetAngle());
}

Where to now?

  • To see the full list of features, check out REVLib Simulation Feature Overview

  • To simulate sensors and auxiliary devices, see Simulating Additional Sensors and Auxiliary Devices

Simulating Additional Sensors and Auxiliary Devices

Each Spark device has a set of additional sensors, limit switches, and encoders that can be accessed and addressed in your robot code. To simulate each of these, we use a similar model where the user can directly set, either via the GUI or programmatically, each value that these devices measure.

As each auxiliary device is addressed in your native robot code they will be added to the simulation GUI, allowing you to easily adjust their values and test a variety of scenarios.

For example, the code below will generate the GUI display shown below:

Simulating Auxiliary Devices in Code

In the same fashion as the Spark devices, all auxiliary devices have their own Sim classes for accessing the simulation tooling. These follow a similar model, where all physics and motion or change in sensor values need to be handled externally, allowing you to configure these auxiliary devices in the simulation to match how they behave on your robot.

Each Encoder Sim class also contains a .iterate function, which automatically updates both position and velocity from a velocity input, streamlining the process of integrating with an existing WPILib physics simulation. For example, an External/Alternate Encoder attached after a gearbox could be updated with the motor's velocity transformed by the gear ratio to provide accurate measurements, or an independent simulation could be run for the auxiliary device.

SparkMax m_motor = new SparkMax(10, MotorType.kBrushless);
SparkRelativeEncoder m_relEncoder = (SparkRelativeEncoder) m_motor.getEncoder();
SparkAnalogSensor m_analog = m_motor.getAnalog();
SparkAbsoluteEncoder m_absoluteEncoder = m_motor.getAbsoluteEncoder();
using namespace rev::spark;

SparkMax m_motor {10, SparkMax::MotorType::kBrushless};
SparkRelativeEncoder m_relEncoder = m_motor.GetEncoder();
SparkAnalogSensor m_analog = m_motor.GetAnalog();
SparkAbsoluteEncoder m_absoluteEncoder = m_motor.GetAbsoluteEncoder();