libPlayingWithFusion 2022.01.12
Playing With Fusion driver library for FRC roboRIO
|
#include <CANVenom.h>
Public Types | |
enum | ControlMode { kDisabled = 0 , kProportional = 1 , kCurrentControl = 3 , kSpeedControl = 4 , kPositionControl = 5 , kMotionProfile = 6 , kFollowTheLeader = 7 , kVoltageControl = 8 } |
enum | BrakeCoastMode { kCoast = 0 , kBrake = 1 } |
enum | FaultFlag { kNone = 0 , kNoHeartbeat = 1 , kNoLeaderHeartbeat = 2 , kBadLeaderID = 4 , kHighTemperature = 8 , kHighCurrent = 16 , kBadMode = 32 , kDuplicateID = 64 , kForwardLimit = 128 , kReverseLimit = 256 , kReset = 512 } |
enum | MotionProfileState { kInit = 0 , kRunning = 1 , kErrBufferCleared = 2 , kErrBufferUnderflow = 3 , kErrBufferInvalid = 4 , kDone = 5 } |
Public Member Functions | |
CANVenom (uint8_t motorID) | |
virtual | ~CANVenom () |
CANVenom (const CANVenom &)=delete | |
CANVenom & | operator= (const CANVenom &)=delete |
CANVenom (CANVenom &&)=default | |
CANVenom & | operator= (CANVenom &&)=default |
virtual void | StopMotor () override |
virtual std::string | GetDescription () const override |
virtual void | Set (double command) override |
virtual double | Get () const override |
virtual void | SetInverted (bool isInverted) override |
virtual bool | GetInverted () const override |
virtual void | Disable () override |
void | Enable () |
virtual void | PIDWrite (double output) |
virtual void | InitSendable (wpi::SendableBuilder &builder) override |
void | SetCommand (ControlMode mode, double command) |
void | SetCommand (ControlMode mode, double command, double kF, double b) |
void | Follow (CANVenom &leadVenom) |
bool | GetFwdLimitSwitchActive () const |
bool | GetRevLimitSwitchActive () const |
void | EnableLimitSwitches (bool fwdLimitSwitchEnabled, bool revLimitSwitchEnabled) |
void | IdentifyMotor () |
void | ResetPosition () |
void | SetPosition (double newPosition) |
uint16_t | GetNumAvaliableMotionProfilePoints () const |
uint16_t | GetCurrentMotionProfilePoint () const |
double | GetMotionProfilePositionTarget () const |
double | GetMotionProfileSpeedTarget () const |
bool | GetMotionProfileIsValid () const |
MotionProfileState | GetMotionProfileState () const |
void | ClearMotionProfilePoints () |
void | AddMotionProfilePoint (double time, double speed, double position) |
void | CompleteMotionProfilePath (double time, double position) |
void | ExecutePath () |
uint32_t | GetFirmwareVersion () const |
uint32_t | GetSerialNumber () const |
double | GetBusVoltage () const |
double | GetOutputVoltage () const |
double | GetDutyCycle () const |
double | GetOutputCurrent () const |
double | GetTemperature () const |
double | GetAuxVoltage () const |
double | GetSpeed () const |
double | GetPosition () const |
double | GetPIDTarget () const |
double | GetKF () const |
double | GetB () const |
double | GetKP () const |
double | GetKI () const |
double | GetKD () const |
double | GetMinPILimit () const |
double | GetMaxPILimit () const |
double | GetMaxSpeed () const |
double | GetMaxAcceleration () const |
double | GetMaxJerk () const |
ControlMode | GetControlMode () const |
ControlMode | GetActiveControlMode () const |
BrakeCoastMode | GetBrakeCoastMode () const |
FaultFlag | GetActiveFaults () const |
FaultFlag | GetLatchedFaults () const |
void | ClearLatchedFaults () |
void | SetPID (double kP, double kI, double kD, double kF, double b) |
void | SetKF (double kF) |
void | SetB (double b) |
void | SetKP (double kP) |
void | SetKI (double kI) |
void | SetKD (double kD) |
void | SetMinPILimit (double limit) |
void | SetMaxPILimit (double limit) |
void | SetMaxSpeed (double limit) |
void | SetMaxAcceleration (double limit) |
void | SetMaxJerk (double limit) |
void | SetControlMode (ControlMode controlMode) |
void | SetBrakeCoastMode (BrakeCoastMode brakeCoastMode) |
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
Enumerator | |
---|---|
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 ClearLatchedFaults function was called |
Enumerator | |
---|---|
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 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 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 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 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. |
|
explicit |
Create an instance of the CAN Venom Motor Controller driver.
This is designed to support the Playing With Fusion Venom motor controller
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. |
|
virtual |
Destroy the CANVenom object and free any asscioated resources.
|
delete |
|
default |
void CANVenom::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
time | Time since the start of the profile in miliseconds |
speed | Commanded speed in rotations per second |
position | Commanded motor angle/position in revolutions |
void CANVenom::ClearLatchedFaults | ( | ) |
Clear all latched faults
void CANVenom::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.
void CANVenom::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.
time | Time since the start of the profile in milliseconds |
position | Commanded motor angle/position in revolution |
|
overridevirtual |
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.
void CANVenom::Enable | ( | ) |
Enable the motor again after a call to stopMotor() or disable().
void CANVenom::EnableLimitSwitches | ( | bool | fwdLimitSwitchEnabled, |
bool | revLimitSwitchEnabled | ||
) |
Enable/disable the forward and reverse limit switches.
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 |
void CANVenom::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)
void CANVenom::Follow | ( | CANVenom & | leadVenom | ) |
Place the motor into FollowTheLeader mode and follow the specified motor
This method is equivelent to calling SetComand(FollowTheLeader, ID_of_lead_motor);
leadVenom | Reference to the CANVenom instance which reperesents the lead motor. |
|
overridevirtual |
Get the motor duty-cycle.
CANVenom::ControlMode CANVenom::GetActiveControlMode | ( | ) | const |
Get the active Venom control mode.
CANVenom::FaultFlag CANVenom::GetActiveFaults | ( | ) | const |
Return set of active motor faults which curently limit or disable motor output. More than one Fault may be active at a time
double CANVenom::GetAuxVoltage | ( | ) | const |
Get the measured voltage at the auxilary analog input on the limit switch breakout board.
double CANVenom::GetB | ( | ) | const |
Get the feed-forward command offset in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
CANVenom::BrakeCoastMode CANVenom::GetBrakeCoastMode | ( | ) | const |
Get the brake/coast behavior when zero is commanded in Proportional and VoltageControl control modes.
double CANVenom::GetBusVoltage | ( | ) | const |
Get the bus (battery) voltage supplying the Venmom motor.
CANVenom::ControlMode CANVenom::GetControlMode | ( | ) | const |
Get the commanded Venom control mode.
uint16_t CANVenom::GetCurrentMotionProfilePoint | ( | ) | const |
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.
|
overridevirtual |
Return a description of this motor controller.
double CANVenom::GetDutyCycle | ( | ) | const |
Get the motor h-bridge duty cycle.
uint32_t CANVenom::GetFirmwareVersion | ( | ) | const |
Return the Venom motor firmware version of the motor asscioated with this instance of the CANVenom class.
bool CANVenom::GetFwdLimitSwitchActive | ( | ) | const |
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.
|
overridevirtual |
Return the motor direction inversion state.
double CANVenom::GetKD | ( | ) | const |
Get the close-loop PID derative gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
double CANVenom::GetKF | ( | ) | const |
Get the feed-forward gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
double CANVenom::GetKI | ( | ) | const |
Get the close-loop PID integral gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
double CANVenom::GetKP | ( | ) | const |
Get the close-loop PID proportional gain in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
CANVenom::FaultFlag CANVenom::GetLatchedFaults | ( | ) | const |
Return set of latched motor faults which are curently active or were previously active since the last time the 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.
double CANVenom::GetMaxAcceleration | ( | ) | const |
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.
double CANVenom::GetMaxJerk | ( | ) | const |
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..
double CANVenom::GetMaxPILimit | ( | ) | const |
Get the maximum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
double CANVenom::GetMaxSpeed | ( | ) | const |
Get the maximum speed (absolute value of velocity) that may be commanded in the SpeedControl and PositionControl control modes.
double CANVenom::GetMinPILimit | ( | ) | const |
Get the minimum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
bool CANVenom::GetMotionProfileIsValid | ( | ) | const |
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.
double CANVenom::GetMotionProfilePositionTarget | ( | ) | const |
Get the instantaneous motion profile position commanded
Gets the motor position commanded by the current motion profile point while a motion profile is active
double CANVenom::GetMotionProfileSpeedTarget | ( | ) | const |
Get the instantaneous motion profile speed commanded
Gets the motor speed commanded by the current motion profile point while a motion profile is active
CANVenom::MotionProfileState CANVenom::GetMotionProfileState | ( | ) | const |
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.
uint16_t CANVenom::GetNumAvaliableMotionProfilePoints | ( | ) | const |
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.
double CANVenom::GetOutputCurrent | ( | ) | const |
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.
double CANVenom::GetOutputVoltage | ( | ) | const |
Get the calculated voltage across the motor burshes.
double CANVenom::GetPIDTarget | ( | ) | const |
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
double CANVenom::GetPosition | ( | ) | const |
Signed motor revolutions (position) since the last time it was cleared.
bool CANVenom::GetRevLimitSwitchActive | ( | ) | const |
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.
uint32_t CANVenom::GetSerialNumber | ( | ) | const |
Return the serial number of the motor asscioated with this instance of the CANVenom class.
double CANVenom::GetSpeed | ( | ) | const |
Measured signed motor velocity in RPM.
double CANVenom::GetTemperature | ( | ) | const |
The measured Venom backplate temperature.
void CANVenom::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.
|
overridevirtual |
Initialize vaiiables and parameters to be passed into the smart dashboard.
|
virtual |
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.
speed | Proportional motor command from -1.0 to 1.0 |
void CANVenom::ResetPosition | ( | ) |
Reset the motor revolution counter (position) to 0.
|
overridevirtual |
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.
speed | Proportional motor duty-cycle command from -1.0 to 1.0 |
void CANVenom::SetB | ( | double | b | ) |
Set Feed-forward duty cycle offset in closed loop control modes.
b | Feed-forward offset as duty-cycle between -2.0 and 2.0. |
void CANVenom::SetBrakeCoastMode | ( | CANVenom::BrakeCoastMode | brakeCoastMode | ) |
Set the brake/coast behavior when zero is commanded in Proportional and VoltageControl control modes.
brakeCoastMode | The Brake or Coast behavior in Proportional and VoltageControl modes. |
void CANVenom::SetCommand | ( | ControlMode | mode, |
double | command | ||
) |
Set the motor command and control mode.
Where control mode is one of:
mode | Motor control mode (Proportional, CurrentControl, SpeedControl, etc.) |
command | Motor command (%, Amps, RPM, etc) |
void CANVenom::SetCommand | ( | ControlMode | mode, |
double | command, | ||
double | kF, | ||
double | b | ||
) |
Set the motor command and control mode.
Where control mode is one of:
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.
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 |
void CANVenom::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 function. Using setCommand() guarentees the control mode and the motor command will be received by the Venom controller at the same time.
controlMode | The commanded control mode. |
|
overridevirtual |
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.
isInverted | True if the motor direction should be reversed |
void CANVenom::SetKD | ( | double | kD | ) |
Set PID Derivative gain.
kD | Derivative gain as a ratio between 0.0 and 4.0. |
void CANVenom::SetKF | ( | double | kF | ) |
Set Feed-forward gain in closed loop control modes.
kF | Feed-forward gain as a ratio between -2.0 and 2.0 |
void CANVenom::SetKI | ( | double | kI | ) |
Set PID Integral gain.
kI | Integral gain as a ratio between 0.0 and 4.0. |
void CANVenom::SetKP | ( | double | kP | ) |
Set PID Proportional gain.
kP | Proportional gain as a ratio between 0.0 and 4.0. |
void CANVenom::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
limit | Maximum acceleration between 0 and 25,500 RPM per second |
void CANVenom::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
limit | Maximum jerk between 0 and 159,375 RPM per second squared. |
void CANVenom::SetMaxPILimit | ( | double | limit | ) |
Set the maximum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
limit | Maximum PID output duty-cycle as a ratio between -1.0 and 1.0. |
void CANVenom::SetMaxSpeed | ( | double | limit | ) |
Set the maximum speed (absolute value of velocity) that may be commanded in the SpeedControl and PositionControl control modes.
limit | Maximum speed command between 0 and 6000 RPM. |
void CANVenom::SetMinPILimit | ( | double | limit | ) |
Set the minimum duty cycle that may be commanded by the PID in SpeedControl, PositionControl, CurrentCurrent and MotionProfile control modes.
limit | Minimum PID output duty-cycle as a ratio between -1.0 and 1.0. |
void CANVenom::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
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 |
void CANVenom::SetPosition | ( | double | newPosition | ) |
Reset the motor revolution counter (position) to the specified position.
newPosition | Value to assign motor position in revolutions |
|
overridevirtual |
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.