public class CRServoImpl extends java.lang.Object implements CRServo
DcMotorSimple.Direction
HardwareDevice.Manufacturer
Modifier and Type | Field and Description |
---|---|
protected static double |
apiPowerMax |
protected static double |
apiPowerMin |
protected static double |
apiServoPositionMax |
protected static double |
apiServoPositionMin |
protected ServoController |
controller |
protected DcMotorSimple.Direction |
direction |
protected int |
portNumber |
Constructor and Description |
---|
CRServoImpl(ServoController controller,
int portNumber)
Constructor
|
CRServoImpl(ServoController controller,
int portNumber,
DcMotorSimple.Direction direction)
Constructor
|
Modifier and Type | Method and Description |
---|---|
void |
close()
Closes this device
|
java.lang.String |
getConnectionInfo()
Get connection information about this device in a human readable format
|
ServoController |
getController()
Returns the underlying servo controller on which this servo is situated.
|
java.lang.String |
getDeviceName()
Returns a string suitable for display to the user as to the type of device.
|
DcMotorSimple.Direction |
getDirection()
Returns the current logical direction in which this motor is set as operating.
|
HardwareDevice.Manufacturer |
getManufacturer()
Returns an indication of the manufacturer of this device.
|
int |
getPortNumber()
Returns the port number on the underlying servo controller on which this motor is situated.
|
double |
getPower()
Returns the current configured power level of the motor.
|
int |
getVersion()
Version
|
void |
resetDeviceConfigurationForOpMode()
Resets the device's configuration to that which is expected at the beginning of an OpMode.
|
void |
setDirection(DcMotorSimple.Direction direction)
Sets the logical direction in which this motor operates.
|
void |
setPower(double power)
Sets the power level of the motor, expressed as a fraction of the maximum
possible power / speed supported according to the run mode in which the
motor is operating.
|
protected ServoController controller
protected int portNumber
protected DcMotorSimple.Direction direction
protected static final double apiPowerMin
protected static final double apiPowerMax
protected static final double apiServoPositionMin
protected static final double apiServoPositionMax
public CRServoImpl(ServoController controller, int portNumber)
controller
- Servo controller that this servo is attached toportNumber
- physical port number on the servo controllerpublic CRServoImpl(ServoController controller, int portNumber, DcMotorSimple.Direction direction)
controller
- Servo controller that this servo is attached toportNumber
- physical port number on the servo controllerdirection
- FORWARD for normal operation, REVERSE to reverse operationpublic HardwareDevice.Manufacturer getManufacturer()
HardwareDevice
getManufacturer
in interface HardwareDevice
public java.lang.String getDeviceName()
HardwareDevice
getDeviceName
in interface HardwareDevice
public java.lang.String getConnectionInfo()
HardwareDevice
getConnectionInfo
in interface HardwareDevice
public int getVersion()
HardwareDevice
getVersion
in interface HardwareDevice
public void resetDeviceConfigurationForOpMode()
HardwareDevice
resetDeviceConfigurationForOpMode
in interface HardwareDevice
public void close()
HardwareDevice
close
in interface HardwareDevice
public ServoController getController()
CRServo
getController
in interface CRServo
CRServo.getPortNumber()
public int getPortNumber()
CRServo
getPortNumber
in interface CRServo
CRServo.getController()
public void setDirection(DcMotorSimple.Direction direction)
DcMotorSimple
setDirection
in interface DcMotorSimple
direction
- the direction to set for this motorDcMotorSimple.getDirection()
public DcMotorSimple.Direction getDirection()
DcMotorSimple
getDirection
in interface DcMotorSimple
DcMotorSimple.setDirection(Direction)
public void setPower(double power)
DcMotorSimple
Setting a power level of zero will brake the motor
setPower
in interface DcMotorSimple
power
- the new power level of the motor, a value in the interval [-1.0, 1.0]DcMotorSimple.getPower()
,
DcMotor.setMode(DcMotor.RunMode)
,
DcMotor.setPowerFloat()
public double getPower()
DcMotorSimple
getPower
in interface DcMotorSimple
DcMotorSimple.setPower(double)