diff --git a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp index ee96a5f89f..03cce88ef4 100644 --- a/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp @@ -136,6 +136,7 @@ bool DoubleSolenoid::IsRevSolenoidBlackListed() const { void DoubleSolenoid::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Double Solenoid"); + builder.SetActuator(true); builder.SetSafeState([=]() { Set(kOff); }); builder.AddSmallStringProperty( "Value", diff --git a/wpilibc/src/main/native/cpp/NidecBrushless.cpp b/wpilibc/src/main/native/cpp/NidecBrushless.cpp index 6117ded2c2..8f95fdd3af 100644 --- a/wpilibc/src/main/native/cpp/NidecBrushless.cpp +++ b/wpilibc/src/main/native/cpp/NidecBrushless.cpp @@ -84,6 +84,7 @@ int NidecBrushless::GetChannel() const { return m_pwm.GetChannel(); } void NidecBrushless::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Nidec Brushless"); + builder.SetActuator(true); builder.SetSafeState([=]() { StopMotor(); }); builder.AddDoubleProperty("Value", [=]() { return Get(); }, [=](double value) { Set(value); }); diff --git a/wpilibc/src/main/native/cpp/PWM.cpp b/wpilibc/src/main/native/cpp/PWM.cpp index a9a4abe67f..f87dcfdf4d 100644 --- a/wpilibc/src/main/native/cpp/PWM.cpp +++ b/wpilibc/src/main/native/cpp/PWM.cpp @@ -184,6 +184,7 @@ int PWM::GetChannel() const { return m_channel; } void PWM::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("PWM"); + builder.SetActuator(true); builder.SetSafeState([=]() { SetDisabled(); }); builder.AddDoubleProperty("Value", [=]() { return GetRaw(); }, [=](double value) { SetRaw(value); }); diff --git a/wpilibc/src/main/native/cpp/PWMSpeedController.cpp b/wpilibc/src/main/native/cpp/PWMSpeedController.cpp index bd3cf148b1..19263e37e0 100644 --- a/wpilibc/src/main/native/cpp/PWMSpeedController.cpp +++ b/wpilibc/src/main/native/cpp/PWMSpeedController.cpp @@ -33,6 +33,7 @@ PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {} void PWMSpeedController::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Speed Controller"); + builder.SetActuator(true); builder.SetSafeState([=]() { SetDisabled(); }); builder.AddDoubleProperty("Value", [=]() { return GetSpeed(); }, [=](double value) { SetSpeed(value); }); diff --git a/wpilibc/src/main/native/cpp/Relay.cpp b/wpilibc/src/main/native/cpp/Relay.cpp index 8252430ce9..b2c3f5bd7c 100644 --- a/wpilibc/src/main/native/cpp/Relay.cpp +++ b/wpilibc/src/main/native/cpp/Relay.cpp @@ -201,6 +201,7 @@ void Relay::GetDescription(wpi::raw_ostream& desc) const { void Relay::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Relay"); + builder.SetActuator(true); builder.SetSafeState([=]() { Set(kOff); }); builder.AddSmallStringProperty( "Value", diff --git a/wpilibc/src/main/native/cpp/Solenoid.cpp b/wpilibc/src/main/native/cpp/Solenoid.cpp index 7b5ebf4e4b..a53e2c2fc8 100644 --- a/wpilibc/src/main/native/cpp/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/Solenoid.cpp @@ -87,6 +87,7 @@ void Solenoid::StartPulse() { void Solenoid::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Solenoid"); + builder.SetActuator(true); builder.SetSafeState([=]() { Set(false); }); builder.AddBooleanProperty("Value", [=]() { return Get(); }, [=](bool value) { Set(value); }); diff --git a/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp b/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp index 5b3521bc44..a807afcf33 100644 --- a/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp +++ b/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp @@ -46,6 +46,7 @@ void SpeedControllerGroup::PIDWrite(double output) { Set(output); } void SpeedControllerGroup::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("Speed Controller"); + builder.SetActuator(true); builder.SetSafeState([=]() { StopMotor(); }); builder.AddDoubleProperty("Value", [=]() { return Get(); }, [=](double value) { Set(value); }); diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index 8ce060efd3..33b75c6a5d 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -211,6 +211,8 @@ void DifferentialDrive::GetDescription(wpi::raw_ostream& desc) const { void DifferentialDrive::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("DifferentialDrive"); + builder.SetActuator(true); + builder.SetSafeState([=] { StopMotor(); }); builder.AddDoubleProperty("Left Motor Speed", [=]() { return m_leftMotor.Get(); }, [=](double value) { m_leftMotor.Set(value); }); diff --git a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp index 48ae9f2fc2..680796efca 100644 --- a/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp @@ -101,6 +101,8 @@ void KilloughDrive::GetDescription(wpi::raw_ostream& desc) const { void KilloughDrive::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("KilloughDrive"); + builder.SetActuator(true); + builder.SetSafeState([=] { StopMotor(); }); builder.AddDoubleProperty("Left Motor Speed", [=]() { return m_leftMotor.Get(); }, [=](double value) { m_leftMotor.Set(value); }); diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index 4792416d9f..b18238e976 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -107,6 +107,8 @@ void MecanumDrive::GetDescription(wpi::raw_ostream& desc) const { void MecanumDrive::InitSendable(SendableBuilder& builder) { builder.SetSmartDashboardType("MecanumDrive"); + builder.SetActuator(true); + builder.SetSafeState([=] { StopMotor(); }); builder.AddDoubleProperty("Front Left Motor Speed", [=]() { return m_frontLeftMotor.Get(); }, [=](double value) { m_frontLeftMotor.Set(value); }); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp index fb30724fa4..5eb9d6285b 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp @@ -21,6 +21,8 @@ std::shared_ptr SendableBuilderImpl::GetTable() { return m_table; } +bool SendableBuilderImpl::IsActuator() const { return m_actuator; } + void SendableBuilderImpl::UpdateTable() { uint64_t time = nt::Now(); for (auto& property : m_properties) { @@ -53,6 +55,11 @@ void SendableBuilderImpl::SetSmartDashboardType(const wpi::Twine& type) { m_table->GetEntry(".type").SetString(type); } +void SendableBuilderImpl::SetActuator(bool value) { + m_table->GetEntry(".actuator").SetBoolean(value); + m_actuator = value; +} + void SendableBuilderImpl::SetSafeState(std::function func) { m_safeState = func; } diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h index c0821c15fa..3f5f8928fe 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h @@ -32,6 +32,14 @@ class SendableBuilder { */ virtual void SetSmartDashboardType(const wpi::Twine& type) = 0; + /** + * Set a flag indicating if this sendable should be treated as an actuator. + * By default this flag is false. + * + * @param value true if actuator, false if not + */ + virtual void SetActuator(bool value) = 0; + /** * Set the function that should be called to set the Sendable into a safe * state. This is called when entering and exiting Live Window mode. diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h index a10098a244..b246b6ae48 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h @@ -46,6 +46,12 @@ class SendableBuilderImpl : public SendableBuilder { */ std::shared_ptr GetTable(); + /** + * Return whether this sendable should be treated as an actuator. + * @return True if actuator, false if not. + */ + bool IsActuator() const; + /** * Update the network table values by calling the getters for all properties. */ @@ -74,6 +80,7 @@ class SendableBuilderImpl : public SendableBuilder { void StopLiveWindowMode(); void SetSmartDashboardType(const wpi::Twine& type) override; + void SetActuator(bool value) override; void SetSafeState(std::function func) override; void SetUpdateTable(std::function func) override; nt::NetworkTableEntry GetEntry(const wpi::Twine& key) override; @@ -188,6 +195,7 @@ class SendableBuilderImpl : public SendableBuilder { std::function m_updateTable; std::shared_ptr m_table; nt::NetworkTableEntry m_controllableEntry; + bool m_actuator = false; }; } // namespace frc diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java index 842ffc8f7f..691bc66df2 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java @@ -166,6 +166,7 @@ public class DoubleSolenoid extends SolenoidBase { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Double Solenoid"); + builder.setActuator(true); builder.setSafeState(() -> set(Value.kOff)); builder.addStringProperty("Value", () -> get().name().substring(1), value -> { if ("Forward".equals(value)) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java index 98e2ddeb49..f27a22e918 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java @@ -196,6 +196,7 @@ public class NidecBrushless extends SendableBase implements SpeedController, Mot @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Nidec Brushless"); + builder.setActuator(true); builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Value", this::get, this::set); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java index cdc016d796..91ce4af4d5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java @@ -242,6 +242,7 @@ public class PWM extends SendableBase { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("PWM"); + builder.setActuator(true); builder.setSafeState(this::setDisabled); builder.addDoubleProperty("Value", this::getRaw, value -> setRaw((int) value)); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java index d0c5777c0c..3a52987bf9 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java @@ -77,6 +77,7 @@ public abstract class PWMSpeedController extends SafePWM implements SpeedControl @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Speed Controller"); + builder.setActuator(true); builder.setSafeState(this::setDisabled); builder.addDoubleProperty("Value", this::getSpeed, this::setSpeed); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java index c8dfff1746..ca849bc75a 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java @@ -334,6 +334,7 @@ public class Relay extends SendableBase implements MotorSafety { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Relay"); + builder.setActuator(true); builder.setSafeState(() -> set(Value.kOff)); builder.addStringProperty("Value", () -> get().getPrettyValue(), value -> set(Value.getValueOf(value).orElse(Value.kOff))); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java index bacd3a25c6..fd886c6e09 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java @@ -115,6 +115,7 @@ public class Solenoid extends SolenoidBase { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Solenoid"); + builder.setActuator(true); builder.setSafeState(() -> set(false)); builder.addBooleanProperty("Value", this::get, this::set); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java index 774761363e..9158bb3fff 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java @@ -83,6 +83,7 @@ public class SpeedControllerGroup extends SendableBase implements SpeedControlle @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("Speed Controller"); + builder.setActuator(true); builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Value", this::get, this::set); } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java index bc832859a4..a9589ea8e0 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java @@ -390,6 +390,8 @@ public class DifferentialDrive extends RobotDriveBase { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("DifferentialDrive"); + builder.setActuator(true); + builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Left Motor Speed", m_leftMotor::get, m_leftMotor::set); builder.addDoubleProperty( "Right Motor Speed", diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java index 0438b6e8aa..876aef1585 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java @@ -204,6 +204,8 @@ public class KilloughDrive extends RobotDriveBase { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("KilloughDrive"); + builder.setActuator(true); + builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Left Motor Speed", m_leftMotor::get, m_leftMotor::set); builder.addDoubleProperty("Right Motor Speed", m_rightMotor::get, m_rightMotor::set); builder.addDoubleProperty("Back Motor Speed", m_backMotor::get, m_backMotor::set); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java index b897e39529..7cdc31978c 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java @@ -208,6 +208,8 @@ public class MecanumDrive extends RobotDriveBase { @Override public void initSendable(SendableBuilder builder) { builder.setSmartDashboardType("MecanumDrive"); + builder.setActuator(true); + builder.setSafeState(this::stopMotor); builder.addDoubleProperty("Front Left Motor Speed", m_frontLeftMotor::get, m_frontLeftMotor::set); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java index d143082dc7..35a8b54449 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java @@ -25,6 +25,14 @@ public interface SendableBuilder { */ void setSmartDashboardType(String type); + /** + * Set a flag indicating if this sendable should be treated as an actuator. + * By default this flag is false. + * + * @param value true if actuator, false if not + */ + void setActuator(boolean value); + /** * Set the function that should be called to set the Sendable into a safe * state. This is called when entering and exiting Live Window mode. diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java index 44445de099..13986f5726 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java @@ -58,6 +58,7 @@ public class SendableBuilderImpl implements SendableBuilder { private Runnable m_updateTable; private NetworkTable m_table; private NetworkTableEntry m_controllableEntry; + private boolean m_actuator; /** * Set the network table. Must be called prior to any Add* functions being @@ -77,6 +78,14 @@ public class SendableBuilderImpl implements SendableBuilder { return m_table; } + /** + * Return whether this sendable should be treated as an actuator. + * @return True if actuator, false if not. + */ + public boolean isActuator() { + return m_actuator; + } + /** * Update the network table values by calling the getters for all properties. */ @@ -144,6 +153,18 @@ public class SendableBuilderImpl implements SendableBuilder { m_table.getEntry(".type").setString(type); } + /** + * Set a flag indicating if this sendable should be treated as an actuator. + * By default this flag is false. + * + * @param value true if actuator, false if not + */ + @Override + public void setActuator(boolean value) { + m_table.getEntry(".actuator").setBoolean(value); + m_actuator = value; + } + /** * Set the function that should be called to set the Sendable into a safe * state. This is called when entering and exiting Live Window mode.