Files
allwpilib/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java
Peter Johnson 5175829bab PWM: Use getRaw and setRaw for Sendable "Value" property. (#963)
Also change type to "PWM".  Move old PWM Sendable behavior for both value
and type to PWMSpeedController.
2018-03-03 21:36:25 -08:00

79 lines
2.1 KiB
Java

/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package edu.wpi.first.wpilibj;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
/**
* Common base class for all PWM Speed Controllers.
*/
public abstract class PWMSpeedController extends SafePWM implements SpeedController {
private boolean m_isInverted = false;
/**
* Constructor.
*
* @param channel The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are
* on the MXP port
*/
protected PWMSpeedController(int channel) {
super(channel);
}
/**
* Set the PWM value.
*
* <p>The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the
* FPGA.
*
* @param speed The speed value between -1.0 and 1.0 to set.
*/
@Override
public void set(double speed) {
setSpeed(m_isInverted ? -speed : speed);
feed();
}
/**
* Get the recently set value of the PWM.
*
* @return The most recently set value for the PWM between -1.0 and 1.0.
*/
@Override
public double get() {
return getSpeed();
}
@Override
public void setInverted(boolean isInverted) {
m_isInverted = isInverted;
}
@Override
public boolean getInverted() {
return m_isInverted;
}
/**
* Write out the PID value as seen in the PIDOutput base object.
*
* @param output Write out the PWM value as was found in the PIDController
*/
@Override
public void pidWrite(double output) {
set(output);
}
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Speed Controller");
builder.setSafeState(this::setDisabled);
builder.addDoubleProperty("Value", this::getSpeed, this::setSpeed);
}
}