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
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
close()
void
disable()
Disable the motor.void
enable()
Re-enable the motor after disable() has been called.double
get()
Get the recently set value of the PWM.int
getChannel()
Gets the channel number associated with the object.String
getDescription()
boolean
getInverted()
Common interface for returning if a motor controller is in the inverted state or not.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
set(double speed)
Set the PWM value.void
setInverted(boolean isInverted)
Common interface for inverting direction of a motor controller.void
stopMotor()
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.motorcontrol.MotorController
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:
close
in 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:
set
in interfaceMotorController
- Specified by:
set
in 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:
get
in interfaceMotorController
- Specified by:
get
in 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:MotorController
Common interface for inverting direction of a motor controller.- Specified by:
setInverted
in interfaceMotorController
- Specified by:
setInverted
in interfaceSpeedController
- Parameters:
isInverted
- The state of inversion true is inverted.
-
getInverted
public boolean getInverted()
Description copied from interface:MotorController
Common interface for returning if a motor controller is in the inverted state or not.- Specified by:
getInverted
in interfaceMotorController
- Specified by:
getInverted
in interfaceSpeedController
- Returns:
- isInverted The state of the inversion true is inverted.
-
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:
stopMotor
in interfaceMotorController
- Specified by:
stopMotor
in interfaceSpeedController
- Specified by:
stopMotor
in classMotorSafety
-
getDescription
public String getDescription()
- Specified by:
getDescription
in classMotorSafety
-
disable
public void disable()
Disable the motor. The enable() function must be called to re-enable the motor.- Specified by:
disable
in interfaceMotorController
- Specified by:
disable
in 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:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-
-