Simulating CANSpark motors in robotpy

I am trying to create a physics model for our team’s robot, which uses rev CANSpark motors. I haven’t been able to find documentation or examples for python that does this, and so far have not been able to crack the code. Does anyone have any experience or suggestions?

I believe rev has better simulation support in 2022, so you’ll have to wait for that. Hopefully tonight, but maybe tomorrow depending on these Windows issues.

However, if you’re really impatient, you can find a list of all the available simulation devices via wpilib.simulation.SimDeviceSim.enumerateDevices, and maybe there’s something there that you hadn’t seen previously?

I tried with 2022 and still not working. I think the problem is even before we get to physics, as I can’t see any values update in the Other Devices panel when I drive the robot in the simulator, even though

  1. I can see changes in the PWM Outputs panel when I instantiate Jaguars instead of CANSparkMax motors, and
  2. We have successfully driven an actual robot with the CANSparkMax controllers, so I know that we’re instantiating them correctly.

To create the simplest test case possible, I forked robotpy/examples and created a branch to test where the ONLY difference is whether Jaguars or CANSparkMaxes are initialized. It’s here: https://github.com/FRC1076/robotpy-examples/blob/spark-sim/physics/src/robot.py

First–am I correct in assuming that I should see values updating in Other Devices/Spark Max [1] if simulation is working correctly?

And next–am I correct in assuming that physics simulation won’t work if the values in Other Devices aren’t changing, since presumably this means the simulator can’t read from the HAL correctly?

Dug into this a little bit:

  • According to REV’s changelog, in 2022.1.0… “Java: Adds initial WPILib simulation support”, but no mention of C++ support
  • There’s a REVPhysicsSim in Java but not in C++… so I’m guessing they didn’t implement the WPILib simulation interface and did their own thing instead?

@NoahAndrews answered some questions in another thread so maybe he knows. Noah, did you guys implement simulation for C++?

It does look like they have some WPILib simulation support built in. Try this program out:

#!/usr/bin/env python3

import pprint
import rev
import wpilib.simulation

m = rev.CANSparkMax(0, rev.CANSparkMaxLowLevel.MotorType.kBrushless)
print("devices:", wpilib.simulation.SimDeviceSim.enumerateDevices())

sm = wpilib.simulation.SimDeviceSim("SPARK MAX [0]")
print("SparkMax properties:")
pprint.pprint(sm.enumerateValues())

v = sm.getDouble("Motor Current")
v.value = 42
print("Motor current is", m.getOutputCurrent())

The output I get is:

devices: ['SPARK MAX [0]']
SparkMax properties:
[('Applied Output', False),
 ('Faults', False),
 ('Sticky Faults', False),
 ('Velocity', False),
 ('Velocity Conversion Factor', False),
 ('Velocity Pre-Conversion', False),
 ('Position', False),
 ('Position Conversion Factor', False),
 ('Motor Temperature', False),
 ('Bus Voltage', False),
 ('Motor Current', False),
 ('Analog Voltage', False),
 ('Analog Velocity', False),
 ('Analog Position', False),
 ('Alt Encoder Velocity', False),
 ('Alt Encoder Position', False),
 ('Control Mode', False),
 ('Stall Torque', False),
 ('Free Speed', False),
 ('FW Version', False)]
Motor current is 42.0

Now that I’ve actually read your question (sorry!), the answers are:

Yes, but…

you have to do the work to make the simulation work correctly. In your modified example, you’re creating PWMSim objects, which will only affect PWM motors, not CANSparkMAX motors. To affect the operation of a CANSparkMax motor, you need to set the correct sim value. Which is… one of those.

1 Like

OK, thanks for all this. I do know that the physics sim won’t work with PWMSim objects and that I’ll need SimDeviceSims (did that in another repo), but none of that was working and I thought that having the values show up in the simulator at all (e.g., in the Other Devices panel) was a prerequisite. Sounds like that may not be the case. I did previously confirm that I could see the Spark MAX devices using enumerateDevices(), but didn’t try enumerating values (and wouldn’t have thought to access ‘Motor Current’–I had tried ‘Velocity’ since I saw that in the Other Devices panel, but got nothing). Will report back once I have a chance to try this out.

I didn’t run your modified example on Saturday, but I just ran it now and the sparks show up in other devices with all the values I mentioned.

The bug that caused the ctre bindings to completely break was something core to pybind11, which we use to wrap all of the C++ libraries that we depend on. Maybe that was causing your issue here? I pushed a rebuild of all RobotPy libraries this weekend with the fix, so please upgrade everything and see if the behavior still doesn’t match your expectations.

OK, I was able to get the example working and I updated to the latest robotpy and robotpy[rev]. However, what I’m hoping to do is read values in simulation that are set when the robot is driven (e.g., so we can make our robot drive around on the 2D field). Here is my attempt at setting the motor speed and then reading values from the SimDeviceSim:

#!/usr/bin/env python3

import pprint
import rev
import wpilib.simulation

m = rev.CANSparkMax(0, rev.CANSparkMaxLowLevel.MotorType.kBrushless)

sm = wpilib.simulation.SimDeviceSim("SPARK MAX [0]")

print('\n*** before set speed ***')
for tup in sm.enumerateValues():
  v = sm.getDouble(tup[0])
  print(tup[0], v.get())

m.set(0.5)

print('\n*** after set speed ***')
for tup in sm.enumerateValues():
  v = sm.getDouble(tup[0])
  print(tup[0], v.get())

And here is the output. As you can see no values have been changed:

*** before set speed ***
Applied Output 0.0
Faults 0.0
Sticky Faults 0.0
Velocity 0.0
Velocity Conversion Factor 1.0
Velocity Pre-Conversion 1.0
Position 0.0
Position Conversion Factor 1.0
Motor Temperature 0.0
Bus Voltage 12.0
Motor Current 0.0
Analog Voltage 0.0
Analog Velocity 0.0
Analog Position 0.0
Alt Encoder Velocity 0.0
Alt Encoder Position 0.0
Control Mode 0.0
Stall Torque 0.0
Free Speed 0.0
FW Version 0.0

*** after set speed ***
Applied Output 0.0
Faults 0.0
Sticky Faults 0.0
Velocity 0.0
Velocity Conversion Factor 1.0
Velocity Pre-Conversion 1.0
Position 0.0
Position Conversion Factor 1.0
Motor Temperature 0.0
Bus Voltage 12.0
Motor Current 0.0
Analog Voltage 0.0
Analog Velocity 0.0
Analog Position 0.0
Alt Encoder Velocity 0.0
Alt Encoder Position 0.0
Control Mode 0.0
Stall Torque 0.0
Free Speed 0.0
FW Version 0.0

I don’t have time to look at this right this second, but someone else was trying a similar thing with the CTRE libraries, and CTRE doesn’t set the value immediately, it delays similar to how real hardware does. It’s possible rev does this also?

You might try modifying the example I created in that post and see if you get expected results by waiting for change.

However, I agree that none of those value names really look like what you’re looking for. Unfortunately, if REV doesn’t support simulation, there’s not a ton I can do. You might try emailing REV support and ask them about their C++ simulation support (or @NoahAndrews might know someone who knows the answer?). None of their examples seem to explicitly support simulation.

I did reach out to REV and got this response:

C++ doesn’t have the part of sim support where position is calculated based on the velocity history. This first iteration on sim support is incomplete, and we’re going to be making significant changes.

Hopefully it will be better soon!

OK, sounds like I should stop beating my head against this. Bummer that we can’t use simulation for robot code development given the choice to use Spark. Is there a list or some such that one can subscribe to for tracking REV releases?

Looks like they post them here: https://github.com/REVrobotics/REV-Software-Binaries/releases

Just tested this out on my end, even using simple .set() all values seem to stay at zero, darn… we’ll live without the simulator but i hope to see it in future years!
image

Have you seen the Rev Trello board, which also has a link to a form to submit feature requests? Trello

Yes i have, also bookmarked the github releases repo, did i miss something :o

This topic was automatically closed 365 days after the last reply. New replies are no longer allowed.