CANVenom

class playingwithfusion.CANVenom(motorID: int)

Bases: MotorSafety, MotorController, Sendable

CAN based Venom motor controller instance

This class is used to control a single Venom motor connected to the roboRIO through the CAN bus. The motor supports many controls modes, including: Proportional Dutycycle, Voltage compensated proportional, closed-loop current, closed-loop speed with true s-curve trajector planning, closed-loop position control and motion profile execution

Create an instance of the CAN Venom Motor Controller driver.

This is designed to support the Playing With Fusion Venom motor controller

Parameters:

motorId – The 6-bit identifier used to select a particular motor on the CAN bus. This identifier may be set through the PWF Device configuration page on the roboRIO.

class BrakeCoastMode(value: int)

Bases: pybind11_object

Members:

kCoast : The motor is open circuited when the porportional or volatage command

is zero, causing the motor to coast or free-wheel

kBrake : The motor is shorted when the porportional or vlotage command is zero.

This acts to brake/slow the motor to a stop.

kBrake = <BrakeCoastMode.kBrake: 1>
kCoast = <BrakeCoastMode.kCoast: 0>
property name
property value
class ControlMode(value: int)

Bases: pybind11_object

Members:

kDisabled : Motor is disabled and coasting

kProportional : Proportional (duty-cycle) control

kCurrentControl : Closed-loop current (torque) control

kSpeedControl : Closed-loop speed control.

kPositionControl : Closed-loop position (servo) control.

kMotionProfile : Execute a motion control path.

Motion profiles are generally loaded in Disabled mode. The transition to the MotionProfile state causes Venom to begin following the path.

kFollowTheLeader : Follow the duty cycle commanded to another Venom motor.

Generally used when more that one Venom is geared together in a drivetrain application. In that case one Venom, the leader, executes a motion profile or is placed in another control mode. The other Venom(s) are placed in FolloewTheLeader and command the same duty cycle as the leader so that only the leader is used to calculate closed-loop commands. This avoid implementing PID controllers on multiple motors which may “fight”.

kVoltageControl : Open-loop voltage control mode, also refered to voltage compensated

proportional mode

kCurrentControl = <ControlMode.kCurrentControl: 3>
kDisabled = <ControlMode.kDisabled: 0>
kFollowTheLeader = <ControlMode.kFollowTheLeader: 7>
kMotionProfile = <ControlMode.kMotionProfile: 6>
kPositionControl = <ControlMode.kPositionControl: 5>
kProportional = <ControlMode.kProportional: 1>
kSpeedControl = <ControlMode.kSpeedControl: 4>
kVoltageControl = <ControlMode.kVoltageControl: 8>
property name
property value
class FaultFlag(value: int)

Bases: pybind11_object

Members:

kNone : No Active Faults

kNoHeartbeat : Missing heartbeat from the roboRIO. Ensure device ID matches device ID

used by CANVenom class.

kNoLeaderHeartbeat : Lead motor heartbeat is missing while in FollowTheLeader mode.

kBadLeaderID : The lead motor ID is same as the motor ID. One Venom cannot follow itself.

Ensure the leader and follower have different IDs

kHighTemperature : Motor temperature is too high

kHighCurrent : Average motor current is too high

kBadMode : An invalid control mode was specified by the roboRIO. This should not

occur when using PlayingWithFusionDriver. Contact PWF Technical support.

kDuplicateID : Another Venom with the same device ID was detected on the CAN bus. All

Venom device IDs must be unique

kForwardLimit : The forward limit switch is enabled and is active

kReverseLimit : The reverse limit switch is enabled and is active

kReset : The Venom motor reset, lost power, or browned out since the last time

the {@link #ClearLatchedFaults} function was called

kBadLeaderID = <FaultFlag.kBadLeaderID: 4>
kBadMode = <FaultFlag.kBadMode: 32>
kDuplicateID = <FaultFlag.kDuplicateID: 64>
kForwardLimit = <FaultFlag.kForwardLimit: 128>
kHighCurrent = <FaultFlag.kHighCurrent: 16>
kHighTemperature = <FaultFlag.kHighTemperature: 8>
kNoHeartbeat = <FaultFlag.kNoHeartbeat: 1>
kNoLeaderHeartbeat = <FaultFlag.kNoLeaderHeartbeat: 2>
kNone = <FaultFlag.kNone: 0>
kReset = <FaultFlag.kReset: 512>
kReverseLimit = <FaultFlag.kReverseLimit: 256>
property name
property value
class MotionProfileState(value: int)

Bases: pybind11_object

Members:

kInit : Initial state after Venom powerup

kRunning : Motion profile is currently executing, but has not reached the final

point yet. No errors are active

kErrBufferCleared : The motion profile buffer was cleared while the profile was being

executed. The motor cannot continue and will coast until the motor is placed in another control mode (to reset the error condition)

kErrBufferUnderflow : The motor ran out of points while executing a motion profile. Either

new points were not sent to the motor fast enough or the profile wasn’t terminated using the {@link #CompleteMotionProfilePath} function. The motor cannot continue and will coast until the motor is placed in another control mode (to reset the error condition)

kErrBufferInvalid : Attempted to begin executing a motion profile but there was no valid

start point. This can happen if the {@link #ClearMotionProfilePoints} function is not called before loading a motion profile, or if too many points are loaded and the motor cannot buffer the entire path.

Venom can buffer about 300 points. The exact buffer length can be be determined by calling {@link #GetNumAvaliableMotionProfilePoints} immediatly after power up. If the motion profile contains more points than can be stored in the buffer, the profile must be reloaded each time before begining to follow the profile.

For large paths with many points, first load a subset of the points, begin executing the path, then continue to load new points as the motor executes the path. Call the {@link #GetNumAvaliableMotionProfilePoints} function periodically to ensure the Venom buffer has sufficient space before loading additional points.

kDone : The motion profile was successfully executed. The motor will now

hold the current position (at zero speed) until the motor is placed in another control mode.

kDone = <MotionProfileState.kDone: 5>
kErrBufferCleared = <MotionProfileState.kErrBufferCleared: 2>
kErrBufferInvalid = <MotionProfileState.kErrBufferInvalid: 4>
kErrBufferUnderflow = <MotionProfileState.kErrBufferUnderflow: 3>
kInit = <MotionProfileState.kInit: 0>
kRunning = <MotionProfileState.kRunning: 1>
property name
property value
PIDWrite(output: float) None

Used by an instance of PIDController to command the motor duty-cycle

Places the motor in Proportional control mode and sets the motor proportional command. If disable() or stopMotor() is called, enable() must be called before set() will command motion again.

Parameters:

speed – Proportional motor command from -1.0 to 1.0

addMotionProfilePoint(time: float, speed: float, position: float) None

Add single motion profile point.

Add a single point to the motion profile buffer. To load a motion profile, the application should call clearMotionProfilePoints(), then call addMotionProfilePoint() for each point. The application should then close the path using completeMotionProfilePath() Once a path is loaded, or partially loaded, the application may initiate the motion profile using executePath() or setCommand(ControlMode.MotionProfile, 0)

The motor will will lineraly interpolate commanded speed and position between motion profile points. Acceleration and Jerk limits are not used when executing a motion profile

Parameters:
  • time – Time since the start of the profile in miliseconds

  • speed – Commanded speed in rotations per second

  • position – Commanded motor angle/position in revolutions

clearLatchedFaults() None

Clear all latched faults

clearMotionProfilePoints() None

Erase all motion profile points.

Clear all motion profile points from the motor controller buffer. This function should Be called first, each time a new motion profile path is loaded into the motor controller.

completeMotionProfilePath(time: float, position: float) None

Add final point to motion profile.

Add the last point to a motion profile. The motor will attempt to hold the commanded poistion indefinitly once reaching the final point.

Parameters:
  • time – Time since the start of the profile in milliseconds

  • position – Commanded motor angle/position in revolution

disable() None

Stop applying power to the motor immediately.

If Brake mode is active and the current control mode is Proportional or VoltageControl the motor will brake to a stop. Otherwise the motor will coast.

The enable() function must be called after a call to stopMotor() before motion may be commanded again.

enable() None

Enable the motor again after a call to stopMotor() or disable().

enableLimitSwitches(fwdLimitSwitchEnabled: bool, revLimitSwitchEnabled: bool) None

Enable/disable the forward and reverse limit switches.

Parameters:
  • fwdLimitSwitchEnabled – Prevent forward rotation if this argument is true and the forward limit switch is active

  • revLimitSwitchEnabled – Prevent reverse rotation if this argument is true and the forward limit switch is active

executePath() None

Execute stored motion profile.

Instruct the motor to begin following the sotred motion profile. This function is equivlelent to calling setCommand(ControlMode.MotionProfile, 0)

follow(leadVenom: playingwithfusion._playingwithfusion.CANVenom) None

Place the motor into FollowTheLeader mode and follow the specified motor

This method is equivelent to calling SetComand(FollowTheLeader, ID_of_lead_motor);

Parameters:

leadVenom – Reference to the CANVenom instance which reperesents the lead motor.

get() float

Get the motor duty-cycle.

Returns:

The motor duty cycle as a ratio between -1.0 and 1.0.

getActiveControlMode() playingwithfusion._playingwithfusion.CANVenom.ControlMode

Get the active Venom control mode.

Returns:

Get the active Venom control mode reported by the motor.

getActiveFaults() playingwithfusion._playingwithfusion.CANVenom.FaultFlag

Return set of active motor faults which curently limit or disable motor output. More than one Fault may be active at a time

Returns:

Bitmask of active faults

getAuxVoltage() float

Get the measured voltage at the auxilary analog input on the limit switch breakout board.

Returns:

Auxilary analog input voltage in Volts.

getB() float

Get the feed-forward command offset in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

Feed-forward offset as duty-cycle between -2.0 and 2.0.

getBrakeCoastMode() playingwithfusion._playingwithfusion.CANVenom.BrakeCoastMode

Get the brake/coast behavior when zero is commanded in Proportional and VoltageControl control modes.

Returns:

The Brake or Coast behavion in Proportional and VoltageControl modes

getBusVoltage() float

Get the bus (battery) voltage supplying the Venmom motor.

Returns:

The bus voltage in Volts

getControlMode() playingwithfusion._playingwithfusion.CANVenom.ControlMode

Get the commanded Venom control mode.

Returns:

The commanded control mode

getCurrentMotionProfilePoint() int

Get current motion profile point

Gets the active motion profile point while a motion profile is active. The first point sent to the controller acter a call to clearMotionProfilePoints() is point 0. The next point is 1, then 2, and so on.

Returns:

The motion profile point which is currently targeted by the Venom controller

getDescription() str

Return a description of this motor controller.

Returns:

The Venom motor controller description

getDutyCycle() float

Get the motor h-bridge duty cycle.

Returns:

The motor duty cycle as a ration between -1.0 and 1.0

getFirmwareVersion() int

Return the Venom motor firmware version of the motor asscioated with this instance of the CANVenom class.

Returns:

The Venom motor firmware version (multiplied by 100)

getFwdLimitSwitchActive() bool

Determine the state of the forward motion limit switch.

An internal pull-up resistor activates the limit switch is nothing is connected. Connect the limit switch to GND to deactivate the limit.

Returns:

true if the limit switch voltage is high (which would prevent forward rotation if the limit was enabled)

getInverted() bool

Return the motor direction inversion state.

Returns:

True if the motor direction is inverted

getKD() float

Get the close-loop PID derative gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

PID derivative gain as ratio between 0.0 and 4.0.

getKF() float

Get the feed-forward gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

Feed-forward gain as ratio between -8.0 and 8.0.

getKI() float

Get the close-loop PID integral gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

PID integral gain as ratio between 0.0 and 4.0.

getKP() float

Get the close-loop PID proportional gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

PID proportional gain as ratio between 0.0 and 4.0.

getLatchedFaults() playingwithfusion._playingwithfusion.CANVenom.FaultFlag

Return set of latched motor faults which are curently active or were previously active since the last time the {@link #ClearLatchedFaults} function was called. This function can be helpful when diagnosing harness or brownout issues which cause Venom to reset. The Reset flag will be set each time venom starts up.

Returns:

Bitmask of latched faults

getMaxAcceleration() float

Get the maximum acceleration in the SpeedControl and PositionControl control modes.

This number is used as part of the s-curve path planning in SpeedControl mode and the trapezoid planning in Position Control mode.

Trajectory planning is disabled if the maximum accelleration is zero.

Returns:

Maximum acceleration RPM per second

getMaxJerk() float

Get the maximum jerk (second derivitive of speed) in the SpeedControl control mode.

This number is used as part of the s-curve path planning.

The jerk limit is disabled if the maximum jerk is 0..

Returns:

Maximum jerk RPM per second squared

getMaxPILimit() float

Get the maximum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

Maximum PID output duty-cycle as a ratio between -1.0 and 1.0.

getMaxSpeed() float

Get the maximum speed (absolute value of velocity) that may be commanded in the SpeedControl and PositionControl control modes.

Returns:

Maximum speed command in RPM.

getMinPILimit() float

Get the minimum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Returns:

Minimum PID output duty-cycle as a ratio between -1.0 and 1.0.

getMotionProfileIsValid() bool

Determine if the motor is prepared to execute a motion profile

Determins is a valit start point is present and that the motor is read to begin executing a motion profile.

Returns:

True if the motion profile stored on the motor contains a valid start point

getMotionProfilePositionTarget() float

Get the instantaneous motion profile position commanded

Gets the motor position commanded by the current motion profile point while a motion profile is active

Returns:

The commanded motor position in revolutions.

getMotionProfileSpeedTarget() float

Get the instantaneous motion profile speed commanded

Gets the motor speed commanded by the current motion profile point while a motion profile is active

Returns:

The commanded speed position in revolutions per second (not RPM).

getMotionProfileState() playingwithfusion._playingwithfusion.CANVenom.MotionProfileState

Get the Motion Profile state.

Gets the state of the internal Venom Motion Profile state machine. This state can be used to determine if a motion profile is being executed, has completed sucessfully, or has stopped due to an error.

Returns:

Venom Motion Profile state.

getNumAvaliableMotionProfilePoints() int

Get number of empty motion profile points avaliable.

Gets number of motion profile point buffer locations avaliable in motor controller. The motor will ignore additional calls to addMotionProfilePoint() once all buffer locations are full.

Returns:

The number of remaining empty motion profile points which may be loaded into the Venom controller

getOutputCurrent() float

Get the measured motor current consumption.

Current is measured between the Venom power leads (the battery) to the motor brushes. Current is positive regardles of motor direction. Only current from the battery to the motor is measured. Zero amps are returned if the motor is charging the battery.

Returns:

The measured current Amps.

getOutputVoltage() float

Get the calculated voltage across the motor burshes.

Returns:

The calculated motor voltage in Volts.

getPIDTarget() float

Internal PID Target (position, speed, current).

The PID target is equal to the motor command specified by setCommand() in CurrentControl mode. In SpeedControl and PositionControl modes, the PID command is the output of the s-curve or trapezoidal slew rate limit calculation. In MotionProfile mode the PID command is equal to the current motion profile position command.

In all closed-loop modes, the PID target represents the motor speed/position/current that the Venom PID is activly trying to achieve

Returns:

PID target in RPM, rotations, or Amps (based on current control mode)

getPosition() float

Signed motor revolutions (position) since the last time it was cleared.

Returns:

The signed motor position in revolutions.

getRevLimitSwitchActive() bool

Determine the state of the reverse motion limit switch.

And internal pull-up resistor activates the limit switch is nothing is connected. Connect the limit switch to GND to deactivate the limit.

Returns:

true if the limit switch voltage is high (which would prevent reverse rotation if the limit was enabled)

getSerialNumber() int

Return the serial number of the motor asscioated with this instance of the CANVenom class.

Returns:

The Venom motor serial number

getSpeed() float

Measured signed motor velocity in RPM.

Returns:

Motor velocity in RPM.

getTemperature() float

The measured Venom backplate temperature.

Returns:

Measured backplate temperature in degrees C.

identifyMotor() None

Flash LED to identify motor.

Identify the physical motor asscioated with this instance of the Venom driver by causing its LED to flash red and green for several seconds.

initSendable(builder: wpiutil._wpiutil.SendableBuilder) None

Initialize vaiiables and parameters to be passed into the smart dashboard.

resetPosition() None

Reset the motor revolution counter (position) to 0.

set(command: float) None

Sets the motor duty-cycle command.

Places the motor in Proportional control mode and sets the motor proportional command. If disable() or stopMotor() is called, enable() must be called before set() will command motion again.

Parameters:

speed – Proportional motor duty-cycle command from -1.0 to 1.0

setB(b: float) None

Set Feed-forward duty cycle offset in closed loop control modes.

Parameters:

b – Feed-forward offset as duty-cycle between -2.0 and 2.0.

setBrakeCoastMode(brakeCoastMode: playingwithfusion._playingwithfusion.CANVenom.BrakeCoastMode) None

Set the brake/coast behavior when zero is commanded in Proportional and VoltageControl control modes.

Parameters:

brakeCoastMode – The Brake or Coast behavior in Proportional and VoltageControl modes.

setCommand(*args, **kwargs)

Overloaded function.

  1. setCommand(self: playingwithfusion._playingwithfusion.CANVenom, mode: playingwithfusion._playingwithfusion.CANVenom.ControlMode, command: float) -> None

Set the motor command and control mode.

Where control mode is one of:

  • Proportional - command specifies the raw motor duty-cycle as a ratio between -1.0 and 1.0

  • CurrentControl - command specifies a target motor current in Amps between -40.0 and 40.0.

  • Note that the commanded is signed to specify the motor direction, but the measured motor

current provided by the getOutputCurrent() function is unsigned (the absolute value of current) - In this mode a PID active controls the motor duty cycle to achieve the commanded current. - VoltageControl - command specified the voltage to be applied to the motor bushes as a value between 0.0 and 14.0 Volts. - This mode is also refered to as voltage compensated proportional mode. - Is is useful because the motor speed at a given voltage voltage will be constant if the battery voltage changes, as long as the voltage command is less than the battery voltage. - SpeedControl - command specifies the motor speed value between -6000.0 and 6000.0 RPM. - In this mode a PID activle controls the motor duty cycle to achieve the commanded speed - PositionControl - command specifies the motor position as a value between -4096 and 4096 motor revolutions. - This mode is sometime refered to as servo control because the motor attempts to hold a commanded position, just like a servo. - In this mode a PID actively controls motor duty cycle to achieve the commanded position - MotionProfile - command is unused. - The motor attempts to follow a previously entered motion profile. - Once the last point in the motion profile is reached the motor will hold the last command position from the profile. - See the addMotionProfilePoint() function for more details - FollowTheLeader - command specified the device ID of the Venom motor to follow. - In this mode the Venom motor will command the same duty cycle as the lead motor. - Generally used when more that one Venom is geared together in a drivetrain application. In that case one Venom, the leader, executes a motion profile or is placed in another control mode. The other Venom(s) are placed in FolloewTheLeader and command the same duty cycle as the leader so that only the leader is used to calculate closed-loop commands. This avoid implementing PID controllers on multiple motors which may “fight”.

Parameters:
  • mode – Motor control mode (Proportional, CurrentControl, SpeedControl, etc.)

  • command – Motor command (%, Amps, RPM, etc)

  1. setCommand(self: playingwithfusion._playingwithfusion.CANVenom, mode: playingwithfusion._playingwithfusion.CANVenom.ControlMode, command: float, kF: float, b: float) -> None

Set the motor command and control mode.

Where control mode is one of:

  • Proportional - command specifies the raw motor duty-cycle as a ratio between -1.0 and 1.0

  • CurrentControl - command specifies a target motor current in Amps between -40.0 and 40.0.

  • Note that the commanded is signed to specify the motor direction, but the measured motor

current provided by the getOutputCurrent() function is unsigned (the absolute value of current) - In this mode a PID active controls the motor duty cycle to achieve the commanded current. - VoltageControl - command specified the voltage to be applied to the motor bushes as a value between 0.0 and 14.0 Volts. - This mode is also refered to as voltage compensated proportional mode. - Is is useful because the motor speed at a given voltage voltage will be constant if the battery voltage changes, as long as the voltage command is less than the battery voltage. - SpeedControl - command specifies the motor speed value between -6000.0 and 6000.0 RPM. - In this mode a PID activle controls the motor duty cycle to achieve the commanded speed - PositionControl - command specifies the motor position as a value between -4096 and 4096 motor revolutions. - This mode is sometime refered to as servo control because the motor attempts to hold a commanded position, just like a servo. - In this mode a PID actively controls motor duty cycle to achieve the commanded position - MotionProfile - command is unused. - The motor attempts to follow a previously entered motion profile. - Once the last point in the motion profile is reached the motor will hold the last command position from the profile. - See the {@link #AddMotionProfilePoint} function for more details - FollowTheLeader - command specified the device ID of the Venom motor to follow. - In this mode the Venom motor will command the same duty cycle as the lead motor. - Generally used when more that one Venom is geared together in a drivetrain application. In that case one Venom, the leader, executes a motion profile or is placed in another control mode. The other Venom(s) are placed in FolloewTheLeader and command the same duty cycle as the leader so that only the leader is used to calculate closed-loop commands. This avoid implementing PID controllers on multiple motors which may “fight”.

When the kF and b terms are included in this function, they are guarenteed to be sent to the motor in the same CAN frame as the control mode and command. This is useful when an open-loop correction or feed-forward term is calculated by the roboRIO.

Parameters:
  • mode – Motor control mode (Proportional, CurrentControl, SpeedControl, etc.)

  • command – Motor command (%, Amps, RPM, etc)

  • kF – Feed-forward gain as ratio between -8.0 and 8.0

  • b – Feed-forward offset as duty-cycle between -2.0 and 2.0

setControlMode(controlMode: playingwithfusion._playingwithfusion.CANVenom.ControlMode) None

Set the Venom motor control mode.

Set the control mode without modifying the motor command.

The prefered method to change the motor control mode is the {@link #setCommand} function. Using setCommand() guarentees the control mode and the motor command will be received by the Venom controller at the same time.

Parameters:

controlMode – The commanded control mode.

setInverted(isInverted: bool) None

Specify which direction the motor rotates in response to a posive motor command.

When inverted the motor will spin the opposite direction it rotates when isInverted is false. The motor will always report a positive speed when commanded in the ‘forward’ direction.

This function is commonly used for drivetrain applications so that the and right motors both drive the frobot forward when given a forward command, even though one side is spinnig clockwise and the other is spinning counter clockwise.

Parameters:

isInverted – True if the motor direction should be reversed

setKD(kD: float) None

Set PID Derivative gain.

Parameters:

kD – Derivative gain as a ratio between 0.0 and 4.0.

setKF(kF: float) None

Set Feed-forward gain in closed loop control modes.

Parameters:

kF – Feed-forward gain as a ratio between -2.0 and 2.0

setKI(kI: float) None

Set PID Integral gain.

Parameters:

kI – Integral gain as a ratio between 0.0 and 4.0.

setKP(kP: float) None

Set PID Proportional gain.

Parameters:

kP – Proportional gain as a ratio between 0.0 and 4.0.

setMaxAcceleration(limit: float) None

Set the maximum acceleration in the SpeedControl and PositionControl control modes.

This number is used as part of the s-curve path planning in SpeedControl mode and the trapezoid planning in Position Control mode.

Trajectory planning is disabled if the maximum acceleration is zero

Parameters:

limit – Maximum acceleration between 0 and 25,500 RPM per second

setMaxJerk(limit: float) None

Set the maximum jerk (second derivitive of speed) in the SpeedControl control mode.

This number is used as part of the s-curve path planning.

The jerk limit is disabled if the maximum jerk is 0

Parameters:

limit – Maximum jerk between 0 and 159,375 RPM per second squared.

setMaxPILimit(limit: float) None

Set the maximum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Parameters:

limit – Maximum PID output duty-cycle as a ratio between -1.0 and 1.0.

setMaxSpeed(limit: float) None

Set the maximum speed (absolute value of velocity) that may be commanded in the SpeedControl and PositionControl control modes.

Parameters:

limit – Maximum speed command between 0 and 6000 RPM.

setMinPILimit(limit: float) None

Set the minimum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.

Parameters:

limit – Minimum PID output duty-cycle as a ratio between -1.0 and 1.0.

setPID(kP: float, kI: float, kD: float, kF: float, b: float) None

Set the PID gains for closed-loop control modes.

Sets the proportional, integral, and derivative gains as well as the feed-forward gain and offset. In general, the motor duty-cycle is calculated using:

error = (commandedValue - measuredValue) dutyCycle = (kP * error) + (kI * integral(error)) + (kD * derrivative(error)) + (kF * commandedValue) + b

Parameters:
  • kP – Proportional gain as a ratio between 0.0 and 4.0

  • kI – Integral gain as a ratio between 0.0 and 4.0

  • kD – Derivative gain as a ratio between 0.0 and 4.0

  • kF – Feed-forward gain as a ratio between -2.0 and 2.0

  • b – Feed-forward offset as duty-cycle between -2.0 and 2.0

setPosition(newPosition: float) None

Reset the motor revolution counter (position) to the specified position.

Parameters:

newPosition – Value to assign motor position in revolutions

stopMotor() None

Stop applying power to the motor immediately.

If Brake mode is active and the current control mode is Proportional or VoltageControl the motor will brake to a stop. Otherwise the motor will coast.

The enable() function must be called after a call to stopMotor() before motion may be commanded again.