Class NidecBrushless
java.lang.Object
edu.wpi.first.wpilibj.MotorSafety
edu.wpi.first.wpilibj.motorcontrol.NidecBrushless
- All Implemented Interfaces:
Sendable,MotorController,SpeedController,AutoCloseable
public class NidecBrushless extends MotorSafety implements MotorController, Sendable, AutoCloseable
Nidec Brushless Motor.
-
Constructor Summary
Constructors Constructor Description NidecBrushless(int pwmChannel, int dioChannel)Constructor. -
Method Summary
Modifier and Type Method Description voidclose()voiddisable()Disable the motor.voidenable()Re-enable the motor after disable() has been called.doubleget()Get the recently set value of the PWM.intgetChannel()Gets the channel number associated with the object.StringgetDescription()booleangetInverted()Common interface for returning if a motor controller is in the inverted state or not.voidinitSendable(SendableBuilder builder)Initializes thisSendableobject.voidset(double speed)Set the PWM value.voidsetInverted(boolean isInverted)Common interface for inverting direction of a motor controller.voidstopMotor()Stop the motor.Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Constructor Details
-
NidecBrushless
Constructor.- Parameters:
pwmChannel- The PWM channel that the Nidec Brushless controller is attached to. 0-9 are on-board, 10-19 are on the MXP portdioChannel- The DIO channel that the Nidec Brushless controller is attached to. 0-9 are on-board, 10-25 are on the MXP port
-
-
Method Details
-
close
- Specified by:
closein interfaceAutoCloseable
-
set
Set the PWM value.The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the FPGA.
- Specified by:
setin interfaceMotorController- Specified by:
setin interfaceSpeedController- Parameters:
speed- The speed value between -1.0 and 1.0 to set.
-
get
Get the recently set value of the PWM.- Specified by:
getin interfaceMotorController- Specified by:
getin interfaceSpeedController- Returns:
- The most recently set value for the PWM between -1.0 and 1.0.
-
setInverted
Description copied from interface:MotorControllerCommon interface for inverting direction of a motor controller.- Specified by:
setInvertedin interfaceMotorController- Specified by:
setInvertedin interfaceSpeedController- Parameters:
isInverted- The state of inversion true is inverted.
-
getInverted
Description copied from interface:MotorControllerCommon interface for returning if a motor controller is in the inverted state or not.- Specified by:
getInvertedin interfaceMotorController- Specified by:
getInvertedin interfaceSpeedController- Returns:
- isInverted The state of the inversion true is inverted.
-
stopMotor
Stop the motor. This is called by the MotorSafety object when it has a timeout for this PWM and needs to stop it from running. Calling set() will re-enable the motor.- Specified by:
stopMotorin interfaceMotorController- Specified by:
stopMotorin interfaceSpeedController- Specified by:
stopMotorin classMotorSafety
-
getDescription
- Specified by:
getDescriptionin classMotorSafety
-
disable
Disable the motor. The enable() function must be called to re-enable the motor.- Specified by:
disablein interfaceMotorController- Specified by:
disablein interfaceSpeedController
-
enable
Re-enable the motor after disable() has been called. The set() function must be called to set a new motor speed. -
getChannel
Gets the channel number associated with the object.- Returns:
- The channel number.
-
initSendable
Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-