mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Remove MotorSafetyHelper, create MotorSafety base class instead (#562)
Most of the MotorSafety implementation was moved into the MotorSafety base class. SafePWM's inheritance of MotorSafety was moved into PWM to eliminate Java needing a helper class. In Java, a helper class for Sendable (SendableImpl) was added due to lack of multiple inheritance.
This commit is contained in:
committed by
Peter Johnson
parent
df347e3d80
commit
acb786a791
@@ -19,7 +19,7 @@
|
||||
#include <wpi/StringRef.h>
|
||||
|
||||
#include "frc/AnalogInput.h"
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/Timer.h"
|
||||
#include "frc/Utility.h"
|
||||
#include "frc/WPIErrors.h"
|
||||
@@ -557,7 +557,7 @@ void DriverStation::Run() {
|
||||
if (IsDisabled()) safetyCounter = 0;
|
||||
|
||||
if (++safetyCounter >= 4) {
|
||||
MotorSafetyHelper::CheckMotors();
|
||||
MotorSafety::CheckMotors();
|
||||
safetyCounter = 0;
|
||||
}
|
||||
if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
|
||||
|
||||
@@ -5,58 +5,80 @@
|
||||
/* the project. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
|
||||
#include <algorithm>
|
||||
#include <utility>
|
||||
|
||||
#include <wpi/SmallPtrSet.h>
|
||||
#include <wpi/SmallString.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "frc/DriverStation.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/Timer.h"
|
||||
#include "frc/WPIErrors.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
static wpi::SmallPtrSet<MotorSafetyHelper*, 32> helperList;
|
||||
static wpi::SmallPtrSet<MotorSafety*, 32> instanceList;
|
||||
static wpi::mutex listMutex;
|
||||
|
||||
MotorSafetyHelper::MotorSafetyHelper(MotorSafety* safeObject)
|
||||
: m_safeObject(safeObject) {
|
||||
m_enabled = false;
|
||||
m_expiration = DEFAULT_SAFETY_EXPIRATION;
|
||||
m_stopTime = Timer::GetFPGATimestamp();
|
||||
|
||||
MotorSafety::MotorSafety() {
|
||||
std::lock_guard<wpi::mutex> lock(listMutex);
|
||||
helperList.insert(this);
|
||||
instanceList.insert(this);
|
||||
}
|
||||
|
||||
MotorSafetyHelper::~MotorSafetyHelper() {
|
||||
MotorSafety::~MotorSafety() {
|
||||
std::lock_guard<wpi::mutex> lock(listMutex);
|
||||
helperList.erase(this);
|
||||
instanceList.erase(this);
|
||||
}
|
||||
|
||||
void MotorSafetyHelper::Feed() {
|
||||
MotorSafety::MotorSafety(MotorSafety&& rhs)
|
||||
: ErrorBase(std::move(rhs)),
|
||||
m_expiration(std::move(rhs.m_expiration)),
|
||||
m_enabled(std::move(rhs.m_enabled)),
|
||||
m_stopTime(std::move(rhs.m_stopTime)) {}
|
||||
|
||||
MotorSafety& MotorSafety::operator=(MotorSafety&& rhs) {
|
||||
ErrorBase::operator=(std::move(rhs));
|
||||
|
||||
m_expiration = std::move(rhs.m_expiration);
|
||||
m_enabled = std::move(rhs.m_enabled);
|
||||
m_stopTime = std::move(rhs.m_stopTime);
|
||||
|
||||
return *this;
|
||||
}
|
||||
|
||||
void MotorSafety::Feed() {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
|
||||
}
|
||||
|
||||
void MotorSafetyHelper::SetExpiration(double expirationTime) {
|
||||
void MotorSafety::SetExpiration(double expirationTime) {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
m_expiration = expirationTime;
|
||||
}
|
||||
|
||||
double MotorSafetyHelper::GetExpiration() const {
|
||||
double MotorSafety::GetExpiration() const {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
return m_expiration;
|
||||
}
|
||||
|
||||
bool MotorSafetyHelper::IsAlive() const {
|
||||
bool MotorSafety::IsAlive() const {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
|
||||
}
|
||||
|
||||
void MotorSafetyHelper::Check() {
|
||||
void MotorSafety::SetSafetyEnabled(bool enabled) {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
m_enabled = enabled;
|
||||
}
|
||||
|
||||
bool MotorSafety::IsSafetyEnabled() const {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
return m_enabled;
|
||||
}
|
||||
|
||||
void MotorSafety::Check() {
|
||||
bool enabled;
|
||||
double stopTime;
|
||||
|
||||
@@ -67,31 +89,24 @@ void MotorSafetyHelper::Check() {
|
||||
}
|
||||
|
||||
DriverStation& ds = DriverStation::GetInstance();
|
||||
if (!enabled || ds.IsDisabled() || ds.IsTest()) return;
|
||||
if (!enabled || ds.IsDisabled() || ds.IsTest()) {
|
||||
return;
|
||||
}
|
||||
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
if (stopTime < Timer::GetFPGATimestamp()) {
|
||||
wpi::SmallString<128> buf;
|
||||
wpi::raw_svector_ostream desc(buf);
|
||||
m_safeObject->GetDescription(desc);
|
||||
GetDescription(desc);
|
||||
desc << "... Output not updated often enough.";
|
||||
wpi_setWPIErrorWithContext(Timeout, desc.str());
|
||||
m_safeObject->StopMotor();
|
||||
StopMotor();
|
||||
}
|
||||
}
|
||||
|
||||
void MotorSafetyHelper::SetSafetyEnabled(bool enabled) {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
m_enabled = enabled;
|
||||
}
|
||||
|
||||
bool MotorSafetyHelper::IsSafetyEnabled() const {
|
||||
std::lock_guard<wpi::mutex> lock(m_thisMutex);
|
||||
return m_enabled;
|
||||
}
|
||||
|
||||
void MotorSafetyHelper::CheckMotors() {
|
||||
void MotorSafety::CheckMotors() {
|
||||
std::lock_guard<wpi::mutex> lock(listMutex);
|
||||
for (auto elem : helperList) {
|
||||
for (auto elem : instanceList) {
|
||||
elem->Check();
|
||||
}
|
||||
}
|
||||
@@ -14,11 +14,11 @@
|
||||
using namespace frc;
|
||||
|
||||
NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
|
||||
: m_safetyHelper(this), m_dio(dioChannel), m_pwm(pwmChannel) {
|
||||
: m_dio(dioChannel), m_pwm(pwmChannel) {
|
||||
AddChild(&m_dio);
|
||||
AddChild(&m_pwm);
|
||||
m_safetyHelper.SetExpiration(0.0);
|
||||
m_safetyHelper.SetSafetyEnabled(false);
|
||||
SetExpiration(0.0);
|
||||
SetSafetyEnabled(false);
|
||||
|
||||
// the dio controls the output (in PWM mode)
|
||||
m_dio.SetPWMRate(15625);
|
||||
@@ -34,7 +34,7 @@ void NidecBrushless::Set(double speed) {
|
||||
m_dio.UpdateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
|
||||
m_pwm.SetRaw(0xffff);
|
||||
}
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
double NidecBrushless::Get() const { return m_speed; }
|
||||
@@ -49,31 +49,13 @@ void NidecBrushless::Disable() {
|
||||
m_pwm.SetDisabled();
|
||||
}
|
||||
|
||||
void NidecBrushless::StopMotor() {
|
||||
m_dio.UpdateDutyCycle(0.5);
|
||||
m_pwm.SetDisabled();
|
||||
}
|
||||
|
||||
void NidecBrushless::Enable() { m_disabled = false; }
|
||||
|
||||
void NidecBrushless::PIDWrite(double output) { Set(output); }
|
||||
|
||||
void NidecBrushless::SetExpiration(double timeout) {
|
||||
m_safetyHelper.SetExpiration(timeout);
|
||||
}
|
||||
|
||||
double NidecBrushless::GetExpiration() const {
|
||||
return m_safetyHelper.GetExpiration();
|
||||
}
|
||||
|
||||
bool NidecBrushless::IsAlive() const { return m_safetyHelper.IsAlive(); }
|
||||
|
||||
void NidecBrushless::SetSafetyEnabled(bool enabled) {
|
||||
m_safetyHelper.SetSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
bool NidecBrushless::IsSafetyEnabled() const {
|
||||
return m_safetyHelper.IsSafetyEnabled();
|
||||
void NidecBrushless::StopMotor() {
|
||||
m_dio.UpdateDutyCycle(0.5);
|
||||
m_pwm.SetDisabled();
|
||||
}
|
||||
|
||||
void NidecBrushless::GetDescription(wpi::raw_ostream& desc) const {
|
||||
|
||||
@@ -47,6 +47,8 @@ PWM::PWM(int channel) {
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_PWM, channel);
|
||||
SetName("PWM", channel);
|
||||
|
||||
SetSafetyEnabled(false);
|
||||
}
|
||||
|
||||
PWM::~PWM() {
|
||||
@@ -60,7 +62,7 @@ PWM::~PWM() {
|
||||
}
|
||||
|
||||
PWM::PWM(PWM&& rhs)
|
||||
: ErrorBase(std::move(rhs)),
|
||||
: MotorSafety(std::move(rhs)),
|
||||
SendableBase(std::move(rhs)),
|
||||
m_channel(std::move(rhs.m_channel)) {
|
||||
std::swap(m_handle, rhs.m_handle);
|
||||
@@ -76,6 +78,12 @@ PWM& PWM::operator=(PWM&& rhs) {
|
||||
return *this;
|
||||
}
|
||||
|
||||
void PWM::StopMotor() { SetDisabled(); }
|
||||
|
||||
void PWM::GetDescription(wpi::raw_ostream& desc) const {
|
||||
desc << "PWM " << GetChannel();
|
||||
}
|
||||
|
||||
void PWM::SetRaw(uint16_t value) {
|
||||
if (StatusIsFatal()) return;
|
||||
|
||||
@@ -114,6 +122,8 @@ void PWM::SetSpeed(double speed) {
|
||||
int32_t status = 0;
|
||||
HAL_SetPWMSpeed(m_handle, speed, &status);
|
||||
wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
|
||||
|
||||
Feed();
|
||||
}
|
||||
|
||||
double PWM::GetSpeed() const {
|
||||
|
||||
@@ -25,11 +25,11 @@ bool PWMSpeedController::GetInverted() const { return m_isInverted; }
|
||||
|
||||
void PWMSpeedController::Disable() { SetDisabled(); }
|
||||
|
||||
void PWMSpeedController::StopMotor() { SafePWM::StopMotor(); }
|
||||
void PWMSpeedController::StopMotor() { PWM::StopMotor(); }
|
||||
|
||||
void PWMSpeedController::PIDWrite(double output) { Set(output); }
|
||||
|
||||
PWMSpeedController::PWMSpeedController(int channel) : SafePWM(channel) {}
|
||||
PWMSpeedController::PWMSpeedController(int channel) : PWM(channel) {}
|
||||
|
||||
void PWMSpeedController::InitSendable(SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Speed Controller");
|
||||
|
||||
@@ -14,7 +14,6 @@
|
||||
#include <hal/Relay.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
#include "frc/SensorUtil.h"
|
||||
#include "frc/WPIErrors.h"
|
||||
#include "frc/smartdashboard/SendableBuilder.h"
|
||||
@@ -77,9 +76,6 @@ Relay::Relay(int channel, Relay::Direction direction)
|
||||
}
|
||||
}
|
||||
|
||||
m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
|
||||
m_safetyHelper->SetSafetyEnabled(false);
|
||||
|
||||
SetName("Relay", m_channel);
|
||||
}
|
||||
|
||||
@@ -94,25 +90,21 @@ Relay::~Relay() {
|
||||
|
||||
Relay::Relay(Relay&& rhs)
|
||||
: MotorSafety(std::move(rhs)),
|
||||
ErrorBase(std::move(rhs)),
|
||||
SendableBase(std::move(rhs)),
|
||||
m_channel(std::move(rhs.m_channel)),
|
||||
m_direction(std::move(rhs.m_direction)),
|
||||
m_safetyHelper(std::move(rhs.m_safetyHelper)) {
|
||||
m_direction(std::move(rhs.m_direction)) {
|
||||
std::swap(m_forwardHandle, rhs.m_forwardHandle);
|
||||
std::swap(m_reverseHandle, rhs.m_reverseHandle);
|
||||
}
|
||||
|
||||
Relay& Relay::operator=(Relay&& rhs) {
|
||||
MotorSafety::operator=(std::move(rhs));
|
||||
ErrorBase::operator=(std::move(rhs));
|
||||
SendableBase::operator=(std::move(rhs));
|
||||
|
||||
m_channel = std::move(rhs.m_channel);
|
||||
m_direction = std::move(rhs.m_direction);
|
||||
std::swap(m_forwardHandle, rhs.m_forwardHandle);
|
||||
std::swap(m_reverseHandle, rhs.m_reverseHandle);
|
||||
m_safetyHelper = std::move(rhs.m_safetyHelper);
|
||||
|
||||
return *this;
|
||||
}
|
||||
@@ -204,24 +196,8 @@ Relay::Value Relay::Get() const {
|
||||
|
||||
int Relay::GetChannel() const { return m_channel; }
|
||||
|
||||
void Relay::SetExpiration(double timeout) {
|
||||
m_safetyHelper->SetExpiration(timeout);
|
||||
}
|
||||
|
||||
double Relay::GetExpiration() const { return m_safetyHelper->GetExpiration(); }
|
||||
|
||||
bool Relay::IsAlive() const { return m_safetyHelper->IsAlive(); }
|
||||
|
||||
void Relay::StopMotor() { Set(kOff); }
|
||||
|
||||
void Relay::SetSafetyEnabled(bool enabled) {
|
||||
m_safetyHelper->SetSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
bool Relay::IsSafetyEnabled() const {
|
||||
return m_safetyHelper->IsSafetyEnabled();
|
||||
}
|
||||
|
||||
void Relay::GetDescription(wpi::raw_ostream& desc) const {
|
||||
desc << "Relay " << GetChannel();
|
||||
}
|
||||
|
||||
@@ -298,7 +298,7 @@ void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation,
|
||||
m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
|
||||
m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
|
||||
|
||||
m_safetyHelper->Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
|
||||
@@ -330,7 +330,7 @@ void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
|
||||
m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
|
||||
m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
|
||||
|
||||
m_safetyHelper->Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void RobotDrive::HolonomicDrive(double magnitude, double direction,
|
||||
@@ -350,7 +350,7 @@ void RobotDrive::SetLeftRightMotorOutputs(double leftOutput,
|
||||
m_frontRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
|
||||
m_rearRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
|
||||
|
||||
m_safetyHelper->Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
|
||||
@@ -380,40 +380,19 @@ void RobotDrive::SetSensitivity(double sensitivity) {
|
||||
|
||||
void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
|
||||
|
||||
void RobotDrive::SetExpiration(double timeout) {
|
||||
m_safetyHelper->SetExpiration(timeout);
|
||||
void RobotDrive::GetDescription(wpi::raw_ostream& desc) const {
|
||||
desc << "RobotDrive";
|
||||
}
|
||||
|
||||
double RobotDrive::GetExpiration() const {
|
||||
return m_safetyHelper->GetExpiration();
|
||||
}
|
||||
|
||||
bool RobotDrive::IsAlive() const { return m_safetyHelper->IsAlive(); }
|
||||
|
||||
void RobotDrive::StopMotor() {
|
||||
if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
|
||||
if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
|
||||
if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
|
||||
if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
|
||||
m_safetyHelper->Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
bool RobotDrive::IsSafetyEnabled() const {
|
||||
return m_safetyHelper->IsSafetyEnabled();
|
||||
}
|
||||
|
||||
void RobotDrive::SetSafetyEnabled(bool enabled) {
|
||||
m_safetyHelper->SetSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
void RobotDrive::GetDescription(wpi::raw_ostream& desc) const {
|
||||
desc << "RobotDrive";
|
||||
}
|
||||
|
||||
void RobotDrive::InitRobotDrive() {
|
||||
m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
|
||||
m_safetyHelper->SetSafetyEnabled(true);
|
||||
}
|
||||
void RobotDrive::InitRobotDrive() { SetSafetyEnabled(true); }
|
||||
|
||||
double RobotDrive::Limit(double number) {
|
||||
if (number > 1.0) {
|
||||
|
||||
@@ -1,44 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#include "frc/SafePWM.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
SafePWM::SafePWM(int channel) : PWM(channel) {
|
||||
m_safetyHelper = std::make_unique<MotorSafetyHelper>(this);
|
||||
m_safetyHelper->SetSafetyEnabled(false);
|
||||
}
|
||||
|
||||
void SafePWM::SetExpiration(double timeout) {
|
||||
m_safetyHelper->SetExpiration(timeout);
|
||||
}
|
||||
|
||||
double SafePWM::GetExpiration() const {
|
||||
return m_safetyHelper->GetExpiration();
|
||||
}
|
||||
|
||||
bool SafePWM::IsAlive() const { return m_safetyHelper->IsAlive(); }
|
||||
|
||||
void SafePWM::StopMotor() { SetDisabled(); }
|
||||
|
||||
void SafePWM::SetSafetyEnabled(bool enabled) {
|
||||
m_safetyHelper->SetSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
bool SafePWM::IsSafetyEnabled() const {
|
||||
return m_safetyHelper->IsSafetyEnabled();
|
||||
}
|
||||
|
||||
void SafePWM::GetDescription(wpi::raw_ostream& desc) const {
|
||||
desc << "PWM " << GetChannel();
|
||||
}
|
||||
|
||||
void SafePWM::SetSpeed(double speed) {
|
||||
PWM::SetSpeed(speed);
|
||||
m_safetyHelper->Feed();
|
||||
}
|
||||
@@ -19,7 +19,7 @@ constexpr double Servo::kMinServoAngle;
|
||||
constexpr double Servo::kDefaultMaxServoPWM;
|
||||
constexpr double Servo::kDefaultMinServoPWM;
|
||||
|
||||
Servo::Servo(int channel) : SafePWM(channel) {
|
||||
Servo::Servo(int channel) : PWM(channel) {
|
||||
// Set minimum and maximum PWM values supported by the servo
|
||||
SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
|
||||
|
||||
|
||||
@@ -79,7 +79,7 @@ void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,
|
||||
m_rightMotor.Set(Limit(rightMotorOutput) * m_maxOutput *
|
||||
m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
|
||||
@@ -152,7 +152,7 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
|
||||
m_rightMotor.Set(rightMotorOutput * m_maxOutput *
|
||||
m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed,
|
||||
@@ -180,7 +180,7 @@ void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed,
|
||||
m_leftMotor.Set(leftSpeed * m_maxOutput);
|
||||
m_rightMotor.Set(rightSpeed * m_maxOutput * m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void DifferentialDrive::SetQuickStopThreshold(double threshold) {
|
||||
@@ -202,7 +202,7 @@ void DifferentialDrive::SetRightSideInverted(bool rightSideInverted) {
|
||||
void DifferentialDrive::StopMotor() {
|
||||
m_leftMotor.StopMotor();
|
||||
m_rightMotor.StopMotor();
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void DifferentialDrive::GetDescription(wpi::raw_ostream& desc) const {
|
||||
|
||||
@@ -73,7 +73,7 @@ void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
|
||||
m_rightMotor.Set(wheelSpeeds[kRight] * m_maxOutput);
|
||||
m_backMotor.Set(wheelSpeeds[kBack] * m_maxOutput);
|
||||
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void KilloughDrive::DrivePolar(double magnitude, double angle,
|
||||
@@ -92,7 +92,7 @@ void KilloughDrive::StopMotor() {
|
||||
m_leftMotor.StopMotor();
|
||||
m_rightMotor.StopMotor();
|
||||
m_backMotor.StopMotor();
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void KilloughDrive::GetDescription(wpi::raw_ostream& desc) const {
|
||||
|
||||
@@ -70,7 +70,7 @@ void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,
|
||||
m_rearRightMotor.Set(wheelSpeeds[kRearRight] * m_maxOutput *
|
||||
m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void MecanumDrive::DrivePolar(double magnitude, double angle,
|
||||
@@ -98,7 +98,7 @@ void MecanumDrive::StopMotor() {
|
||||
m_frontRightMotor.StopMotor();
|
||||
m_rearLeftMotor.StopMotor();
|
||||
m_rearRightMotor.StopMotor();
|
||||
m_safetyHelper.Feed();
|
||||
Feed();
|
||||
}
|
||||
|
||||
void MecanumDrive::GetDescription(wpi::raw_ostream& desc) const {
|
||||
|
||||
@@ -18,31 +18,13 @@
|
||||
|
||||
using namespace frc;
|
||||
|
||||
RobotDriveBase::RobotDriveBase() { m_safetyHelper.SetSafetyEnabled(true); }
|
||||
RobotDriveBase::RobotDriveBase() { SetSafetyEnabled(true); }
|
||||
|
||||
void RobotDriveBase::SetDeadband(double deadband) { m_deadband = deadband; }
|
||||
|
||||
void RobotDriveBase::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
|
||||
|
||||
void RobotDriveBase::FeedWatchdog() { m_safetyHelper.Feed(); }
|
||||
|
||||
void RobotDriveBase::SetExpiration(double timeout) {
|
||||
m_safetyHelper.SetExpiration(timeout);
|
||||
}
|
||||
|
||||
double RobotDriveBase::GetExpiration() const {
|
||||
return m_safetyHelper.GetExpiration();
|
||||
}
|
||||
|
||||
bool RobotDriveBase::IsAlive() const { return m_safetyHelper.IsAlive(); }
|
||||
|
||||
bool RobotDriveBase::IsSafetyEnabled() const {
|
||||
return m_safetyHelper.IsSafetyEnabled();
|
||||
}
|
||||
|
||||
void RobotDriveBase::SetSafetyEnabled(bool enabled) {
|
||||
m_safetyHelper.SetSafetyEnabled(enabled);
|
||||
}
|
||||
void RobotDriveBase::FeedWatchdog() { Feed(); }
|
||||
|
||||
double RobotDriveBase::Limit(double value) {
|
||||
if (value > 1.0) {
|
||||
|
||||
@@ -1,19 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// clang-format off
|
||||
#ifdef _MSC_VER
|
||||
#pragma message "warning: MotorSafetyHelper.h is deprecated; include frc/MotorSafetyHelper.h instead"
|
||||
#else
|
||||
#warning "MotorSafetyHelper.h is deprecated; include frc/MotorSafetyHelper.h instead"
|
||||
#endif
|
||||
|
||||
// clang-format on
|
||||
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
@@ -1,19 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
// clang-format off
|
||||
#ifdef _MSC_VER
|
||||
#pragma message "warning: SafePWM.h is deprecated; include frc/SafePWM.h instead"
|
||||
#else
|
||||
#warning "SafePWM.h is deprecated; include frc/SafePWM.h instead"
|
||||
#endif
|
||||
|
||||
// clang-format on
|
||||
|
||||
#include "frc/SafePWM.h"
|
||||
@@ -7,25 +7,107 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#define DEFAULT_SAFETY_EXPIRATION 0.1
|
||||
|
||||
#include <wpi/mutex.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "frc/ErrorBase.h"
|
||||
#include "frc/Timer.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
class MotorSafety {
|
||||
/**
|
||||
* This base class runs a watchdog timer and calls the subclass's StopMotor()
|
||||
* function if the timeout expires.
|
||||
*
|
||||
* The subclass should call Feed() whenever the motor value is updated.
|
||||
*/
|
||||
class MotorSafety : public ErrorBase {
|
||||
public:
|
||||
MotorSafety() = default;
|
||||
MotorSafety(MotorSafety&&) = default;
|
||||
MotorSafety& operator=(MotorSafety&&) = default;
|
||||
MotorSafety();
|
||||
virtual ~MotorSafety();
|
||||
|
||||
MotorSafety(MotorSafety&& rhs);
|
||||
MotorSafety& operator=(MotorSafety&& rhs);
|
||||
|
||||
/**
|
||||
* Feed the motor safety object.
|
||||
*
|
||||
* Resets the timer on this object that is used to do the timeouts.
|
||||
*/
|
||||
void Feed();
|
||||
|
||||
/**
|
||||
* Set the expiration time for the corresponding motor safety object.
|
||||
*
|
||||
* @param expirationTime The timeout value in seconds.
|
||||
*/
|
||||
void SetExpiration(double expirationTime);
|
||||
|
||||
/**
|
||||
* Retrieve the timeout value for the corresponding motor safety object.
|
||||
*
|
||||
* @return the timeout value in seconds.
|
||||
*/
|
||||
double GetExpiration() const;
|
||||
|
||||
/**
|
||||
* Determine if the motor is still operating or has timed out.
|
||||
*
|
||||
* @return true if the motor is still operating normally and hasn't timed out.
|
||||
*/
|
||||
bool IsAlive() const;
|
||||
|
||||
/**
|
||||
* Enable/disable motor safety for this device.
|
||||
*
|
||||
* Turn on and off the motor safety option for this PWM object.
|
||||
*
|
||||
* @param enabled True if motor safety is enforced for this object.
|
||||
*/
|
||||
void SetSafetyEnabled(bool enabled);
|
||||
|
||||
/**
|
||||
* Return the state of the motor safety enabled flag.
|
||||
*
|
||||
* Return if the motor safety is currently enabled for this device.
|
||||
*
|
||||
* @return True if motor safety is enforced for this device.
|
||||
*/
|
||||
bool IsSafetyEnabled() const;
|
||||
|
||||
/**
|
||||
* Check if this motor has exceeded its timeout.
|
||||
*
|
||||
* This method is called periodically to determine if this motor has exceeded
|
||||
* its timeout value. If it has, the stop method is called, and the motor is
|
||||
* shut down until its value is updated again.
|
||||
*/
|
||||
void Check();
|
||||
|
||||
/**
|
||||
* Check the motors to see if any have timed out.
|
||||
*
|
||||
* This static method is called periodically to poll all the motors and stop
|
||||
* any that have timed out.
|
||||
*/
|
||||
static void CheckMotors();
|
||||
|
||||
virtual void SetExpiration(double timeout) = 0;
|
||||
virtual double GetExpiration() const = 0;
|
||||
virtual bool IsAlive() const = 0;
|
||||
virtual void StopMotor() = 0;
|
||||
virtual void SetSafetyEnabled(bool enabled) = 0;
|
||||
virtual bool IsSafetyEnabled() const = 0;
|
||||
virtual void GetDescription(wpi::raw_ostream& desc) const = 0;
|
||||
|
||||
private:
|
||||
static constexpr double kDefaultSafetyExpiration = 0.1;
|
||||
|
||||
// The expiration time for this object
|
||||
double m_expiration = kDefaultSafetyExpiration;
|
||||
|
||||
// True if motor safety is enabled for this motor
|
||||
bool m_enabled = false;
|
||||
|
||||
// The FPGA clock value when the motor has expired
|
||||
double m_stopTime = Timer::GetFPGATimestamp();
|
||||
|
||||
mutable wpi::mutex m_thisMutex;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
|
||||
@@ -1,120 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <wpi/mutex.h>
|
||||
|
||||
#include "frc/ErrorBase.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
class MotorSafety;
|
||||
|
||||
class MotorSafetyHelper : public ErrorBase {
|
||||
public:
|
||||
/**
|
||||
* The constructor for a MotorSafetyHelper object.
|
||||
*
|
||||
* The helper object is constructed for every object that wants to implement
|
||||
* the Motor Safety protocol. The helper object has the code to actually do
|
||||
* the timing and call the motors Stop() method when the timeout expires. The
|
||||
* motor object is expected to call the Feed() method whenever the motors
|
||||
* value is updated.
|
||||
*
|
||||
* @param safeObject a pointer to the motor object implementing MotorSafety.
|
||||
* This is used to call the Stop() method on the motor.
|
||||
*/
|
||||
explicit MotorSafetyHelper(MotorSafety* safeObject);
|
||||
|
||||
~MotorSafetyHelper();
|
||||
|
||||
MotorSafetyHelper(MotorSafetyHelper&&) = default;
|
||||
MotorSafetyHelper& operator=(MotorSafetyHelper&&) = default;
|
||||
|
||||
/**
|
||||
* Feed the motor safety object.
|
||||
*
|
||||
* Resets the timer on this object that is used to do the timeouts.
|
||||
*/
|
||||
void Feed();
|
||||
|
||||
/**
|
||||
* Set the expiration time for the corresponding motor safety object.
|
||||
*
|
||||
* @param expirationTime The timeout value in seconds.
|
||||
*/
|
||||
void SetExpiration(double expirationTime);
|
||||
|
||||
/**
|
||||
* Retrieve the timeout value for the corresponding motor safety object.
|
||||
*
|
||||
* @return the timeout value in seconds.
|
||||
*/
|
||||
double GetExpiration() const;
|
||||
|
||||
/**
|
||||
* Determine if the motor is still operating or has timed out.
|
||||
*
|
||||
* @return a true value if the motor is still operating normally and hasn't
|
||||
* timed out.
|
||||
*/
|
||||
bool IsAlive() const;
|
||||
|
||||
/**
|
||||
* Check if this motor has exceeded its timeout.
|
||||
*
|
||||
* This method is called periodically to determine if this motor has exceeded
|
||||
* its timeout value. If it has, the stop method is called, and the motor is
|
||||
* shut down until its value is updated again.
|
||||
*/
|
||||
void Check();
|
||||
|
||||
/**
|
||||
* Enable/disable motor safety for this device
|
||||
*
|
||||
* Turn on and off the motor safety option for this PWM object.
|
||||
*
|
||||
* @param enabled True if motor safety is enforced for this object
|
||||
*/
|
||||
void SetSafetyEnabled(bool enabled);
|
||||
|
||||
/**
|
||||
* Return the state of the motor safety enabled flag
|
||||
*
|
||||
* Return if the motor safety is currently enabled for this devicce.
|
||||
*
|
||||
* @return True if motor safety is enforced for this device
|
||||
*/
|
||||
bool IsSafetyEnabled() const;
|
||||
|
||||
/**
|
||||
* Check the motors to see if any have timed out.
|
||||
*
|
||||
* This static method is called periodically to poll all the motors and stop
|
||||
* any that have timed out.
|
||||
*/
|
||||
static void CheckMotors();
|
||||
|
||||
private:
|
||||
// The expiration time for this object
|
||||
double m_expiration;
|
||||
|
||||
// True if motor safety is enabled for this motor
|
||||
bool m_enabled;
|
||||
|
||||
// The FPGA clock value when this motor has expired
|
||||
double m_stopTime;
|
||||
|
||||
// Protect accesses to the state for this object
|
||||
mutable wpi::mutex m_thisMutex;
|
||||
|
||||
// The object that is using the helper
|
||||
MotorSafety* m_safeObject;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -12,7 +12,6 @@
|
||||
#include "frc/DigitalOutput.h"
|
||||
#include "frc/ErrorBase.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
#include "frc/PWM.h"
|
||||
#include "frc/SpeedController.h"
|
||||
#include "frc/smartdashboard/SendableBase.h"
|
||||
@@ -22,8 +21,7 @@ namespace frc {
|
||||
/**
|
||||
* Nidec Brushless Motor.
|
||||
*/
|
||||
class NidecBrushless : public ErrorBase,
|
||||
public SendableBase,
|
||||
class NidecBrushless : public SendableBase,
|
||||
public SpeedController,
|
||||
public MotorSafety {
|
||||
public:
|
||||
@@ -70,15 +68,6 @@ class NidecBrushless : public ErrorBase,
|
||||
*/
|
||||
void Disable() override;
|
||||
|
||||
/**
|
||||
* Stop the motor.
|
||||
*
|
||||
* This is called by the MotorSafetyHelper object when it has a timeout for
|
||||
* this PWM and needs to stop it from running. Calling Set() will re-enable
|
||||
* the motor.
|
||||
*/
|
||||
void StopMotor() override;
|
||||
|
||||
/**
|
||||
* Re-enable the motor after Disable() has been called. The Set() function
|
||||
* must be called to set a new motor speed.
|
||||
@@ -94,32 +83,7 @@ class NidecBrushless : public ErrorBase,
|
||||
void PIDWrite(double output) override;
|
||||
|
||||
// MotorSafety interface
|
||||
/**
|
||||
* Set the safety expiration time.
|
||||
*
|
||||
* @param timeout The timeout (in seconds) for this motor object
|
||||
*/
|
||||
void SetExpiration(double timeout) override;
|
||||
|
||||
/**
|
||||
* Return the safety expiration time.
|
||||
*
|
||||
* @return The expiration time value.
|
||||
*/
|
||||
double GetExpiration() const override;
|
||||
|
||||
/**
|
||||
* Check if the motor is currently alive or stopped due to a timeout.
|
||||
*
|
||||
* @return a bool value that is true if the motor has NOT timed out and should
|
||||
* still be running.
|
||||
*/
|
||||
bool IsAlive() const override;
|
||||
|
||||
void SetSafetyEnabled(bool enabled) override;
|
||||
|
||||
bool IsSafetyEnabled() const override;
|
||||
|
||||
void StopMotor() override;
|
||||
void GetDescription(wpi::raw_ostream& desc) const override;
|
||||
|
||||
/**
|
||||
@@ -133,7 +97,6 @@ class NidecBrushless : public ErrorBase,
|
||||
void InitSendable(SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
MotorSafetyHelper m_safetyHelper;
|
||||
bool m_isInverted = false;
|
||||
std::atomic_bool m_disabled{false};
|
||||
DigitalOutput m_dio;
|
||||
|
||||
@@ -10,8 +10,9 @@
|
||||
#include <stdint.h>
|
||||
|
||||
#include <hal/Types.h>
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "frc/ErrorBase.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/smartdashboard/SendableBase.h"
|
||||
|
||||
namespace frc {
|
||||
@@ -33,7 +34,7 @@ namespace frc {
|
||||
* - 1 = minimum pulse width (currently .5ms)
|
||||
* - 0 = disabled (i.e. PWM output is held low)
|
||||
*/
|
||||
class PWM : public ErrorBase, public SendableBase {
|
||||
class PWM : public MotorSafety, public SendableBase {
|
||||
public:
|
||||
/**
|
||||
* Represents the amount to multiply the minimum servo-pulse pwm period by.
|
||||
@@ -75,6 +76,10 @@ class PWM : public ErrorBase, public SendableBase {
|
||||
PWM(PWM&& rhs);
|
||||
PWM& operator=(PWM&& rhs);
|
||||
|
||||
// MotorSafety interface
|
||||
void StopMotor() override;
|
||||
void GetDescription(wpi::raw_ostream& desc) const override;
|
||||
|
||||
/**
|
||||
* Set the PWM value directly to the hardware.
|
||||
*
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/SafePWM.h"
|
||||
#include "frc/PWM.h"
|
||||
#include "frc/SpeedController.h"
|
||||
|
||||
namespace frc {
|
||||
@@ -15,7 +15,7 @@ namespace frc {
|
||||
/**
|
||||
* Common base class for all PWM Speed Controllers.
|
||||
*/
|
||||
class PWMSpeedController : public SafePWM, public SpeedController {
|
||||
class PWMSpeedController : public PWM, public SpeedController {
|
||||
public:
|
||||
PWMSpeedController(PWMSpeedController&&) = default;
|
||||
PWMSpeedController& operator=(PWMSpeedController&&) = default;
|
||||
|
||||
@@ -18,8 +18,6 @@
|
||||
|
||||
namespace frc {
|
||||
|
||||
class MotorSafetyHelper;
|
||||
|
||||
/**
|
||||
* Class for Spike style relay outputs.
|
||||
*
|
||||
@@ -32,7 +30,7 @@ class MotorSafetyHelper;
|
||||
* independently for something that does not care about voltage polarity (like
|
||||
* a solenoid).
|
||||
*/
|
||||
class Relay : public MotorSafety, public ErrorBase, public SendableBase {
|
||||
class Relay : public MotorSafety, public SendableBase {
|
||||
public:
|
||||
enum Value { kOff, kOn, kForward, kReverse };
|
||||
enum Direction { kBothDirections, kForwardOnly, kReverseOnly };
|
||||
@@ -89,52 +87,9 @@ class Relay : public MotorSafety, public ErrorBase, public SendableBase {
|
||||
|
||||
int GetChannel() const;
|
||||
|
||||
/**
|
||||
* Set the expiration time for the Relay object.
|
||||
*
|
||||
* @param timeout The timeout (in seconds) for this relay object
|
||||
*/
|
||||
void SetExpiration(double timeout) override;
|
||||
|
||||
/**
|
||||
* Return the expiration time for the relay object.
|
||||
*
|
||||
* @return The expiration time value.
|
||||
*/
|
||||
double GetExpiration() const override;
|
||||
|
||||
/**
|
||||
* Check if the relay object is currently alive or stopped due to a timeout.
|
||||
*
|
||||
* @return a bool value that is true if the motor has NOT timed out and should
|
||||
* still be running.
|
||||
*/
|
||||
bool IsAlive() const override;
|
||||
|
||||
/**
|
||||
* Stop the motor associated with this PWM object.
|
||||
*
|
||||
* This is called by the MotorSafetyHelper object when it has a timeout for
|
||||
* this relay and needs to stop it from running.
|
||||
*/
|
||||
// MotorSafety interface
|
||||
void StopMotor() override;
|
||||
|
||||
/**
|
||||
* Enable/disable motor safety for this device.
|
||||
*
|
||||
* Turn on and off the motor safety option for this relay object.
|
||||
*
|
||||
* @param enabled True if motor safety is enforced for this object
|
||||
*/
|
||||
void SetSafetyEnabled(bool enabled) override;
|
||||
|
||||
/**
|
||||
* Check if motor safety is enabled for this object.
|
||||
*
|
||||
* @returns True if motor safety is enforced for this object
|
||||
*/
|
||||
bool IsSafetyEnabled() const override;
|
||||
|
||||
void GetDescription(wpi::raw_ostream& desc) const override;
|
||||
|
||||
void InitSendable(SendableBuilder& builder) override;
|
||||
@@ -145,8 +100,6 @@ class Relay : public MotorSafety, public ErrorBase, public SendableBase {
|
||||
|
||||
HAL_RelayHandle m_forwardHandle = HAL_kInvalidHandle;
|
||||
HAL_RelayHandle m_reverseHandle = HAL_kInvalidHandle;
|
||||
|
||||
std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
|
||||
@@ -14,7 +14,6 @@
|
||||
|
||||
#include "frc/ErrorBase.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
@@ -32,7 +31,7 @@ class GenericHID;
|
||||
* function (intended for hand created drive code, such as autonomous) or with
|
||||
* the Tank/Arcade functions intended to be used for Operator Control driving.
|
||||
*/
|
||||
class RobotDrive : public MotorSafety, public ErrorBase {
|
||||
class RobotDrive : public MotorSafety {
|
||||
public:
|
||||
enum MotorType {
|
||||
kFrontLeftMotor = 0,
|
||||
@@ -401,12 +400,7 @@ class RobotDrive : public MotorSafety, public ErrorBase {
|
||||
*/
|
||||
void SetMaxOutput(double maxOutput);
|
||||
|
||||
void SetExpiration(double timeout) override;
|
||||
double GetExpiration() const override;
|
||||
bool IsAlive() const override;
|
||||
void StopMotor() override;
|
||||
bool IsSafetyEnabled() const override;
|
||||
void SetSafetyEnabled(bool enabled) override;
|
||||
void GetDescription(wpi::raw_ostream& desc) const override;
|
||||
|
||||
protected:
|
||||
@@ -444,7 +438,6 @@ class RobotDrive : public MotorSafety, public ErrorBase {
|
||||
std::shared_ptr<SpeedController> m_frontRightMotor;
|
||||
std::shared_ptr<SpeedController> m_rearLeftMotor;
|
||||
std::shared_ptr<SpeedController> m_rearRightMotor;
|
||||
std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
|
||||
|
||||
private:
|
||||
int GetNumMotors() {
|
||||
|
||||
@@ -1,105 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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. */
|
||||
/*----------------------------------------------------------------------------*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
#include "frc/PWM.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* A safe version of the PWM class.
|
||||
*
|
||||
* It is safe because it implements the MotorSafety interface that provides
|
||||
* timeouts in the event that the motor value is not updated before the
|
||||
* expiration time. This delegates the actual work to a MotorSafetyHelper
|
||||
* object that is used for all objects that implement MotorSafety.
|
||||
*/
|
||||
class SafePWM : public PWM, public MotorSafety {
|
||||
public:
|
||||
/**
|
||||
* Constructor for a SafePWM object taking a channel number.
|
||||
*
|
||||
* @param channel The PWM channel number 0-9 are on-board, 10-19 are on the
|
||||
* MXP port
|
||||
*/
|
||||
explicit SafePWM(int channel);
|
||||
|
||||
virtual ~SafePWM() = default;
|
||||
|
||||
SafePWM(SafePWM&&) = default;
|
||||
SafePWM& operator=(SafePWM&&) = default;
|
||||
|
||||
/**
|
||||
* Set the expiration time for the PWM object.
|
||||
*
|
||||
* @param timeout The timeout (in seconds) for this motor object
|
||||
*/
|
||||
void SetExpiration(double timeout);
|
||||
|
||||
/**
|
||||
* Return the expiration time for the PWM object.
|
||||
*
|
||||
* @returns The expiration time value.
|
||||
*/
|
||||
double GetExpiration() const;
|
||||
|
||||
/**
|
||||
* Check if the PWM object is currently alive or stopped due to a timeout.
|
||||
*
|
||||
* @return a bool value that is true if the motor has NOT timed out and should
|
||||
* still be running.
|
||||
*/
|
||||
bool IsAlive() const;
|
||||
|
||||
/**
|
||||
* Stop the motor associated with this PWM object.
|
||||
*
|
||||
* This is called by the MotorSafetyHelper object when it has a timeout for
|
||||
* this PWM and needs to stop it from running.
|
||||
*/
|
||||
void StopMotor();
|
||||
|
||||
/**
|
||||
* Enable/disable motor safety for this device.
|
||||
*
|
||||
* Turn on and off the motor safety option for this PWM object.
|
||||
*
|
||||
* @param enabled True if motor safety is enforced for this object
|
||||
*/
|
||||
void SetSafetyEnabled(bool enabled);
|
||||
|
||||
/**
|
||||
* Check if motor safety is enabled for this object.
|
||||
*
|
||||
* @returns True if motor safety is enforced for this object
|
||||
*/
|
||||
bool IsSafetyEnabled() const;
|
||||
|
||||
void GetDescription(wpi::raw_ostream& desc) const;
|
||||
|
||||
/**
|
||||
* Feed the MotorSafety timer when setting the speed.
|
||||
*
|
||||
* This method is called by the subclass motor whenever it updates its speed,
|
||||
* thereby reseting the timeout value.
|
||||
*
|
||||
* @param speed Value to pass to the PWM class
|
||||
*/
|
||||
virtual void SetSpeed(double speed);
|
||||
|
||||
private:
|
||||
std::unique_ptr<MotorSafetyHelper> m_safetyHelper;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/SafePWM.h"
|
||||
#include "frc/PWM.h"
|
||||
#include "frc/SpeedController.h"
|
||||
|
||||
namespace frc {
|
||||
@@ -18,7 +18,7 @@ namespace frc {
|
||||
* The range parameters default to the appropriate values for the Hitec HS-322HD
|
||||
* servo provided in the FIRST Kit of Parts in 2008.
|
||||
*/
|
||||
class Servo : public SafePWM {
|
||||
class Servo : public PWM {
|
||||
public:
|
||||
/**
|
||||
* @param channel The PWM channel to which the servo is attached. 0-9 are
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
#include <wpi/raw_ostream.h>
|
||||
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/MotorSafetyHelper.h"
|
||||
#include "frc/smartdashboard/SendableBase.h"
|
||||
|
||||
namespace frc {
|
||||
@@ -72,12 +71,7 @@ class RobotDriveBase : public MotorSafety, public SendableBase {
|
||||
*/
|
||||
void FeedWatchdog();
|
||||
|
||||
void SetExpiration(double timeout) override;
|
||||
double GetExpiration() const override;
|
||||
bool IsAlive() const override;
|
||||
void StopMotor() override = 0;
|
||||
bool IsSafetyEnabled() const override;
|
||||
void SetSafetyEnabled(bool enabled) override;
|
||||
void GetDescription(wpi::raw_ostream& desc) const override = 0;
|
||||
|
||||
protected:
|
||||
@@ -103,7 +97,6 @@ class RobotDriveBase : public MotorSafety, public SendableBase {
|
||||
|
||||
double m_deadband = 0.02;
|
||||
double m_maxOutput = 1.0;
|
||||
MotorSafetyHelper m_safetyHelper{this};
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
|
||||
@@ -1127,7 +1127,7 @@ public class DriverStation {
|
||||
|
||||
safetyCounter++;
|
||||
if (safetyCounter >= 4) {
|
||||
MotorSafetyHelper.checkMotors();
|
||||
MotorSafety.checkMotors();
|
||||
safetyCounter = 0;
|
||||
}
|
||||
if (m_userInDisabled) {
|
||||
|
||||
@@ -7,23 +7,144 @@
|
||||
|
||||
package edu.wpi.first.wpilibj;
|
||||
|
||||
import java.util.LinkedHashSet;
|
||||
import java.util.Set;
|
||||
|
||||
/**
|
||||
* Shuts off motors when their outputs aren't updated often enough.
|
||||
* This base class runs a watchdog timer and calls the subclass's StopMotor()
|
||||
* function if the timeout expires.
|
||||
*
|
||||
* <p>The subclass should call feed() whenever the motor value is updated.
|
||||
*/
|
||||
public interface MotorSafety {
|
||||
double DEFAULT_SAFETY_EXPIRATION = 0.1;
|
||||
public abstract class MotorSafety {
|
||||
private static final double kDefaultSafetyExpiration = 0.1;
|
||||
|
||||
void setExpiration(double timeout);
|
||||
private double m_expiration = kDefaultSafetyExpiration;
|
||||
private boolean m_enabled;
|
||||
private double m_stopTime = Timer.getFPGATimestamp();
|
||||
private final Object m_thisMutex = new Object();
|
||||
private static final Set<MotorSafety> m_instanceList = new LinkedHashSet<>();
|
||||
private static final Object m_listMutex = new Object();
|
||||
|
||||
double getExpiration();
|
||||
/**
|
||||
* MotorSafety constructor.
|
||||
*/
|
||||
public MotorSafety() {
|
||||
synchronized (m_listMutex) {
|
||||
m_instanceList.add(this);
|
||||
}
|
||||
}
|
||||
|
||||
boolean isAlive();
|
||||
/**
|
||||
* Feed the motor safety object.
|
||||
*
|
||||
* <p>Resets the timer on this object that is used to do the timeouts.
|
||||
*/
|
||||
public void feed() {
|
||||
synchronized (m_thisMutex) {
|
||||
m_stopTime = Timer.getFPGATimestamp() + m_expiration;
|
||||
}
|
||||
}
|
||||
|
||||
void stopMotor();
|
||||
/**
|
||||
* Set the expiration time for the corresponding motor safety object.
|
||||
*
|
||||
* @param expirationTime The timeout value in seconds.
|
||||
*/
|
||||
public void setExpiration(double expirationTime) {
|
||||
synchronized (m_thisMutex) {
|
||||
m_expiration = expirationTime;
|
||||
}
|
||||
}
|
||||
|
||||
void setSafetyEnabled(boolean enabled);
|
||||
/**
|
||||
* Retrieve the timeout value for the corresponding motor safety object.
|
||||
*
|
||||
* @return the timeout value in seconds.
|
||||
*/
|
||||
public double getExpiration() {
|
||||
synchronized (m_thisMutex) {
|
||||
return m_expiration;
|
||||
}
|
||||
}
|
||||
|
||||
boolean isSafetyEnabled();
|
||||
/**
|
||||
* Determine of the motor is still operating or has timed out.
|
||||
*
|
||||
* @return a true value if the motor is still operating normally and hasn't timed out.
|
||||
*/
|
||||
public boolean isAlive() {
|
||||
synchronized (m_thisMutex) {
|
||||
return !m_enabled || m_stopTime > Timer.getFPGATimestamp();
|
||||
}
|
||||
}
|
||||
|
||||
String getDescription();
|
||||
/**
|
||||
* Check if this motor has exceeded its timeout. This method is called periodically to determine
|
||||
* if this motor has exceeded its timeout value. If it has, the stop method is called, and the
|
||||
* motor is shut down until its value is updated again.
|
||||
*/
|
||||
public void check() {
|
||||
boolean enabled;
|
||||
double stopTime;
|
||||
|
||||
synchronized (m_thisMutex) {
|
||||
enabled = m_enabled;
|
||||
stopTime = m_stopTime;
|
||||
}
|
||||
|
||||
if (!enabled || RobotState.isDisabled() || RobotState.isTest()) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (stopTime < Timer.getFPGATimestamp()) {
|
||||
DriverStation.reportError(getDescription() + "... Output not updated often enough.", false);
|
||||
|
||||
stopMotor();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable/disable motor safety for this device.
|
||||
*
|
||||
* <p>Turn on and off the motor safety option for this PWM object.
|
||||
*
|
||||
* @param enabled True if motor safety is enforced for this object
|
||||
*/
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
synchronized (m_thisMutex) {
|
||||
m_enabled = enabled;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the state of the motor safety enabled flag.
|
||||
*
|
||||
* <p>Return if the motor safety is currently enabled for this device.
|
||||
*
|
||||
* @return True if motor safety is enforced for this device
|
||||
*/
|
||||
public boolean isSafetyEnabled() {
|
||||
synchronized (m_thisMutex) {
|
||||
return m_enabled;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check the motors to see if any have timed out.
|
||||
*
|
||||
* <p>This static method is called periodically to poll all the motors and stop any that have
|
||||
* timed out.
|
||||
*/
|
||||
public static void checkMotors() {
|
||||
synchronized (m_listMutex) {
|
||||
for (MotorSafety elem : m_instanceList) {
|
||||
elem.check();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public abstract void stopMotor();
|
||||
|
||||
public abstract String getDescription();
|
||||
}
|
||||
|
||||
@@ -1,150 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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 java.util.LinkedHashSet;
|
||||
import java.util.Set;
|
||||
|
||||
/**
|
||||
* The MotorSafetyHelper object is constructed for every object that wants to implement the Motor
|
||||
* Safety protocol. The helper object has the code to actually do the timing and call the motors
|
||||
* Stop() method when the timeout expires. The motor object is expected to call the Feed() method
|
||||
* whenever the motors value is updated.
|
||||
*/
|
||||
public final class MotorSafetyHelper {
|
||||
private double m_expiration;
|
||||
private boolean m_enabled;
|
||||
private double m_stopTime;
|
||||
private final Object m_thisMutex = new Object();
|
||||
private final MotorSafety m_safeObject;
|
||||
private static final Set<MotorSafetyHelper> m_helperList = new LinkedHashSet<>();
|
||||
private static final Object m_listMutex = new Object();
|
||||
|
||||
/**
|
||||
* The constructor for a MotorSafetyHelper object. The helper object is constructed for every
|
||||
* object that wants to implement the Motor Safety protocol. The helper object has the code to
|
||||
* actually do the timing and call the motors Stop() method when the timeout expires. The motor
|
||||
* object is expected to call the Feed() method whenever the motors value is updated.
|
||||
*
|
||||
* @param safeObject a pointer to the motor object implementing MotorSafety. This is used to call
|
||||
* the Stop() method on the motor.
|
||||
*/
|
||||
public MotorSafetyHelper(MotorSafety safeObject) {
|
||||
m_safeObject = safeObject;
|
||||
m_enabled = false;
|
||||
m_expiration = MotorSafety.DEFAULT_SAFETY_EXPIRATION;
|
||||
m_stopTime = Timer.getFPGATimestamp();
|
||||
|
||||
synchronized (m_listMutex) {
|
||||
m_helperList.add(this);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Feed the motor safety object. Resets the timer on this object that is used to do the timeouts.
|
||||
*/
|
||||
public void feed() {
|
||||
synchronized (m_thisMutex) {
|
||||
m_stopTime = Timer.getFPGATimestamp() + m_expiration;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the expiration time for the corresponding motor safety object.
|
||||
*
|
||||
* @param expirationTime The timeout value in seconds.
|
||||
*/
|
||||
public void setExpiration(double expirationTime) {
|
||||
synchronized (m_thisMutex) {
|
||||
m_expiration = expirationTime;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Retrieve the timeout value for the corresponding motor safety object.
|
||||
*
|
||||
* @return the timeout value in seconds.
|
||||
*/
|
||||
public double getExpiration() {
|
||||
synchronized (m_thisMutex) {
|
||||
return m_expiration;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Determine of the motor is still operating or has timed out.
|
||||
*
|
||||
* @return a true value if the motor is still operating normally and hasn't timed out.
|
||||
*/
|
||||
public boolean isAlive() {
|
||||
synchronized (m_thisMutex) {
|
||||
return !m_enabled || m_stopTime > Timer.getFPGATimestamp();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if this motor has exceeded its timeout. This method is called periodically to determine
|
||||
* if this motor has exceeded its timeout value. If it has, the stop method is called, and the
|
||||
* motor is shut down until its value is updated again.
|
||||
*/
|
||||
public void check() {
|
||||
boolean enabled;
|
||||
double stopTime;
|
||||
|
||||
synchronized (m_thisMutex) {
|
||||
enabled = m_enabled;
|
||||
stopTime = m_stopTime;
|
||||
}
|
||||
|
||||
if (!enabled || RobotState.isDisabled() || RobotState.isTest()) {
|
||||
return;
|
||||
}
|
||||
if (stopTime < Timer.getFPGATimestamp()) {
|
||||
DriverStation.reportError(m_safeObject.getDescription() + "... Output not updated often "
|
||||
+ "enough.", false);
|
||||
|
||||
m_safeObject.stopMotor();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Enable/disable motor safety for this device Turn on and off the motor safety option for this
|
||||
* PWM object.
|
||||
*
|
||||
* @param enabled True if motor safety is enforced for this object
|
||||
*/
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
synchronized (m_thisMutex) {
|
||||
m_enabled = enabled;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the state of the motor safety enabled flag Return if the motor safety is currently
|
||||
* enabled for this device.
|
||||
*
|
||||
* @return True if motor safety is enforced for this device
|
||||
*/
|
||||
public boolean isSafetyEnabled() {
|
||||
synchronized (m_thisMutex) {
|
||||
return m_enabled;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check the motors to see if any have timed out. This static method is called periodically to
|
||||
* poll all the motors and stop any that have timed out.
|
||||
*/
|
||||
public static void checkMotors() {
|
||||
synchronized (m_listMutex) {
|
||||
for (MotorSafetyHelper elem : m_helperList) {
|
||||
elem.check();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -14,14 +14,16 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
/**
|
||||
* Nidec Brushless Motor.
|
||||
*/
|
||||
public class NidecBrushless extends SendableBase implements SpeedController, MotorSafety, Sendable {
|
||||
private final MotorSafetyHelper m_safetyHelper;
|
||||
public class NidecBrushless extends MotorSafety implements SpeedController, Sendable,
|
||||
AutoCloseable {
|
||||
private boolean m_isInverted;
|
||||
private final DigitalOutput m_dio;
|
||||
private final PWM m_pwm;
|
||||
private volatile double m_speed;
|
||||
private volatile boolean m_disabled;
|
||||
|
||||
private final SendableImpl m_sendableImpl;
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
@@ -31,9 +33,9 @@ public class NidecBrushless extends SendableBase implements SpeedController, Mot
|
||||
* 0-9 are on-board, 10-25 are on the MXP port
|
||||
*/
|
||||
public NidecBrushless(final int pwmChannel, final int dioChannel) {
|
||||
m_safetyHelper = new MotorSafetyHelper(this);
|
||||
m_safetyHelper.setExpiration(0.0);
|
||||
m_safetyHelper.setSafetyEnabled(false);
|
||||
m_sendableImpl = new SendableImpl(true);
|
||||
|
||||
setSafetyEnabled(false);
|
||||
|
||||
// the dio controls the output (in PWM mode)
|
||||
m_dio = new DigitalOutput(dioChannel);
|
||||
@@ -51,11 +53,61 @@ public class NidecBrushless extends SendableBase implements SpeedController, Mot
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
super.close();
|
||||
m_sendableImpl.close();
|
||||
m_dio.close();
|
||||
m_pwm.close();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getName() {
|
||||
return m_sendableImpl.getName();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setName(String name) {
|
||||
m_sendableImpl.setName(name);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param channel The channel number the device is plugged into
|
||||
*/
|
||||
protected final void setName(String moduleType, int channel) {
|
||||
m_sendableImpl.setName(moduleType, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a module and channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param moduleNumber The number of the particular module type
|
||||
* @param channel The channel number the device is plugged into (usually PWM)
|
||||
*/
|
||||
protected final void setName(String moduleType, int moduleNumber, int channel) {
|
||||
m_sendableImpl.setName(moduleType, moduleNumber, channel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getSubsystem() {
|
||||
return m_sendableImpl.getSubsystem();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setSubsystem(String subsystem) {
|
||||
m_sendableImpl.setSubsystem(subsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a child component.
|
||||
*
|
||||
* @param child child component
|
||||
*/
|
||||
protected final void addChild(Object child) {
|
||||
m_sendableImpl.addChild(child);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
@@ -71,7 +123,8 @@ public class NidecBrushless extends SendableBase implements SpeedController, Mot
|
||||
m_dio.updateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
|
||||
m_pwm.setRaw(0xffff);
|
||||
}
|
||||
m_safetyHelper.feed();
|
||||
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -105,39 +158,8 @@ public class NidecBrushless extends SendableBase implements SpeedController, Mot
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the safety expiration time.
|
||||
*
|
||||
* @param timeout The timeout (in seconds) for this motor object
|
||||
*/
|
||||
@Override
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the safety expiration time.
|
||||
*
|
||||
* @return The expiration time value.
|
||||
*/
|
||||
@Override
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if the motor is currently alive or stopped due to a timeout.
|
||||
*
|
||||
* @return a bool value that is true if the motor has NOT timed out and should still be running.
|
||||
*/
|
||||
@Override
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the motor. This is called by the MotorSafetyHelper object
|
||||
* when it has a timeout for this PWM and needs to stop it from running.
|
||||
* Calling set() will re-enable the motor.
|
||||
* 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.
|
||||
*/
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
@@ -145,21 +167,6 @@ public class NidecBrushless extends SendableBase implements SpeedController, Mot
|
||||
m_pwm.setDisabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if motor safety is enabled.
|
||||
*
|
||||
* @return True if motor safety is enforced for this object
|
||||
*/
|
||||
@Override
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDescription() {
|
||||
return "Nidec " + getChannel();
|
||||
|
||||
@@ -25,7 +25,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
* center value - 999 to 2 = linear scaling from "center" to "full reverse" - 1 = minimum pulse
|
||||
* width (currently .5ms) - 0 = disabled (i.e. PWM output is held low)
|
||||
*/
|
||||
public class PWM extends SendableBase {
|
||||
public class PWM extends MotorSafety implements Sendable, AutoCloseable {
|
||||
/**
|
||||
* Represents the amount to multiply the minimum servo-pulse pwm period by.
|
||||
*/
|
||||
@@ -47,12 +47,16 @@ public class PWM extends SendableBase {
|
||||
private final int m_channel;
|
||||
private int m_handle;
|
||||
|
||||
private final SendableImpl m_sendableImpl;
|
||||
|
||||
/**
|
||||
* Allocate a PWM given a channel.
|
||||
*
|
||||
* @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port
|
||||
*/
|
||||
public PWM(final int channel) {
|
||||
m_sendableImpl = new SendableImpl(true);
|
||||
|
||||
SensorUtil.checkPWMChannel(channel);
|
||||
m_channel = channel;
|
||||
|
||||
@@ -64,6 +68,8 @@ public class PWM extends SendableBase {
|
||||
|
||||
HAL.report(tResourceType.kResourceType_PWM, channel);
|
||||
setName("PWM", channel);
|
||||
|
||||
setSafetyEnabled(false);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -71,7 +77,8 @@ public class PWM extends SendableBase {
|
||||
*/
|
||||
@Override
|
||||
public void close() {
|
||||
super.close();
|
||||
m_sendableImpl.close();
|
||||
|
||||
if (m_handle == 0) {
|
||||
return;
|
||||
}
|
||||
@@ -80,6 +87,66 @@ public class PWM extends SendableBase {
|
||||
m_handle = 0;
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getName() {
|
||||
return m_sendableImpl.getName();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setName(String name) {
|
||||
m_sendableImpl.setName(name);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param channel The channel number the device is plugged into
|
||||
*/
|
||||
protected final void setName(String moduleType, int channel) {
|
||||
m_sendableImpl.setName(moduleType, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a module and channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param moduleNumber The number of the particular module type
|
||||
* @param channel The channel number the device is plugged into (usually PWM)
|
||||
*/
|
||||
protected final void setName(String moduleType, int moduleNumber, int channel) {
|
||||
m_sendableImpl.setName(moduleType, moduleNumber, channel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getSubsystem() {
|
||||
return m_sendableImpl.getSubsystem();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setSubsystem(String subsystem) {
|
||||
m_sendableImpl.setSubsystem(subsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a child component.
|
||||
*
|
||||
* @param child child component
|
||||
*/
|
||||
protected final void addChild(Object child) {
|
||||
m_sendableImpl.addChild(child);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
setDisabled();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDescription() {
|
||||
return "PWM " + getChannel();
|
||||
}
|
||||
|
||||
/**
|
||||
* Optionally eliminate the deadband from a speed controller.
|
||||
*
|
||||
|
||||
@@ -12,7 +12,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
/**
|
||||
* Common base class for all PWM Speed Controllers.
|
||||
*/
|
||||
public abstract class PWMSpeedController extends SafePWM implements SpeedController {
|
||||
public abstract class PWMSpeedController extends PWM implements SpeedController {
|
||||
private boolean m_isInverted;
|
||||
|
||||
/**
|
||||
@@ -64,6 +64,11 @@ public abstract class PWMSpeedController extends SafePWM implements SpeedControl
|
||||
return m_isInverted;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disable() {
|
||||
setDisabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Write out the PID value as seen in the PIDOutput base object.
|
||||
*
|
||||
|
||||
@@ -27,9 +27,7 @@ import static java.util.Objects.requireNonNull;
|
||||
* channels (forward and reverse) to be used independently for something that does not care about
|
||||
* voltage polarity (like a solenoid).
|
||||
*/
|
||||
public class Relay extends SendableBase implements MotorSafety {
|
||||
private MotorSafetyHelper m_safetyHelper;
|
||||
|
||||
public class Relay extends MotorSafety implements Sendable, AutoCloseable {
|
||||
/**
|
||||
* This class represents errors in trying to set relay values contradictory to the direction to
|
||||
* which the relay is set.
|
||||
@@ -95,6 +93,8 @@ public class Relay extends SendableBase implements MotorSafety {
|
||||
|
||||
private Direction m_direction;
|
||||
|
||||
private final SendableImpl m_sendableImpl;
|
||||
|
||||
/**
|
||||
* Common relay initialization method. This code is common to all Relay constructors and
|
||||
* initializes the relay and reserves all resources that need to be locked. Initially the relay is
|
||||
@@ -113,8 +113,7 @@ public class Relay extends SendableBase implements MotorSafety {
|
||||
HAL.report(tResourceType.kResourceType_Relay, m_channel + 128);
|
||||
}
|
||||
|
||||
m_safetyHelper = new MotorSafetyHelper(this);
|
||||
m_safetyHelper.setSafetyEnabled(false);
|
||||
setSafetyEnabled(false);
|
||||
|
||||
setName("Relay", m_channel);
|
||||
}
|
||||
@@ -126,6 +125,8 @@ public class Relay extends SendableBase implements MotorSafety {
|
||||
* @param direction The direction that the Relay object will control.
|
||||
*/
|
||||
public Relay(final int channel, Direction direction) {
|
||||
m_sendableImpl = new SendableImpl(true);
|
||||
|
||||
m_channel = channel;
|
||||
m_direction = requireNonNull(direction, "Null Direction was given");
|
||||
initRelay();
|
||||
@@ -143,7 +144,7 @@ public class Relay extends SendableBase implements MotorSafety {
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
super.close();
|
||||
m_sendableImpl.close();
|
||||
freeRelay();
|
||||
}
|
||||
|
||||
@@ -166,6 +167,56 @@ public class Relay extends SendableBase implements MotorSafety {
|
||||
m_reverseHandle = 0;
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getName() {
|
||||
return m_sendableImpl.getName();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setName(String name) {
|
||||
m_sendableImpl.setName(name);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param channel The channel number the device is plugged into
|
||||
*/
|
||||
protected final void setName(String moduleType, int channel) {
|
||||
m_sendableImpl.setName(moduleType, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a module and channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param moduleNumber The number of the particular module type
|
||||
* @param channel The channel number the device is plugged into (usually PWM)
|
||||
*/
|
||||
protected final void setName(String moduleType, int moduleNumber, int channel) {
|
||||
m_sendableImpl.setName(moduleType, moduleNumber, channel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getSubsystem() {
|
||||
return m_sendableImpl.getSubsystem();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setSubsystem(String subsystem) {
|
||||
m_sendableImpl.setSubsystem(subsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a child component.
|
||||
*
|
||||
* @param child child component
|
||||
*/
|
||||
protected final void addChild(Object child) {
|
||||
m_sendableImpl.addChild(child);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the relay state.
|
||||
*
|
||||
@@ -276,36 +327,11 @@ public class Relay extends SendableBase implements MotorSafety {
|
||||
return m_channel;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
@Override
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
set(Value.kOff);
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDescription() {
|
||||
return "Relay ID " + getChannel();
|
||||
|
||||
@@ -26,9 +26,7 @@ import static java.util.Objects.requireNonNull;
|
||||
*/
|
||||
@Deprecated
|
||||
@SuppressWarnings({"PMD.GodClass", "PMD.TooManyMethods"})
|
||||
public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
protected MotorSafetyHelper m_safetyHelper;
|
||||
|
||||
public class RobotDrive extends MotorSafety implements AutoCloseable {
|
||||
/**
|
||||
* The location of a motor on the robot for the purpose of driving.
|
||||
*/
|
||||
@@ -76,7 +74,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
m_frontRightMotor = null;
|
||||
m_rearRightMotor = new Talon(rightMotorChannel);
|
||||
m_allocatedSpeedControllers = true;
|
||||
setupMotorSafety();
|
||||
setSafetyEnabled(true);
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
@@ -99,7 +97,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
m_frontLeftMotor = new Talon(frontLeftMotor);
|
||||
m_frontRightMotor = new Talon(frontRightMotor);
|
||||
m_allocatedSpeedControllers = true;
|
||||
setupMotorSafety();
|
||||
setSafetyEnabled(true);
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
@@ -123,7 +121,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
m_sensitivity = kDefaultSensitivity;
|
||||
m_maxOutput = kDefaultMaxOutput;
|
||||
m_allocatedSpeedControllers = false;
|
||||
setupMotorSafety();
|
||||
setSafetyEnabled(true);
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
@@ -145,7 +143,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
m_sensitivity = kDefaultSensitivity;
|
||||
m_maxOutput = kDefaultMaxOutput;
|
||||
m_allocatedSpeedControllers = false;
|
||||
setupMotorSafety();
|
||||
setSafetyEnabled(true);
|
||||
drive(0, 0);
|
||||
}
|
||||
|
||||
@@ -480,9 +478,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
|
||||
m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput);
|
||||
|
||||
if (m_safetyHelper != null) {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -524,9 +520,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
|
||||
m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput);
|
||||
|
||||
if (m_safetyHelper != null) {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -566,9 +560,7 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
}
|
||||
m_rearRightMotor.set(-limit(rightOutput) * m_maxOutput);
|
||||
|
||||
if (m_safetyHelper != null) {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -689,31 +681,6 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
@Override
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDescription() {
|
||||
return "Robot Drive";
|
||||
@@ -733,15 +700,8 @@ public class RobotDrive implements MotorSafety, AutoCloseable {
|
||||
if (m_rearRightMotor != null) {
|
||||
m_rearRightMotor.stopMotor();
|
||||
}
|
||||
if (m_safetyHelper != null) {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
}
|
||||
|
||||
private void setupMotorSafety() {
|
||||
m_safetyHelper = new MotorSafetyHelper(this);
|
||||
m_safetyHelper.setExpiration(kDefaultExpirationTime);
|
||||
m_safetyHelper.setSafetyEnabled(true);
|
||||
feed();
|
||||
}
|
||||
|
||||
protected int getNumMotors() {
|
||||
|
||||
@@ -1,112 +0,0 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* 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;
|
||||
|
||||
/**
|
||||
* Manages a PWM object.
|
||||
*/
|
||||
public class SafePWM extends PWM implements MotorSafety {
|
||||
private final MotorSafetyHelper m_safetyHelper;
|
||||
|
||||
/**
|
||||
* Constructor for a SafePWM object taking a channel number.
|
||||
*
|
||||
* @param channel The channel number to be used for the underlying PWM object. 0-9 are on-board,
|
||||
* 10-19 are on the MXP port.
|
||||
*/
|
||||
public SafePWM(final int channel) {
|
||||
super(channel);
|
||||
|
||||
m_safetyHelper = new MotorSafetyHelper(this);
|
||||
m_safetyHelper.setExpiration(0.0);
|
||||
m_safetyHelper.setSafetyEnabled(false);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the expiration time for the PWM object.
|
||||
*
|
||||
* @param timeout The timeout (in seconds) for this motor object
|
||||
*/
|
||||
@Override
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return the expiration time for the PWM object.
|
||||
*
|
||||
* @return The expiration time value.
|
||||
*/
|
||||
@Override
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if the PWM object is currently alive or stopped due to a timeout.
|
||||
*
|
||||
* @return a bool value that is true if the motor has NOT timed out and should still be running.
|
||||
*/
|
||||
@Override
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the motor associated with this PWM object. This is called by the MotorSafetyHelper object
|
||||
* when it has a timeout for this PWM and needs to stop it from running.
|
||||
*/
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
disable();
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if motor safety is enabled for this object.
|
||||
*
|
||||
* @return True if motor safety is enforced for this object
|
||||
*/
|
||||
@Override
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Feed the MotorSafety timer. This method is called by the subclass motor whenever it updates its
|
||||
* speed, thereby resetting the timeout value.
|
||||
*
|
||||
* @deprecated Use {@link #feed()} instead.
|
||||
*/
|
||||
@Deprecated
|
||||
@SuppressWarnings("MethodName")
|
||||
public void Feed() {
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Feed the MotorSafety timer. This method is called by the subclass motor whenever it updates its
|
||||
* speed, thereby resetting the timeout value.
|
||||
*/
|
||||
public void feed() {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDescription() {
|
||||
return "PWM " + getChannel();
|
||||
}
|
||||
|
||||
public void disable() {
|
||||
setDisabled();
|
||||
}
|
||||
}
|
||||
101
wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java
Normal file
101
wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java
Normal file
@@ -0,0 +1,101 @@
|
||||
/*----------------------------------------------------------------------------*/
|
||||
/* Copyright (c) 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.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
|
||||
|
||||
/**
|
||||
* The base interface for objects that can be sent over the network through network tables.
|
||||
*/
|
||||
public class SendableImpl implements Sendable, AutoCloseable {
|
||||
private String m_name = "";
|
||||
private String m_subsystem = "Ungrouped";
|
||||
|
||||
/**
|
||||
* Creates an instance of the sensor base.
|
||||
*/
|
||||
public SendableImpl() {
|
||||
this(true);
|
||||
}
|
||||
|
||||
/**
|
||||
* Creates an instance of the sensor base.
|
||||
*
|
||||
* @param addLiveWindow if true, add this Sendable to LiveWindow
|
||||
*/
|
||||
public SendableImpl(boolean addLiveWindow) {
|
||||
if (addLiveWindow) {
|
||||
LiveWindow.add(this);
|
||||
}
|
||||
}
|
||||
|
||||
@Deprecated
|
||||
public void free() {
|
||||
close();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
LiveWindow.remove(this);
|
||||
}
|
||||
|
||||
@Override
|
||||
public synchronized String getName() {
|
||||
return m_name;
|
||||
}
|
||||
|
||||
@Override
|
||||
public synchronized void setName(String name) {
|
||||
m_name = name;
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param channel The channel number the device is plugged into
|
||||
*/
|
||||
public void setName(String moduleType, int channel) {
|
||||
setName(moduleType + "[" + channel + "]");
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a module and channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param moduleNumber The number of the particular module type
|
||||
* @param channel The channel number the device is plugged into (usually PWM)
|
||||
*/
|
||||
public void setName(String moduleType, int moduleNumber, int channel) {
|
||||
setName(moduleType + "[" + moduleNumber + "," + channel + "]");
|
||||
}
|
||||
|
||||
@Override
|
||||
public synchronized String getSubsystem() {
|
||||
return m_subsystem;
|
||||
}
|
||||
|
||||
@Override
|
||||
public synchronized void setSubsystem(String subsystem) {
|
||||
m_subsystem = subsystem;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a child component.
|
||||
*
|
||||
* @param child child component
|
||||
*/
|
||||
public void addChild(Object child) {
|
||||
LiveWindow.addChild(this, child);
|
||||
}
|
||||
}
|
||||
@@ -191,7 +191,7 @@ public class DifferentialDrive extends RobotDriveBase {
|
||||
m_leftMotor.set(limit(leftMotorOutput) * m_maxOutput);
|
||||
m_rightMotor.set(limit(rightMotorOutput) * m_maxOutput * m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -275,7 +275,7 @@ public class DifferentialDrive extends RobotDriveBase {
|
||||
m_leftMotor.set(leftMotorOutput * m_maxOutput);
|
||||
m_rightMotor.set(rightMotorOutput * m_maxOutput * m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -323,7 +323,7 @@ public class DifferentialDrive extends RobotDriveBase {
|
||||
m_leftMotor.set(leftSpeed * m_maxOutput);
|
||||
m_rightMotor.set(rightSpeed * m_maxOutput * m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -379,7 +379,7 @@ public class DifferentialDrive extends RobotDriveBase {
|
||||
public void stopMotor() {
|
||||
m_leftMotor.stopMotor();
|
||||
m_rightMotor.stopMotor();
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -162,7 +162,7 @@ public class KilloughDrive extends RobotDriveBase {
|
||||
m_rightMotor.set(wheelSpeeds[MotorType.kRight.value] * m_maxOutput);
|
||||
m_backMotor.set(wheelSpeeds[MotorType.kBack.value] * m_maxOutput);
|
||||
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -193,7 +193,7 @@ public class KilloughDrive extends RobotDriveBase {
|
||||
m_leftMotor.stopMotor();
|
||||
m_rightMotor.stopMotor();
|
||||
m_backMotor.stopMotor();
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -148,7 +148,7 @@ public class MecanumDrive extends RobotDriveBase {
|
||||
m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput
|
||||
* m_rightSideInvertMultiplier);
|
||||
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -197,7 +197,7 @@ public class MecanumDrive extends RobotDriveBase {
|
||||
m_frontRightMotor.stopMotor();
|
||||
m_rearLeftMotor.stopMotor();
|
||||
m_rearRightMotor.stopMotor();
|
||||
m_safetyHelper.feed();
|
||||
feed();
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -8,19 +8,20 @@
|
||||
package edu.wpi.first.wpilibj.drive;
|
||||
|
||||
import edu.wpi.first.wpilibj.MotorSafety;
|
||||
import edu.wpi.first.wpilibj.MotorSafetyHelper;
|
||||
import edu.wpi.first.wpilibj.SendableBase;
|
||||
import edu.wpi.first.wpilibj.Sendable;
|
||||
import edu.wpi.first.wpilibj.SendableImpl;
|
||||
|
||||
/**
|
||||
* Common base class for drive platforms.
|
||||
*/
|
||||
public abstract class RobotDriveBase extends SendableBase implements MotorSafety {
|
||||
public abstract class RobotDriveBase extends MotorSafety implements Sendable, AutoCloseable {
|
||||
public static final double kDefaultDeadband = 0.02;
|
||||
public static final double kDefaultMaxOutput = 1.0;
|
||||
|
||||
protected double m_deadband = kDefaultDeadband;
|
||||
protected double m_maxOutput = kDefaultMaxOutput;
|
||||
protected MotorSafetyHelper m_safetyHelper = new MotorSafetyHelper(this);
|
||||
|
||||
private final SendableImpl m_sendableImpl;
|
||||
|
||||
/**
|
||||
* The location of a motor on the robot for the purpose of driving.
|
||||
@@ -37,11 +38,71 @@ public abstract class RobotDriveBase extends SendableBase implements MotorSafety
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* RobotDriveBase constructor.
|
||||
*/
|
||||
public RobotDriveBase() {
|
||||
m_safetyHelper.setSafetyEnabled(true);
|
||||
m_sendableImpl = new SendableImpl(true);
|
||||
|
||||
setSafetyEnabled(true);
|
||||
setName("RobotDriveBase");
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
m_sendableImpl.close();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getName() {
|
||||
return m_sendableImpl.getName();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setName(String name) {
|
||||
m_sendableImpl.setName(name);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param channel The channel number the device is plugged into
|
||||
*/
|
||||
protected final void setName(String moduleType, int channel) {
|
||||
m_sendableImpl.setName(moduleType, channel);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of the sensor with a module and channel number.
|
||||
*
|
||||
* @param moduleType A string that defines the module name in the label for the value
|
||||
* @param moduleNumber The number of the particular module type
|
||||
* @param channel The channel number the device is plugged into (usually PWM)
|
||||
*/
|
||||
protected final void setName(String moduleType, int moduleNumber, int channel) {
|
||||
m_sendableImpl.setName(moduleType, moduleNumber, channel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized String getSubsystem() {
|
||||
return m_sendableImpl.getSubsystem();
|
||||
}
|
||||
|
||||
@Override
|
||||
public final synchronized void setSubsystem(String subsystem) {
|
||||
m_sendableImpl.setSubsystem(subsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
* Add a child component.
|
||||
*
|
||||
* @param child child component
|
||||
*/
|
||||
protected final void addChild(Object child) {
|
||||
m_sendableImpl.addChild(child);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the deadband applied to the drive inputs (e.g., joystick values).
|
||||
*
|
||||
@@ -70,40 +131,15 @@ public abstract class RobotDriveBase extends SendableBase implements MotorSafety
|
||||
/**
|
||||
* Feed the motor safety object. Resets the timer that will stop the motors if it completes.
|
||||
*
|
||||
* @see MotorSafetyHelper#feed()
|
||||
* @see MotorSafety#feed()
|
||||
*/
|
||||
public void feedWatchdog() {
|
||||
m_safetyHelper.feed();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setExpiration(double timeout) {
|
||||
m_safetyHelper.setExpiration(timeout);
|
||||
}
|
||||
|
||||
@Override
|
||||
public double getExpiration() {
|
||||
return m_safetyHelper.getExpiration();
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean isAlive() {
|
||||
return m_safetyHelper.isAlive();
|
||||
feed();
|
||||
}
|
||||
|
||||
@Override
|
||||
public abstract void stopMotor();
|
||||
|
||||
@Override
|
||||
public boolean isSafetyEnabled() {
|
||||
return m_safetyHelper.isSafetyEnabled();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setSafetyEnabled(boolean enabled) {
|
||||
m_safetyHelper.setSafetyEnabled(enabled);
|
||||
}
|
||||
|
||||
@Override
|
||||
public abstract String getDescription();
|
||||
|
||||
|
||||
Reference in New Issue
Block a user