mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpilib] Remove Jaguar (and other) motor controllers (#8298)
https://community.firstinspires.org/2025-robot-rules-preview-for-2026
This commit is contained in:
@@ -32,10 +32,6 @@
|
||||
<Bug pattern="AT_STALE_THREAD_WRITE_OF_PRIMITIVE" />
|
||||
<Class name="edu.wpi.first.wpilibj.Ultrasonic" />
|
||||
</Match>
|
||||
<Match>
|
||||
<Bug pattern="AT_STALE_THREAD_WRITE_OF_PRIMITIVE" />
|
||||
<Class name="edu.wpi.first.wpilibj.motorcontrol.NidecBrushless" />
|
||||
</Match>
|
||||
<Match>
|
||||
<Bug pattern="AT_STALE_THREAD_WRITE_OF_PRIMITIVE" />
|
||||
<Class name="edu.wpi.first.wpilibj2.command.CommandScheduler" />
|
||||
|
||||
@@ -1,20 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#include "frc/motorcontrol/DMC60.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
|
||||
using namespace frc;
|
||||
|
||||
DMC60::DMC60(int channel) : PWMMotorController("DMC60", channel) {
|
||||
m_pwm.SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms);
|
||||
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
|
||||
m_pwm.SetSpeed(0.0);
|
||||
m_pwm.SetZeroLatch();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_DigilentDMC60, GetChannel() + 1);
|
||||
}
|
||||
@@ -1,20 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#include "frc/motorcontrol/Jaguar.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
|
||||
using namespace frc;
|
||||
|
||||
Jaguar::Jaguar(int channel) : PWMMotorController("Jaguar", channel) {
|
||||
m_pwm.SetBounds(2.31_ms, 1.55_ms, 1.507_ms, 1.454_ms, 0.697_ms);
|
||||
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
|
||||
m_pwm.SetSpeed(0.0);
|
||||
m_pwm.SetZeroLatch();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel() + 1);
|
||||
}
|
||||
@@ -1,20 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#include "frc/motorcontrol/SD540.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
|
||||
using namespace frc;
|
||||
|
||||
SD540::SD540(int channel) : PWMMotorController("SD540", channel) {
|
||||
m_pwm.SetBounds(2.05_ms, 1.55_ms, 1.5_ms, 1.44_ms, 0.94_ms);
|
||||
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_1X);
|
||||
m_pwm.SetSpeed(0.0);
|
||||
m_pwm.SetZeroLatch();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel() + 1);
|
||||
}
|
||||
@@ -1,20 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#include "frc/motorcontrol/Victor.h"
|
||||
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
|
||||
using namespace frc;
|
||||
|
||||
Victor::Victor(int channel) : PWMMotorController("Victor", channel) {
|
||||
m_pwm.SetBounds(2.027_ms, 1.525_ms, 1.507_ms, 1.49_ms, 1.026_ms);
|
||||
m_pwm.SetPeriodMultiplier(PWM::kPeriodMultiplier_2X);
|
||||
m_pwm.SetSpeed(0.0);
|
||||
m_pwm.SetZeroLatch();
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel() + 1);
|
||||
}
|
||||
@@ -1,43 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/motorcontrol/PWMMotorController.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* Digilent DMC 60 Motor Controller with PWM control.
|
||||
*
|
||||
* Note that the DMC 60 uses the following bounds for PWM values. These
|
||||
* values should work reasonably well for most controllers, but if users
|
||||
* experience issues such as asymmetric behavior around the deadband or
|
||||
* inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the DMC 60 User
|
||||
* Manual available from Digilent.
|
||||
*
|
||||
* \li 2.004ms = full "forward"
|
||||
* \li 1.520ms = the "high end" of the deadband range
|
||||
* \li 1.500ms = center of the deadband range (off)
|
||||
* \li 1.480ms = the "low end" of the deadband range
|
||||
* \li 0.997ms = full "reverse"
|
||||
*/
|
||||
class DMC60 : public PWMMotorController {
|
||||
public:
|
||||
/**
|
||||
* Constructor for a DMC 60 connected via PWM.
|
||||
*
|
||||
* @param channel The PWM channel that the DMC 60 is attached to. 0-9 are
|
||||
* on-board, 10-19 are on the MXP port
|
||||
*/
|
||||
explicit DMC60(int channel);
|
||||
|
||||
DMC60(DMC60&&) = default;
|
||||
DMC60& operator=(DMC60&&) = default;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -1,43 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/motorcontrol/PWMMotorController.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* Luminary Micro / Vex Robotics Jaguar Motor Controller with PWM control.
|
||||
*
|
||||
* Note that the Jaguar uses the following bounds for PWM values. These
|
||||
* values should work reasonably well for most controllers, but if users
|
||||
* experience issues such as asymmetric behavior around the deadband or
|
||||
* inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the Jaguar User
|
||||
* Manual available from Luminary Micro / Vex Robotics.
|
||||
*
|
||||
* \li 2.310ms = full "forward"
|
||||
* \li 1.550ms = the "high end" of the deadband range
|
||||
* \li 1.507ms = center of the deadband range (off)
|
||||
* \li 1.454ms = the "low end" of the deadband range
|
||||
* \li 0.697ms = full "reverse"
|
||||
*/
|
||||
class Jaguar : public PWMMotorController {
|
||||
public:
|
||||
/**
|
||||
* Constructor for a Jaguar connected via PWM.
|
||||
*
|
||||
* @param channel The PWM channel that the Jaguar is attached to. 0-9 are
|
||||
* on-board, 10-19 are on the MXP port
|
||||
*/
|
||||
explicit Jaguar(int channel);
|
||||
|
||||
Jaguar(Jaguar&&) = default;
|
||||
Jaguar& operator=(Jaguar&&) = default;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -1,43 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/motorcontrol/PWMMotorController.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* Mindsensors SD540 Motor Controller with PWM control.
|
||||
*
|
||||
* Note that the SD540 uses the following bounds for PWM values. These
|
||||
* values should work reasonably well for most controllers, but if users
|
||||
* experience issues such as asymmetric behavior around the deadband or
|
||||
* inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the SD540 User
|
||||
* Manual available from Mindsensors.
|
||||
*
|
||||
* \li 2.050ms = full "forward"
|
||||
* \li 1.550ms = the "high end" of the deadband range
|
||||
* \li 1.500ms = center of the deadband range (off)
|
||||
* \li 1.440ms = the "low end" of the deadband range
|
||||
* \li 0.940ms = full "reverse"
|
||||
*/
|
||||
class SD540 : public PWMMotorController {
|
||||
public:
|
||||
/**
|
||||
* Constructor for a SD540 connected via PWM.
|
||||
*
|
||||
* @param channel The PWM channel that the SD540 is attached to. 0-9 are
|
||||
* on-board, 10-19 are on the MXP port
|
||||
*/
|
||||
explicit SD540(int channel);
|
||||
|
||||
SD540(SD540&&) = default;
|
||||
SD540& operator=(SD540&&) = default;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -1,43 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibc/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "frc/motorcontrol/PWMMotorController.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
/**
|
||||
* Vex Robotics Victor 888 Motor Controller with PWM control.
|
||||
*
|
||||
* Note that the Victor 888 uses the following bounds for PWM values. These
|
||||
* values should work reasonably well for most controllers, but if users
|
||||
* experience issues such as asymmetric behavior around the deadband or
|
||||
* inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the Victor 888 User
|
||||
* Manual available from Vex Robotics.
|
||||
*
|
||||
* \li 2.027ms = full "forward"
|
||||
* \li 1.525ms = the "high end" of the deadband range
|
||||
* \li 1.507ms = center of the deadband range (off)
|
||||
* \li 1.490ms = the "low end" of the deadband range
|
||||
* \li 1.026ms = full "reverse"
|
||||
*/
|
||||
class Victor : public PWMMotorController {
|
||||
public:
|
||||
/**
|
||||
* Constructor for a Victor 888 connected via PWM.
|
||||
*
|
||||
* @param channel The PWM channel that the Victor 888 is attached to. 0-9 are
|
||||
* on-board, 10-19 are on the MXP port
|
||||
*/
|
||||
explicit Victor(int channel);
|
||||
|
||||
Victor(Victor&&) = default;
|
||||
Victor& operator=(Victor&&) = default;
|
||||
};
|
||||
|
||||
} // namespace frc
|
||||
@@ -1,86 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "frc/motorcontrol/NidecBrushless.h"
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <fmt/format.h>
|
||||
#include <hal/FRCUsageReporting.h>
|
||||
#include <wpi/sendable/SendableBuilder.h>
|
||||
#include <wpi/sendable/SendableRegistry.h>
|
||||
|
||||
using namespace frc;
|
||||
|
||||
WPI_IGNORE_DEPRECATED
|
||||
|
||||
NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
|
||||
: m_dio(dioChannel), m_pwm(pwmChannel) {
|
||||
wpi::SendableRegistry::AddChild(this, &m_dio);
|
||||
wpi::SendableRegistry::AddChild(this, &m_pwm);
|
||||
SetExpiration(0_s);
|
||||
SetSafetyEnabled(false);
|
||||
|
||||
// the dio controls the output (in PWM mode)
|
||||
m_dio.SetPWMRate(15625);
|
||||
m_dio.EnablePWM(0.5);
|
||||
|
||||
HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel + 1);
|
||||
wpi::SendableRegistry::AddLW(this, "Nidec Brushless", pwmChannel);
|
||||
}
|
||||
|
||||
WPI_UNIGNORE_DEPRECATED
|
||||
|
||||
void NidecBrushless::Set(double speed) {
|
||||
if (!m_disabled) {
|
||||
m_speed = speed;
|
||||
m_dio.UpdateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
|
||||
m_pwm.SetAlwaysHighMode();
|
||||
}
|
||||
Feed();
|
||||
}
|
||||
|
||||
double NidecBrushless::Get() const {
|
||||
return m_speed;
|
||||
}
|
||||
|
||||
void NidecBrushless::SetInverted(bool isInverted) {
|
||||
m_isInverted = isInverted;
|
||||
}
|
||||
|
||||
bool NidecBrushless::GetInverted() const {
|
||||
return m_isInverted;
|
||||
}
|
||||
|
||||
void NidecBrushless::Disable() {
|
||||
m_disabled = true;
|
||||
m_dio.UpdateDutyCycle(0.5);
|
||||
m_pwm.SetDisabled();
|
||||
}
|
||||
|
||||
void NidecBrushless::Enable() {
|
||||
m_disabled = false;
|
||||
}
|
||||
|
||||
void NidecBrushless::StopMotor() {
|
||||
m_dio.UpdateDutyCycle(0.5);
|
||||
m_pwm.SetDisabled();
|
||||
}
|
||||
|
||||
std::string NidecBrushless::GetDescription() const {
|
||||
return fmt::format("Nidec {}", GetChannel());
|
||||
}
|
||||
|
||||
int NidecBrushless::GetChannel() const {
|
||||
return m_pwm.GetChannel();
|
||||
}
|
||||
|
||||
void NidecBrushless::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Nidec Brushless");
|
||||
builder.SetActuator(true);
|
||||
builder.SetSafeState([=, this] { StopMotor(); });
|
||||
builder.AddDoubleProperty(
|
||||
"Value", [=, this] { return Get(); },
|
||||
[=, this](double value) { Set(value); });
|
||||
}
|
||||
@@ -1,103 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
|
||||
#include <wpi/deprecated.h>
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "frc/DigitalOutput.h"
|
||||
#include "frc/MotorSafety.h"
|
||||
#include "frc/PWM.h"
|
||||
#include "frc/motorcontrol/MotorController.h"
|
||||
|
||||
namespace frc {
|
||||
|
||||
WPI_IGNORE_DEPRECATED
|
||||
|
||||
/**
|
||||
* Nidec Brushless Motor.
|
||||
*/
|
||||
class NidecBrushless : public MotorController,
|
||||
public MotorSafety,
|
||||
public wpi::Sendable,
|
||||
public wpi::SendableHelper<NidecBrushless> {
|
||||
public:
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param pwmChannel The PWM channel that the Nidec Brushless controller is
|
||||
* attached to. 0-9 are on-board, 10-19 are on the MXP port.
|
||||
* @param dioChannel The DIO channel that the Nidec Brushless controller is
|
||||
* attached to. 0-9 are on-board, 10-25 are on the MXP port.
|
||||
*/
|
||||
NidecBrushless(int pwmChannel, int dioChannel);
|
||||
|
||||
~NidecBrushless() override = default;
|
||||
|
||||
NidecBrushless(NidecBrushless&&) = default;
|
||||
NidecBrushless& operator=(NidecBrushless&&) = default;
|
||||
|
||||
// MotorController interface
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
|
||||
* the value for the FPGA.
|
||||
*
|
||||
* @param speed The speed value between -1.0 and 1.0 to set.
|
||||
*/
|
||||
void Set(double speed) override;
|
||||
|
||||
/**
|
||||
* Get the recently set value of the PWM.
|
||||
*
|
||||
* @return The most recently set value for the PWM between -1.0 and 1.0.
|
||||
*/
|
||||
double Get() const override;
|
||||
|
||||
void SetInverted(bool isInverted) override;
|
||||
|
||||
bool GetInverted() const override;
|
||||
|
||||
/**
|
||||
* Disable the motor. The Enable() function must be called to re-enable the
|
||||
* motor.
|
||||
*/
|
||||
void Disable() override;
|
||||
|
||||
/**
|
||||
* Re-enable the motor after Disable() has been called. The Set() function
|
||||
* must be called to set a new motor speed.
|
||||
*/
|
||||
void Enable();
|
||||
|
||||
// MotorSafety interface
|
||||
void StopMotor() override;
|
||||
std::string GetDescription() const override;
|
||||
|
||||
/**
|
||||
* Gets the channel number associated with the object.
|
||||
*
|
||||
* @return The channel number.
|
||||
*/
|
||||
int GetChannel() const;
|
||||
|
||||
// Sendable interface
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
private:
|
||||
bool m_isInverted = false;
|
||||
bool m_disabled = false;
|
||||
DigitalOutput m_dio;
|
||||
PWM m_pwm;
|
||||
double m_speed = 0.0;
|
||||
};
|
||||
|
||||
WPI_UNIGNORE_DEPRECATED
|
||||
|
||||
} // namespace frc
|
||||
@@ -204,14 +204,10 @@ enum class BuiltInWidgets {
|
||||
* The motor controller will be controllable from the dashboard when test mode
|
||||
* is enabled, but will otherwise be view-only. <br>Supported types: <ul>
|
||||
* <li>PWMMotorController</li>
|
||||
* <li>DMC60</li>
|
||||
* <li>Jaguar</li>
|
||||
* <li>PWMTalonSRX</li>
|
||||
* <li>PWMVictorSPX</li>
|
||||
* <li>SD540</li>
|
||||
* <li>Spark</li>
|
||||
* <li>Talon</li>
|
||||
* <li>Victor</li>
|
||||
* <li>VictorSP</li>
|
||||
* <li>MotorControllerGroup</li>
|
||||
* <li>Any custom subclass of {@code SpeedContorller}</li>
|
||||
|
||||
@@ -9,9 +9,7 @@
|
||||
|
||||
#include "TestBench.h"
|
||||
#include "frc/Timer.h"
|
||||
#include "frc/motorcontrol/Jaguar.h"
|
||||
#include "frc/motorcontrol/Talon.h"
|
||||
#include "frc/motorcontrol/Victor.h"
|
||||
|
||||
static constexpr auto kMotorDelay = 2.5_s;
|
||||
|
||||
@@ -23,8 +21,8 @@ class CounterTest : public testing::Test {
|
||||
frc::Counter m_victorCounter{TestBench::kVictorEncoderChannelA};
|
||||
frc::Counter m_jaguarCounter{TestBench::kJaguarEncoderChannelA};
|
||||
frc::Talon m_talon{TestBench::kVictorChannel};
|
||||
frc::Victor m_victor{TestBench::kTalonChannel};
|
||||
frc::Jaguar m_jaguar{TestBench::kJaguarChannel};
|
||||
frc::Talon m_victor{TestBench::kTalonChannel};
|
||||
frc::Talon m_jaguar{TestBench::kJaguarChannel};
|
||||
|
||||
void Reset() {
|
||||
m_talonCounter.Reset();
|
||||
|
||||
@@ -13,7 +13,7 @@
|
||||
#include "frc/DMASample.h"
|
||||
#include "frc/DigitalOutput.h"
|
||||
#include "frc/Timer.h"
|
||||
#include "frc/motorcontrol/Jaguar.h"
|
||||
#include "frc/motorcontrol/Talon.h"
|
||||
|
||||
using namespace frc;
|
||||
|
||||
@@ -24,7 +24,7 @@ class DMATest : public testing::Test {
|
||||
AnalogInput m_analogInput{TestBench::kAnalogOutputChannel};
|
||||
AnalogOutput m_analogOutput{TestBench::kFakeAnalogOutputChannel};
|
||||
DigitalOutput m_manualTrigger{TestBench::kLoop1InputChannel};
|
||||
Jaguar m_pwm{TestBench::kFakePwmOutput};
|
||||
Talon m_pwm{TestBench::kFakePwmOutput};
|
||||
DMA m_dma;
|
||||
|
||||
void SetUp() override {
|
||||
|
||||
@@ -14,9 +14,7 @@
|
||||
#include "frc/Timer.h"
|
||||
#include "frc/controller/PIDController.h"
|
||||
#include "frc/filter/LinearFilter.h"
|
||||
#include "frc/motorcontrol/Jaguar.h"
|
||||
#include "frc/motorcontrol/Talon.h"
|
||||
#include "frc/motorcontrol/Victor.h"
|
||||
|
||||
enum MotorEncoderTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
|
||||
|
||||
@@ -53,13 +51,13 @@ class MotorEncoderTest : public testing::TestWithParam<MotorEncoderTestType> {
|
||||
MotorEncoderTest() {
|
||||
switch (GetParam()) {
|
||||
case TEST_VICTOR:
|
||||
m_motorController = new frc::Victor(TestBench::kVictorChannel);
|
||||
m_motorController = new frc::Talon(TestBench::kVictorChannel);
|
||||
m_encoder = new frc::Encoder(TestBench::kVictorEncoderChannelA,
|
||||
TestBench::kVictorEncoderChannelB);
|
||||
break;
|
||||
|
||||
case TEST_JAGUAR:
|
||||
m_motorController = new frc::Jaguar(TestBench::kJaguarChannel);
|
||||
m_motorController = new frc::Talon(TestBench::kJaguarChannel);
|
||||
m_encoder = new frc::Encoder(TestBench::kJaguarEncoderChannelA,
|
||||
TestBench::kJaguarEncoderChannelB);
|
||||
break;
|
||||
|
||||
@@ -9,9 +9,7 @@
|
||||
#include "TestBench.h"
|
||||
#include "frc/Encoder.h"
|
||||
#include "frc/Timer.h"
|
||||
#include "frc/motorcontrol/Jaguar.h"
|
||||
#include "frc/motorcontrol/Talon.h"
|
||||
#include "frc/motorcontrol/Victor.h"
|
||||
|
||||
enum MotorInvertingTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
|
||||
|
||||
@@ -45,13 +43,13 @@ class MotorInvertingTest
|
||||
MotorInvertingTest() {
|
||||
switch (GetParam()) {
|
||||
case TEST_VICTOR:
|
||||
m_motorController = new frc::Victor(TestBench::kVictorChannel);
|
||||
m_motorController = new frc::Talon(TestBench::kVictorChannel);
|
||||
m_encoder = new frc::Encoder(TestBench::kVictorEncoderChannelA,
|
||||
TestBench::kVictorEncoderChannelB);
|
||||
break;
|
||||
|
||||
case TEST_JAGUAR:
|
||||
m_motorController = new frc::Jaguar(TestBench::kJaguarChannel);
|
||||
m_motorController = new frc::Talon(TestBench::kJaguarChannel);
|
||||
m_encoder = new frc::Encoder(TestBench::kJaguarEncoderChannelA,
|
||||
TestBench::kJaguarEncoderChannelB);
|
||||
break;
|
||||
|
||||
@@ -1,30 +1,4 @@
|
||||
[
|
||||
{
|
||||
"name": "DMC60",
|
||||
"Manufacturer": "Digilent",
|
||||
"DisplayName": "DMC 60",
|
||||
"ResourceName": "DigilentDMC60",
|
||||
"pulse_width_ms": {
|
||||
"max": 2.004,
|
||||
"deadbandMax": 1.520,
|
||||
"center": 1.500,
|
||||
"deadbandMin": 1.480,
|
||||
"min": 0.997
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "Jaguar",
|
||||
"Manufacturer": "Luminary Micro / Vex Robotics",
|
||||
"DisplayName": "Jaguar",
|
||||
"ResourceName": "Jaguar",
|
||||
"pulse_width_ms": {
|
||||
"max": 2.310,
|
||||
"deadbandMax": 1.550,
|
||||
"center": 1.507,
|
||||
"deadbandMin": 1.454,
|
||||
"min": 0.697
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "PWMSparkFlex",
|
||||
"Manufacturer": "REV Robotics",
|
||||
@@ -103,19 +77,6 @@
|
||||
"min": 0.997
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "SD540",
|
||||
"Manufacturer": "Mindsensors",
|
||||
"DisplayName": "SD540",
|
||||
"ResourceName": "MindsensorsSD540",
|
||||
"pulse_width_ms": {
|
||||
"max": 2.05,
|
||||
"deadbandMax": 1.55,
|
||||
"center": 1.50,
|
||||
"deadbandMin": 1.44,
|
||||
"min": 0.94
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "Spark",
|
||||
"Manufacturer": "REV Robotics",
|
||||
@@ -142,20 +103,6 @@
|
||||
"min": 0.989
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "Victor",
|
||||
"Manufacturer": "Vex Robotics",
|
||||
"DisplayName": "Victor 888",
|
||||
"ResourceName": "Victor",
|
||||
"PeriodMultiplier": 2,
|
||||
"pulse_width_ms": {
|
||||
"max": 2.027,
|
||||
"deadbandMax": 1.525,
|
||||
"center": 1.507,
|
||||
"deadbandMin": 1.490,
|
||||
"min": 1.026
|
||||
}
|
||||
},
|
||||
{
|
||||
"name": "VictorSP",
|
||||
"Manufacturer": "Vex Robotics",
|
||||
|
||||
@@ -1,48 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.wpilibj.motorcontrol;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.PWM;
|
||||
|
||||
/**
|
||||
* Digilent DMC 60 Motor Controller.
|
||||
*
|
||||
* <p>Note that the DMC 60 uses the following bounds for PWM values. These values should work
|
||||
* reasonably well for most controllers, but if users experience issues such as asymmetric behavior
|
||||
* around the deadband or inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the DMC 60 User Manual available from
|
||||
* Digilent.
|
||||
*
|
||||
* <ul>
|
||||
* <li>2.004ms = full "forward"
|
||||
* <li>1.520ms = the "high end" of the deadband range
|
||||
* <li>1.500ms = center of the deadband range (off)
|
||||
* <li>1.480ms = the "low end" of the deadband range
|
||||
* <li>0.997ms = full "reverse"
|
||||
* </ul>
|
||||
*/
|
||||
public class DMC60 extends PWMMotorController {
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the DMC 60 is attached to. 0-9 are on-board, 10-19
|
||||
* are on the MXP port
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public DMC60(final int channel) {
|
||||
super("DMC60", channel);
|
||||
|
||||
m_pwm.setBoundsMicroseconds(2004, 1520, 1500, 1480, 997);
|
||||
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
|
||||
m_pwm.setSpeed(0.0);
|
||||
m_pwm.setZeroLatch();
|
||||
|
||||
HAL.report(tResourceType.kResourceType_DigilentDMC60, getChannel() + 1);
|
||||
}
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.wpilibj.motorcontrol;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.PWM;
|
||||
|
||||
/**
|
||||
* Luminary Micro / Vex Robotics Jaguar Motor Controller.
|
||||
*
|
||||
* <p>Note that the Jaguar uses the following bounds for PWM values. These values should work
|
||||
* reasonably well for most controllers, but if users experience issues such as asymmetric behavior
|
||||
* around the deadband or inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the Jaguar User Manual available from
|
||||
* Luminary Micro / Vex Robotics.
|
||||
*
|
||||
* <ul>
|
||||
* <li>2.310ms = full "forward"
|
||||
* <li>1.550ms = the "high end" of the deadband range
|
||||
* <li>1.507ms = center of the deadband range (off)
|
||||
* <li>1.454ms = the "low end" of the deadband range
|
||||
* <li>0.697ms = full "reverse"
|
||||
* </ul>
|
||||
*/
|
||||
public class Jaguar extends PWMMotorController {
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19
|
||||
* are on the MXP port
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Jaguar(final int channel) {
|
||||
super("Jaguar", channel);
|
||||
|
||||
m_pwm.setBoundsMicroseconds(2310, 1550, 1507, 1454, 697);
|
||||
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
|
||||
m_pwm.setSpeed(0.0);
|
||||
m_pwm.setZeroLatch();
|
||||
|
||||
HAL.report(tResourceType.kResourceType_Jaguar, getChannel() + 1);
|
||||
}
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.wpilibj.motorcontrol;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.PWM;
|
||||
|
||||
/**
|
||||
* Mindsensors SD540 Motor Controller.
|
||||
*
|
||||
* <p>Note that the SD540 uses the following bounds for PWM values. These values should work
|
||||
* reasonably well for most controllers, but if users experience issues such as asymmetric behavior
|
||||
* around the deadband or inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the SD540 User Manual available from
|
||||
* Mindsensors.
|
||||
*
|
||||
* <ul>
|
||||
* <li>2.050ms = full "forward"
|
||||
* <li>1.550ms = the "high end" of the deadband range
|
||||
* <li>1.500ms = center of the deadband range (off)
|
||||
* <li>1.440ms = the "low end" of the deadband range
|
||||
* <li>0.940ms = full "reverse"
|
||||
* </ul>
|
||||
*/
|
||||
public class SD540 extends PWMMotorController {
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19
|
||||
* are on the MXP port
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public SD540(final int channel) {
|
||||
super("SD540", channel);
|
||||
|
||||
m_pwm.setBoundsMicroseconds(2050, 1550, 1500, 1440, 940);
|
||||
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k1X);
|
||||
m_pwm.setSpeed(0.0);
|
||||
m_pwm.setZeroLatch();
|
||||
|
||||
HAL.report(tResourceType.kResourceType_MindsensorsSD540, getChannel() + 1);
|
||||
}
|
||||
}
|
||||
@@ -1,48 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
// THIS FILE WAS AUTO-GENERATED BY ./wpilibj/generate_pwm_motor_controllers.py. DO NOT MODIFY
|
||||
|
||||
package edu.wpi.first.wpilibj.motorcontrol;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.PWM;
|
||||
|
||||
/**
|
||||
* Vex Robotics Victor 888 Motor Controller.
|
||||
*
|
||||
* <p>Note that the Victor 888 uses the following bounds for PWM values. These values should work
|
||||
* reasonably well for most controllers, but if users experience issues such as asymmetric behavior
|
||||
* around the deadband or inability to saturate the controller in either direction, calibration is
|
||||
* recommended. The calibration procedure can be found in the Victor 888 User Manual available from
|
||||
* Vex Robotics.
|
||||
*
|
||||
* <ul>
|
||||
* <li>2.027ms = full "forward"
|
||||
* <li>1.525ms = the "high end" of the deadband range
|
||||
* <li>1.507ms = center of the deadband range (off)
|
||||
* <li>1.490ms = the "low end" of the deadband range
|
||||
* <li>1.026ms = full "reverse"
|
||||
* </ul>
|
||||
*/
|
||||
public class Victor extends PWMMotorController {
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param channel The PWM channel that the Victor 888 is attached to. 0-9 are on-board, 10-19
|
||||
* are on the MXP port
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public Victor(final int channel) {
|
||||
super("Victor", channel);
|
||||
|
||||
m_pwm.setBoundsMicroseconds(2027, 1525, 1507, 1490, 1026);
|
||||
m_pwm.setPeriodMultiplier(PWM.PeriodMultiplier.k2X);
|
||||
m_pwm.setSpeed(0.0);
|
||||
m_pwm.setZeroLatch();
|
||||
|
||||
HAL.report(tResourceType.kResourceType_Victor, getChannel() + 1);
|
||||
}
|
||||
}
|
||||
@@ -1,145 +0,0 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj.motorcontrol;
|
||||
|
||||
import edu.wpi.first.hal.FRCNetComm.tResourceType;
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj.MotorSafety;
|
||||
import edu.wpi.first.wpilibj.PWM;
|
||||
|
||||
/** Nidec Brushless Motor. */
|
||||
@SuppressWarnings("removal")
|
||||
public class NidecBrushless extends MotorSafety
|
||||
implements MotorController, 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;
|
||||
|
||||
/**
|
||||
* Constructor.
|
||||
*
|
||||
* @param pwmChannel The PWM channel that the Nidec Brushless controller is attached to. 0-9 are
|
||||
* on-board, 10-19 are on the MXP port
|
||||
* @param dioChannel The DIO channel that the Nidec Brushless controller is attached to. 0-9 are
|
||||
* on-board, 10-25 are on the MXP port
|
||||
*/
|
||||
@SuppressWarnings("this-escape")
|
||||
public NidecBrushless(final int pwmChannel, final int dioChannel) {
|
||||
setSafetyEnabled(false);
|
||||
|
||||
// the dio controls the output (in PWM mode)
|
||||
m_dio = new DigitalOutput(dioChannel);
|
||||
SendableRegistry.addChild(this, m_dio);
|
||||
m_dio.setPWMRate(15625);
|
||||
m_dio.enablePWM(0.5);
|
||||
|
||||
// the pwm enables the controller
|
||||
m_pwm = new PWM(pwmChannel);
|
||||
SendableRegistry.addChild(this, m_pwm);
|
||||
|
||||
HAL.report(tResourceType.kResourceType_NidecBrushless, pwmChannel + 1);
|
||||
SendableRegistry.addLW(this, "Nidec Brushless", pwmChannel);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void close() {
|
||||
SendableRegistry.remove(this);
|
||||
m_dio.close();
|
||||
m_pwm.close();
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the PWM value.
|
||||
*
|
||||
* <p>The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the
|
||||
* FPGA.
|
||||
*
|
||||
* @param speed The speed value between -1.0 and 1.0 to set.
|
||||
*/
|
||||
@Override
|
||||
public void set(double speed) {
|
||||
if (!m_disabled) {
|
||||
m_speed = speed;
|
||||
m_dio.updateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
|
||||
m_pwm.setAlwaysHighMode();
|
||||
}
|
||||
|
||||
feed();
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the recently set value of the PWM.
|
||||
*
|
||||
* @return The most recently set value for the PWM between -1.0 and 1.0.
|
||||
*/
|
||||
@Override
|
||||
public double get() {
|
||||
return m_speed;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setInverted(boolean isInverted) {
|
||||
m_isInverted = isInverted;
|
||||
}
|
||||
|
||||
@Override
|
||||
public boolean getInverted() {
|
||||
return m_isInverted;
|
||||
}
|
||||
|
||||
/**
|
||||
* 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() {
|
||||
m_dio.updateDutyCycle(0.5);
|
||||
m_pwm.setDisabled();
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDescription() {
|
||||
return "Nidec " + getChannel();
|
||||
}
|
||||
|
||||
/** Disable the motor. The enable() function must be called to re-enable the motor. */
|
||||
@Override
|
||||
public void disable() {
|
||||
m_disabled = true;
|
||||
m_dio.updateDutyCycle(0.5);
|
||||
m_pwm.setDisabled();
|
||||
}
|
||||
|
||||
/**
|
||||
* Re-enable the motor after disable() has been called. The set() function must be called to set a
|
||||
* new motor speed.
|
||||
*/
|
||||
public void enable() {
|
||||
m_disabled = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the channel number associated with the object.
|
||||
*
|
||||
* @return The channel number.
|
||||
*/
|
||||
public int getChannel() {
|
||||
return m_pwm.getChannel();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Nidec Brushless");
|
||||
builder.setActuator(true);
|
||||
builder.setSafeState(this::stopMotor);
|
||||
builder.addDoubleProperty("Value", this::get, this::set);
|
||||
}
|
||||
}
|
||||
@@ -250,17 +250,13 @@ public enum BuiltInWidgets implements WidgetType {
|
||||
*
|
||||
* <ul>
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.PWMMotorController}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.DMC60}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.Jaguar}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.PWMTalonFX}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.PWMTalonSRX}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.PWMVenom}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.SD540}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.Spark}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.Talon}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.Victor}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.VictorSP}
|
||||
* <li>{@link edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup}
|
||||
* <li>Any custom subclass of {@code MotorController}
|
||||
|
||||
@@ -9,8 +9,8 @@ import static org.junit.Assert.assertTrue;
|
||||
|
||||
import edu.wpi.first.math.util.Units;
|
||||
import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Jaguar;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMMotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Talon;
|
||||
import edu.wpi.first.wpilibj.test.AbstractComsSetup;
|
||||
import edu.wpi.first.wpilibj.test.TestBench;
|
||||
import java.util.ArrayList;
|
||||
@@ -40,7 +40,7 @@ public class DMATest extends AbstractComsSetup {
|
||||
public void setUp() {
|
||||
m_analogIO = TestBench.getAnalogCrossConnectFixture();
|
||||
m_manualTrigger = new DigitalOutput(7);
|
||||
m_pwm = new Jaguar(14);
|
||||
m_pwm = new Talon(14);
|
||||
m_dma = new DMA();
|
||||
m_dmaSample = new DMASample();
|
||||
|
||||
|
||||
@@ -15,9 +15,7 @@ import edu.wpi.first.wpilibj.fixtures.DIOCrossConnectFixture;
|
||||
import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
|
||||
import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture;
|
||||
import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Jaguar;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Talon;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Victor;
|
||||
import java.io.PrintStream;
|
||||
import java.util.ArrayList;
|
||||
import java.util.Collection;
|
||||
@@ -92,16 +90,16 @@ public final class TestBench {
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs a new set of objects representing a connected set of Victor controlled Motors and an
|
||||
* Constructs a new set of objects representing a connected set of Talon controlled Motors and an
|
||||
* encoder.
|
||||
*
|
||||
* @return a freshly allocated Victor, Encoder pair
|
||||
* @return a freshly allocated Talon, Encoder pair
|
||||
*/
|
||||
public static MotorEncoderFixture<Victor> getVictorPair() {
|
||||
public static MotorEncoderFixture<Talon> getVictorPair() {
|
||||
return new MotorEncoderFixture<>() {
|
||||
@Override
|
||||
protected Victor giveMotorController() {
|
||||
return new Victor(kVictorChannel);
|
||||
protected Talon giveMotorController() {
|
||||
return new Talon(kVictorChannel);
|
||||
}
|
||||
|
||||
@Override
|
||||
@@ -122,16 +120,16 @@ public final class TestBench {
|
||||
}
|
||||
|
||||
/**
|
||||
* Constructs a new set of objects representing a connected set of Jaguar controlled Motors and an
|
||||
* Constructs a new set of objects representing a connected set of Talon controlled Motors and an
|
||||
* encoder.
|
||||
*
|
||||
* @return a freshly allocated Jaguar, Encoder pair
|
||||
* @return a freshly allocated Talon, Encoder pair
|
||||
*/
|
||||
public static MotorEncoderFixture<Jaguar> getJaguarPair() {
|
||||
public static MotorEncoderFixture<Talon> getJaguarPair() {
|
||||
return new MotorEncoderFixture<>() {
|
||||
@Override
|
||||
protected Jaguar giveMotorController() {
|
||||
return new Jaguar(kJaguarChannel);
|
||||
protected Talon giveMotorController() {
|
||||
return new Talon(kJaguarChannel);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
Reference in New Issue
Block a user