Class CANVenom
- java.lang.Object
-
- edu.wpi.first.wpilibj.MotorSafety
-
- com.playingwithfusion.CANVenom
-
- All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable
,edu.wpi.first.wpilibj.motorcontrol.MotorController
,edu.wpi.first.wpilibj.SpeedController
,java.lang.AutoCloseable
public class CANVenom extends edu.wpi.first.wpilibj.MotorSafety implements edu.wpi.first.wpilibj.motorcontrol.MotorController, edu.wpi.first.util.sendable.Sendable, java.lang.AutoCloseable
CAN based Venom motor controller instanceThis 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
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
CANVenom.BrakeCoastMode
static class
CANVenom.ControlMode
static class
CANVenom.FaultFlag
static class
CANVenom.MotionProfileState
-
Constructor Summary
Constructors Constructor Description CANVenom(int motorId)
Create an instance of the CAN Venom Motor Controller driver.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
addMotionProfilePoint(double time, double speed, double position)
Add single motion profile point.void
clearLatchedFaults()
Clear all latched faultsvoid
clearMotionProfilePoints()
Erase all motion profile points.void
close()
Destroy the CANVenom object and free any asscioated resources.void
completeMotionProfilePath(double time, double position)
Add final point to motion profile.void
disable()
Stop applying power to the motor immediately.void
enable()
Enable the motor again after a call to stopMotor() or disable().void
enableLimitSwitches(boolean fwdLimitSwitchEnabled, boolean revLimitSwitchEnabled)
Enable/disable the forward and reverse limit switches.void
executePath()
Execute stored motion profile.void
follow(CANVenom leadVenom)
Place the motor into FollowTheLeader mode and follow the specified motordouble
get()
Get the motor duty-cycle.CANVenom.ControlMode
getActiveControlMode()
Get the active Venom control mode reported by the motor.java.util.EnumSet<CANVenom.FaultFlag>
getActiveFaults()
Return set of active motor faults which curently limit or disable motor output.double
getAuxVoltage()
Get the measured voltage at the auxilary analog input on the limit switch breakout board.double
getB()
Get the feed-forward command offset in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.CANVenom.BrakeCoastMode
getBrakeCoastMode()
Get the brake/coast behavior when zero is commanded in Proportional and VoltageControl control modes.double
getBusVoltage()
Get the bus (battery) voltage supplying the Venmom motor.CANVenom.ControlMode
getControlMode()
Get the commanded Venom control mode.int
getCurrentMotionProfilePoint()
Get current motion profile point.java.lang.String
getDescription()
Return a description of this motor controller.double
getDutyCycle()
Get the motor h-bridge duty cycle.long
getFirmwareVersion()
Return the Venom motor firmware version of the motor asscioated with this instance of the CANVenom class.boolean
getFwdLimitSwitchActive()
Determine the state of the forward motion limit switch.boolean
getInverted()
Return the motor direction inversion state.double
getKD()
Get the close-loop PID derative gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.double
getKF()
Get the feed-forward gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.double
getKI()
Get the close-loop PID integral gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.double
getKP()
Get the close-loop PID proportional gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.java.util.EnumSet<CANVenom.FaultFlag>
getLatchedFaults()
Return set of latched motor faults which are curently active or were previously active since the last time theclearLatchedFaults()
function was called.double
getMaxAcceleration()
Get the maximum acceleration in the SpeedControl and PositionControl control modes.double
getMaxJerk()
Get the maximum jerk (second derivitive of speed) in the SpeedControl control mode.double
getMaxPILimit()
Get the maximum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.double
getMaxSpeed()
Get the maximum speed (absolute value of velocity) that may be commanded in the SpeedControl and PositionControl control modes.double
getMinPILimit()
Get the minimum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.boolean
getMotionProfileIsValid()
Determine if the motor is prepared to execute a motion profiledouble
getMotionProfilePositionTarget()
Get the instantaneous motion profile position commanded.double
getMotionProfileSpeedTarget()
Get the instantaneous motion profile speed commanded.CANVenom.MotionProfileState
getMotionProfileState()
Get the Motion Profile state.int
getNumAvaliableMotionProfilePoints()
Get number of empty motion profile points avaliable.double
getOutputCurrent()
Get the measured motor current consumption.double
getOutputVoltage()
Get the calculated voltage across the motor burshes.double
getPIDTarget()
Internal PID Target (position, speed, current).double
getPosition()
Signed motor revolutions (position) since the last time it was cleared.boolean
getRevLimitSwitchActive()
Determine the state of the reverse motion limit switch.long
getSerialNumber()
Return the serial number of the motor asscioated with this instance of the CANVenom class.double
getSpeed()
Measured signed motor velocity in RPM.double
getTemperature()
The measured Venom backplate temperature.void
identifyMotor()
Flash LED to identify motor.void
initSendable(edu.wpi.first.util.sendable.SendableBuilder builder)
Initialize vaiiables and parameters to be passed into the smart dashboard.void
pidWrite(double speed)
Used by an instance of PIDController to command the motor duty-cyclevoid
resetPosition()
Reset the motor revolution counter (position) to 0.void
set(double speed)
Sets the motor duty-cycle command.void
setB(double b)
Set Feed-forward duty cycle offset in closed loop control modes.void
setBrakeCoastMode(CANVenom.BrakeCoastMode brakeCoastMode)
Set the brake/coast behavior when zero is commanded in Proportional and VoltageControl control modes.void
setCommand(CANVenom.ControlMode mode, double command)
Set the motor command and control mode.void
setCommand(CANVenom.ControlMode mode, double command, double kF, double b)
Set the motor command and control mode.void
setControlMode(CANVenom.ControlMode controlMode)
Set the Venom motor control mode.void
setInverted(boolean isInverted)
Specify which direction the motor rotates in response to a posive motor command.void
setKD(double kD)
Set PID Derivative gain.void
setKF(double kF)
Set Feed-forward gain in closed loop control modes.void
setKI(double kI)
Set PID Integral gain.void
setKP(double kP)
Set PID Proportional gain.void
setMaxAcceleration(double limit)
Set the maximum acceleration in the SpeedControl and PositionControl control modes.void
setMaxJerk(double limit)
Set the maximum jerk (second derivitive of speed) in the SpeedControl control mode.void
setMaxPILimit(double limit)
Set the maximum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.void
setMaxSpeed(double limit)
Set the maximum speed (absolute value of velocity) that may be commanded in the SpeedControl and PositionControl control modes.void
setMinPILimit(double limit)
Set the minimum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.void
setPID(double kP, double kI, double kD, double kF, double b)
Set the PID gains for closed-loop control modes.void
setPosition(double newPosition)
Reset the motor revolution counter (position) to the specified position.void
setVoltage(double outputVolts)
Sets the motor voltage comand.void
stopMotor()
Stop applying power to the motor immediately.
-
-
-
Constructor Detail
-
CANVenom
public CANVenom(int motorId)
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.
-
-
Method Detail
-
close
public void close()
Destroy the CANVenom object and free any asscioated resources.- Specified by:
close
in interfacejava.lang.AutoCloseable
-
stopMotor
public void stopMotor()
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.- Specified by:
stopMotor
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
stopMotor
in interfaceedu.wpi.first.wpilibj.SpeedController
- Specified by:
stopMotor
in classedu.wpi.first.wpilibj.MotorSafety
-
getDescription
public java.lang.String getDescription()
Return a description of this motor controller.- Specified by:
getDescription
in classedu.wpi.first.wpilibj.MotorSafety
- Returns:
- The Venom motor controller description
-
initSendable
public void initSendable(edu.wpi.first.util.sendable.SendableBuilder builder)
Initialize vaiiables and parameters to be passed into the smart dashboard.- Specified by:
initSendable
in interfaceedu.wpi.first.util.sendable.Sendable
-
set
public void set(double speed)
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.
- Specified by:
set
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
set
in interfaceedu.wpi.first.wpilibj.SpeedController
- Parameters:
speed
- Proportional motor duty-cycle command from -1.0 to 1.0
-
pidWrite
public void pidWrite(double speed)
Used by an instance of PIDController to command the motor duty-cyclePlaces 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
-
setVoltage
public void setVoltage(double outputVolts)
Sets the motor voltage comand.Places the motor in VoltageControl control mode and sets the motor voltage command. Voltage control is sometimes refered to as voltage compensated proportional mode.
- Specified by:
setVoltage
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
setVoltage
in interfaceedu.wpi.first.wpilibj.SpeedController
- Parameters:
outputVolts
- Commanded motor voltage from 0.0 to 14.0 volts
-
get
public double get()
Get the motor duty-cycle.- Specified by:
get
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
get
in interfaceedu.wpi.first.wpilibj.SpeedController
- Returns:
- The motor duty cycle as a ratio between -1.0 and 1.0.
-
setInverted
public void setInverted(boolean isInverted)
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.
- Specified by:
setInverted
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
setInverted
in interfaceedu.wpi.first.wpilibj.SpeedController
- Parameters:
isInverted
- True if the motor direction should be reversed
-
getInverted
public boolean getInverted()
Return the motor direction inversion state.- Specified by:
getInverted
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
getInverted
in interfaceedu.wpi.first.wpilibj.SpeedController
- Returns:
- True if the motor direction is inverted
-
disable
public void disable()
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.
- Specified by:
disable
in interfaceedu.wpi.first.wpilibj.motorcontrol.MotorController
- Specified by:
disable
in interfaceedu.wpi.first.wpilibj.SpeedController
-
identifyMotor
public void identifyMotor()
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.
-
resetPosition
public void resetPosition()
Reset the motor revolution counter (position) to 0.
-
setPosition
public void setPosition(double newPosition)
Reset the motor revolution counter (position) to the specified position.- Parameters:
newPosition
- Value to assign motor position in revolutions
-
getFirmwareVersion
public long getFirmwareVersion()
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)
-
getSerialNumber
public long getSerialNumber()
Return the serial number of the motor asscioated with this instance of the CANVenom class.- Returns:
- The Venom motor serial number
-
enable
public void enable()
Enable the motor again after a call to stopMotor() or disable().
-
getFwdLimitSwitchActive
public boolean getFwdLimitSwitchActive()
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)
-
getRevLimitSwitchActive
public boolean getRevLimitSwitchActive()
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)
-
enableLimitSwitches
public void enableLimitSwitches(boolean fwdLimitSwitchEnabled, boolean revLimitSwitchEnabled)
Enable/disable the forward and reverse limit switches.- Parameters:
fwdLimitSwitchEnabled
- Prevent forward rotation if this argument is true and the forward limit switch is activerevLimitSwitchEnabled
- Prevent reverse rotation if this argument is true and the forward limit switch is active
-
getNumAvaliableMotionProfilePoints
public int getNumAvaliableMotionProfilePoints()
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
-
getCurrentMotionProfilePoint
public int getCurrentMotionProfilePoint()
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
-
getMotionProfilePositionTarget
public double getMotionProfilePositionTarget()
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
public double getMotionProfileSpeedTarget()
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).
-
getMotionProfileIsValid
public boolean getMotionProfileIsValid()
Determine if the motor is prepared to execute a motion profileDetermins 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
-
getMotionProfileState
public CANVenom.MotionProfileState getMotionProfileState()
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.
-
clearMotionProfilePoints
public void clearMotionProfilePoints()
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.
-
addMotionProfilePoint
public void addMotionProfilePoint(double time, double speed, double position)
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 milisecondsspeed
- Commanded speed in rotations per secondposition
- Commanded motor angle/position in revolutions
-
completeMotionProfilePath
public void completeMotionProfilePath(double time, double position)
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 millisecondsposition
- Commanded motor angle/position in revolution
-
executePath
public void executePath()
Execute stored motion profile.Instruct the motor to begin following the sotred motion profile. This function is equivlelent to calling setCommand(ControlMode.MotionProfile, 0)
-
getBusVoltage
public double getBusVoltage()
Get the bus (battery) voltage supplying the Venmom motor.- Returns:
- The bus voltage in Volts
-
getOutputVoltage
public double getOutputVoltage()
Get the calculated voltage across the motor burshes.- Returns:
- The calculated motor voltage in Volts.
-
getDutyCycle
public double getDutyCycle()
Get the motor h-bridge duty cycle.- Returns:
- The motor duty cycle as a ration between -1.0 and 1.0
-
getOutputCurrent
public double getOutputCurrent()
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.
-
getTemperature
public double getTemperature()
The measured Venom backplate temperature.- Returns:
- Measured backplate temperature in degrees C.
-
getAuxVoltage
public double getAuxVoltage()
Get the measured voltage at the auxilary analog input on the limit switch breakout board.- Returns:
- Auxilary analog input voltage in Volts.
-
getSpeed
public double getSpeed()
Measured signed motor velocity in RPM.- Returns:
- Motor velocity in RPM.
-
getPosition
public double getPosition()
Signed motor revolutions (position) since the last time it was cleared.- Returns:
- The signed motor position in revolutions.
-
getPIDTarget
public double getPIDTarget()
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 input/target in RPM, rotations, or Amps (based on current control mode)
-
getKF
public double getKF()
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.
-
getB
public double getB()
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.
-
getKP
public double getKP()
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.
-
getKI
public double getKI()
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.
-
getKD
public double getKD()
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.
-
getMinPILimit
public double getMinPILimit()
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.
-
getMaxPILimit
public double getMaxPILimit()
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
public double getMaxSpeed()
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.
-
getMaxAcceleration
public double getMaxAcceleration()
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
public double getMaxJerk()
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
-
getControlMode
public CANVenom.ControlMode getControlMode()
Get the commanded Venom control mode.- Returns:
- The commanded control mode
-
getActiveControlMode
public CANVenom.ControlMode getActiveControlMode()
Get the active Venom control mode reported by the motor.- Returns:
- The active control mode
-
getBrakeCoastMode
public CANVenom.BrakeCoastMode getBrakeCoastMode()
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
-
getActiveFaults
public java.util.EnumSet<CANVenom.FaultFlag> getActiveFaults()
Return set of active motor faults which curently limit or disable motor output. More than one Fault may be active at a time- Returns:
- EnumSet of active faults
-
getLatchedFaults
public java.util.EnumSet<CANVenom.FaultFlag> getLatchedFaults()
Return set of latched motor faults which are curently active or were previously active since the last time theclearLatchedFaults()
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:
- EnumSet of latched faults
-
clearLatchedFaults
public void clearLatchedFaults()
Clear all latched faults
-
setCommand
public void setCommand(CANVenom.ControlMode mode, double command)
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)
-
setCommand
public void setCommand(CANVenom.ControlMode mode, double command, double kF, double b)
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(double, double, double)
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.0b
- Feed-forward offset as duty-cycle between -2.0 and 2.0
-
follow
public void follow(CANVenom leadVenom)
Place the motor into FollowTheLeader mode and follow the specified motorThis method is equivelent to calling setComand(FollowTheLeader, ID_of_lead_motor);
- Parameters:
leadVenom
- CANVenom object which reperesents the lead motor.
-
setPID
public void setPID(double kP, double kI, double kD, double kF, double b)
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.0kI
- Integral gain as a ratio between 0.0 and 4.0kD
- Derivative gain as a ratio between 0.0 and 4.0kF
- Feed-forward gain as a ratio between -2.0 and 2.0b
- Feed-forward offset as duty-cycle between -2.0 and 2.0
-
setKF
public void setKF(double kF)
Set Feed-forward gain in closed loop control modes.- Parameters:
kF
- Feed-forward gain as a ratio between -2.0 and 2.0
-
setB
public void setB(double b)
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.
-
setKP
public void setKP(double kP)
Set PID Proportional gain.- Parameters:
kP
- Proportional gain as a ratio between 0.0 and 4.0.
-
setKI
public void setKI(double kI)
Set PID Integral gain.- Parameters:
kI
- Integral gain as a ratio between 0.0 and 4.0.
-
setKD
public void setKD(double kD)
Set PID Derivative gain.- Parameters:
kD
- Derivative gain as a ratio between 0.0 and 4.0.
-
setMinPILimit
public void setMinPILimit(double limit)
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.
-
setMaxPILimit
public void setMaxPILimit(double limit)
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
public void setMaxSpeed(double limit)
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.
-
setMaxAcceleration
public void setMaxAcceleration(double limit)
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
public void setMaxJerk(double limit)
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.
-
setControlMode
public void setControlMode(CANVenom.ControlMode controlMode)
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
setCommand(com.playingwithfusion.CANVenom.ControlMode, double)
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.
-
setBrakeCoastMode
public void setBrakeCoastMode(CANVenom.BrakeCoastMode brakeCoastMode)
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.
-
-