Usage Spark Base - captainsoccer/BasicMotor GitHub Wiki
SparkBase Usage (Spark MAX & Spark Flex)
This page explains how to use Spark-based motor controllers — specifically the Spark MAX and Spark Flex — with the BasicMotor library. Both controllers share a common interface and configuration structure but differ in hardware capabilities.
Initialization
Spark MAX and Spark Flex share the same initialization pattern in the BasicMotor library. You can create either motor using the constructor that takes a set of core parameters, making setup consistent across different REV motor controllers.
Basic Constructor
BasicMotor motor = new BasicSparkFlex(
new ControllerGains(0.1, 0.0, 0.0), // PID gains
2, // CAN ID
"Intake Motor", // Logging/debug name
10.0, // Gear ratio
);
Configuration Constructor
BasicMotorConfig config = new BasicSparkBaseConfig();
BasicMotor motor = new BasicSparkMax(config);
Configuration
The BasicSparkBaseConfig
class is used to configure Spark-based motor controllers (Spark MAX and Spark Flex). It extends BasicMotorConfig
and includes additional fields specific to REV controllers, such as current limits and encoder settings.
Configuration Options
currentLimitConfig
Defines current limits based on motor conditions (free speed, or stall). The available fields are:
All current limits apply to the stator (output) current of the motor, not the current draw.
freeSpeedCurrentLimit
: Max current (in amps) when motor is spinning faster thanfreeSpeedRPM
stallCurrentLimit
: Max current (in amps) when belowfreeSpeedRPM
freeSpeedRPM
: RPM threshold that separates free speed from stall (in the motor's native rotations per minute)secondaryCurrentLimit
: Absolute max output current used to shut off motor briefly in extreme cases
This provides fine-grained protection — especially helpful for smaller motors like the NEO 550.
setCurrentLimits
function
Using the CurrentLimits currentLimits = new CurrentLimitsSparkBase(
/* freeSpeedCurrentLimit */ 25,
/* stallCurrentLimit */ 50,
/* freeSpeedRPM */ 500,
/* secondaryCurrentLimit */ 60,
);
motor.setCurrentLimits(currentLimits);
Encoders:
The spark base (spark max and spark flex) support connecting a quadrature encoder (relative) or an absolute encoder (pwm) directly to the motor controller. This enables the motor to run the closed loop control (PID) on the motor controller it self while using the external encoder as the measurement source. The most common encoder you can connect is the Rev through bore encoder, which supports both relative and absolute readings.
externalEncoderConfig
Used if you're connecting a relative external encoder directly to the motor controller, also uses the MotorConfig.unitConversion
field. Fields include:
useExternalEncoder
: Whether to use an external encoderinverted
: Whether the encoder direction should be inverted (not inverted is clockwise positive)sensorToMotorRatio
: Ratio of motor turns per encoder turn (a number larger then 1 means the motor spins more)mechanismToSensorRatio
: Ratio of encoder turns per mechanism turn (a number larger then 1 means the encoder spins more)
useExternalEncoder
function
using the motor.useExternalEncoder(
/* inverted */ false,
/* sensorToMotorRatio */ 15,
/* unitConversion */ 1, // The same unit conversion as in the motorConfig section
/* mechanismToSensorRatio */ 1,
);
absoluteEncoderConfig
Used when connecting an absolute encoder directly to the motor controller
useAbsoluteEncoder
: Whether to use the absolute encoderinverted
: Inverts the encoder directionzeroOffset
: Offset to define "zero" position of the mechanism (when the encoder reads this value, it will read as zero)sensorToMotorRatio
: Rotations of the motor per the rotation of the encoder.absoluteEncoderRange
: Range of the encoder, whether it reads values between 0 to 1 or -0.5 to 0.5.
This is particularly useful in systems like swerve drive, where initial orientation matters.
useAbsoluteEncoder
function
using the motor.useAbsoluteEncoder(
/* inverted */ false,
/* zeroOffset */ 0.21,
/* sensorToMotorRatio */ 15,
/* absoluteEncoderRange */ AbsoluteEncoderRange.HALF_REVOLUTION
);
Using Through-Bore Encoder with Spark Flex
If you're using a REV Through-Bore Encoder connected directly to a Spark Flex, you can take advantage of a hybrid setup:
- Use the absolute encoder reading at startup to zero the motor position.
- Then, use the relative encoder (external) for high-resolution feedback during runtime.
This setup is only supported on Spark Flex (not Spark MAX), and requires both encoder signals to be connected to the motor controller.
To enable this behavior:
⚠️ If you're using this hybrid setup, you only need to fully configure the
absoluteEncoderConfig
theexternalEncoderConfig
just needs to haveuseExternalEncoder = true
- no additional values are required for the external encoder.
BasicSparkFlexConfig config = new BasicSparkFlexConfig();
// Use absolute encoder to set initial position
config.absoluteEncoderConfig.useAbsoluteEncoder = true;
// Then use relative encoder (external) for runtime feedback
config.externalEncoderConfig.useExternalEncoder = true;
config.absoluteEncderConfig.sensorToMotorRatio = 12.5;
useExternalEncoderWithAbsoluteEncoder
function
using the motor.useExternalEncoderWithAbsoluteEncoder(
/* inverted */ false,
/* sensorToMotorRatio */ 12.5,
/* zeroOffset */ 0.15,
/* absoluteEncoderRange */ AbsoluteEncoderRange.HALF_REVOLUTION
);