Package edu.wpi.first.wpilibj
Class NidecBrushless
- java.lang.Object
-
- edu.wpi.first.wpilibj.MotorSafety
-
- edu.wpi.first.wpilibj.NidecBrushless
-
- All Implemented Interfaces:
PIDOutput,Sendable,SpeedController,AutoCloseable
public class NidecBrushless extends MotorSafety implements SpeedController, Sendable, AutoCloseable
Nidec Brushless Motor.
-
-
Constructor Summary
Constructors Constructor Description NidecBrushless(int pwmChannel, int dioChannel)Constructor.
-
Method Summary
All Methods Instance Methods Concrete Methods 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 speed controller is in the inverted state or not.voidinitSendable(SendableBuilder builder)Initializes thisSendableobject.voidpidWrite(double output)Write out the PID value as seen in the PIDOutput base object.voidset(double speed)Set the PWM value.voidsetInverted(boolean isInverted)Common interface for inverting direction of a speed controller.voidstopMotor()Stop the motor.-
Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj.Sendable
addChild, getName, getSubsystem, setName, setName, setName, setName, setSubsystem
-
Methods inherited from interface edu.wpi.first.wpilibj.SpeedController
setVoltage
-
-
-
-
Constructor Detail
-
NidecBrushless
public NidecBrushless(int pwmChannel, int dioChannel)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 Detail
-
close
public void close()
- Specified by:
closein interfaceAutoCloseable
-
set
public void set(double speed)
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 interfaceSpeedController- Parameters:
speed- The speed value between -1.0 and 1.0 to set.
-
get
public double get()
Get the recently set value of the PWM.- Specified by:
getin interfaceSpeedController- Returns:
- The most recently set value for the PWM between -1.0 and 1.0.
-
setInverted
public void setInverted(boolean isInverted)
Description copied from interface:SpeedControllerCommon interface for inverting direction of a speed controller.- Specified by:
setInvertedin interfaceSpeedController- Parameters:
isInverted- The state of inversion true is inverted.
-
getInverted
public boolean getInverted()
Description copied from interface:SpeedControllerCommon interface for returning if a speed controller is in the inverted state or not.- Specified by:
getInvertedin interfaceSpeedController- Returns:
- isInverted The state of the inversion true is inverted.
-
pidWrite
public void pidWrite(double output)
Write out the PID value as seen in the PIDOutput base object.
-
stopMotor
public void 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 interfaceSpeedController- Specified by:
stopMotorin classMotorSafety
-
getDescription
public String getDescription()
- Specified by:
getDescriptionin classMotorSafety
-
disable
public void disable()
Disable the motor. The enable() function must be called to re-enable the motor.- Specified by:
disablein interfaceSpeedController
-
enable
public void enable()
Re-enable the motor after disable() has been called. The set() function must be called to set a new motor speed.
-
getChannel
public int getChannel()
Gets the channel number associated with the object.- Returns:
- The channel number.
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-
-