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

REVLib C++: simulating Spark devices doesn't change position or velocity #55

Open
Liam-Stow opened this issue Nov 28, 2024 · 2 comments
Labels
bug Something isn't working REV Robotics

Comments

@Liam-Stow
Copy link

Describe the bug
In REVLib C++, simulating a Spark using SparkFlexSim or SparkMaxSim results in no change to the reported position or velocity of the device.

To Reproduce
Error is present when simulating this project: https://github.com/Liam-Stow/2025-spark-sim/blob/main/src/main/cpp/Robot.cpp
As a quick reference:

void Robot::TeleopInit() {
  m_flex.Set(1.0);
  m_max.Set(1.0);
}

void Robot::SimulationPeriodic() {
  const units::volt_t busVoltage = 12_V;
  const units::second_t dt = 20_ms;

  // Sim Spark MAX + NEO
  units::volt_t neoVoltage = m_maxSim.GetAppliedOutput() * busVoltage;
  m_neoFlywheelSim.SetInputVoltage(neoVoltage);
  m_neoFlywheelSim.Update(dt);
  units::revolutions_per_minute_t neoVelocity = m_neoFlywheelSim.GetAngularVelocity() * GEARING;
  m_maxSim.iterate(neoVelocity.value(), busVoltage.value(), dt.value());

  // Sim Spark Flex + Vortex
  units::volt_t flexVoltage = m_flexSim.GetAppliedOutput() * busVoltage;
  m_vortexFlywheelSim.SetInputVoltage(flexVoltage);
  m_vortexFlywheelSim.Update(dt);
  units::revolutions_per_minute_t flexVelocity = m_vortexFlywheelSim.GetAngularVelocity() * GEARING;
  m_flexSim.iterate(flexVelocity.value(), busVoltage.value(), dt.value());
}

Expected behavior
when the robot state in sim gui is set to enabled, the spark devices should gain a positive velocity and change position over time. Applied output, motor current and setpoint should also change.

Actual behavior
position, velocity, applied output and motor current all stay at zero. The setpoint does change as expected.

Screenshots
Image

As a reference, this is what happens when the equivalent code in Java in simulated:
(A little strange that the velocity jumps at the beginning, but that seems like a different issue.)
Image
The above java example uses this code:

  @Override
  public void teleopInit() {
    max.set(1.0);
    flex.set(1.0);
  }

  @Override
  public void simulationPeriodic() {
    double busVoltage = 12;
    double dt = 0.02;

    // Sim Spark MAX + NEO
    double neoVoltage = maxSim.getAppliedOutput() * busVoltage;
    neoFlywheelSim.setInputVoltage(neoVoltage);
    neoFlywheelSim.update(dt);
    double neoVelocity = neoFlywheelSim.getAngularVelocityRPM() * GEARING;
    maxSim.iterate(neoVelocity, busVoltage, dt);

    // Sim Spark Flex + Vortex
    double vortexVoltage = flexSim.getAppliedOutput() * busVoltage;
    vortexFlywheelSim.setInputVoltage(vortexVoltage);
    vortexFlywheelSim.update(dt);
    double vortexVelocity = vortexFlywheelSim.getAngularVelocityRPM() * GEARING;
    flexSim.iterate(vortexVelocity, busVoltage, dt);
  }

Desktop:

  • OS: Windows 11
  • OS Language: English
  • Project Information: WPILib Information:
    • Project Version: 2025.1.1-beta-2
    • VS Code Version: 1.95.3
    • WPILib Extension Version: 2025.1.1-beta-2
    • C++ Extension Version: 1.22.9
    • Java Extension Version: 1.36.2024092708
    • Java Debug Extension Version: 0.58.2024090204
    • Java Dependencies Extension Version 0.24.0
    • Java Version: 17
    • Java Location: C:\Users\Public\wpilib\2025\jdk
    • Vendor Libraries:
      • REVLib (2025.0.0-beta-3)

Additional context

  • This behavior was also seen in REVLib beta 2.
  • REVLib beta 3 was installed through https://github.com/REVrobotics/REV-Software-Binaries/releases/tag/revlib-2025.0.0-beta-3 not through the inbuilt WPI vendor dependency manager.
  • Attempting to "bypass" the iterate() function and instead calling m_flexSim.SetVelocity() or m_flexSim.SetPosition() directly results in the same issue: no change to the device velocity in sim gui.
  • There is also no change to the various encoder devices in sim gui ("SPARK MAX [1] RELATIVE ENCODER", etc)
@Liam-Stow Liam-Stow added the bug Something isn't working label Nov 28, 2024
@jfabellera
Copy link
Contributor

This looks to be an issue with the flywheel sim or how it is used.

When I debug this program, the values for neoVelocity and flexVelocity are 0 (regardless of what robot state I select)

Image

If I replace the variable in iterate() with a number, it looks to behave correctly.

Image

@Liam-Stow
Copy link
Author

Thanks for looking into the issue.
Interestingly, that is not the behavior I am seeing when running with constant numbers in iterate(). This is the simplest I can think to make it, and I still don't see any movement on the sim:
Image

I can also bypass iterate() entirely by running SetVelocity() and SetPosition() and the sim still stays at all zero (except the setpoint, which does change to match any spark.Set() calls)
Image

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working REV Robotics
Projects
None yet
Development

No branches or pull requests

2 participants