Compare commits

...

34 Commits

Author SHA1 Message Date
Peter Johnson
b1357cace7 Fix LiveWindow SetEnabled C++ std::bad_function_call (#2281)
It was missing a null check.
2020-01-16 00:34:51 -08:00
Thad House
37202b6f28 Add missing SensorUtil::kAnalogOutputs (#2276) 2020-01-15 21:34:28 -08:00
Thad House
2ac0d52960 Remove AnalogTrigger::SetDutyCycle (#2275) 2020-01-15 21:33:58 -08:00
Thad House
dbe1e6f466 Fix missing SetDutyCycleSimDevice on Rio (#2274) 2020-01-15 21:33:35 -08:00
Chris Russell
a61fcbd68d Make Button class concrete (#2244) 2020-01-15 18:59:51 -08:00
Thad House
fe597eeba1 Fix SPI DIO count for sim (#2272)
Only 26 DIO were detectable, not 31.
2020-01-15 18:58:14 -08:00
Jonathan Leitschuh
e213a47efd Official Gradle Wrapper Validation GitHub Action (#2273)
See: https://github.com/gradle/wrapper-validation-action
2020-01-15 14:21:50 -08:00
Peter Johnson
dcb96cb50c TrajectoryGenerator: Allow replacement of error reporting function (C++) (#2267)
C++ version of #2234.
2020-01-13 20:36:16 -08:00
Austin Shalit
60d48fec57 Fix Java static colors having zero values (#2269)
Also add test for this.
2020-01-13 12:21:44 -08:00
Austin Shalit
ee8475d21f Run wpiformat (#2270) 2020-01-13 12:19:08 -08:00
Peter Johnson
f47e318131 C++ units: Interoperate with Windows headers min/max (#2268) 2020-01-12 22:52:36 -08:00
Thad House
cb66bcca3c Add callback handlers for LiveWindow (#2053)
Fixes #2223
2020-01-12 22:37:24 -08:00
Simon Abrelat
73302f6162 Fix color name typos (#2265) 2020-01-12 22:15:19 -08:00
Oblarg
cba21a768f Fix C++ JoystickButton and POVButton (#2259)
C++ JoystickButton and POVButton were both nonfunctional due to slicing when trigger passes itself by value to the button scheduler it creates.

Fix is to remove the virtual Get() method entirely and use only the m_isActive functor; since the subclass now passes the button condition back as a functor to the base class, in which it's stored as a member, it will now still work after being sliced.
2020-01-12 14:57:28 -08:00
Peter Johnson
822e75ec45 Simulator GUI: Handle save file having window size=0 (#2260)
This should never happen, but if it does, it's not recoverable without
either deleting imgui.ini or editing it manually.
2020-01-12 01:37:53 -08:00
Peter Johnson
108ddfa1b4 Fix Pi Camera auto exposure property name (#2258) 2020-01-11 15:04:29 -08:00
Prateek Machiraju
d4c8ee5915 Add Axis enum in XboxController (#2253) 2020-01-10 23:43:19 -08:00
Peter Johnson
ab9647ff5b CommandScheduler: Don't store NetworkTableEntry 2020-01-10 23:42:18 -08:00
Peter Johnson
6666d3be42 SendableBuilder: Allow multiple updateTable functions
This fixes cases like CommandScheduler not working when added to both
LiveWindow and SmartDashboard.
2020-01-10 23:42:18 -08:00
Peter Johnson
795086b4cf Fix Demangle when used standalone (#2256) 2020-01-10 23:41:40 -08:00
Peter Johnson
56765cf49a C++ CommandBase: Don't add to LiveWindow (#2255) 2020-01-10 20:37:49 -08:00
Peter Johnson
bf7012fa2d Fix new CommandScheduler.cancelAll() (#2251)
When called outside the run loop, it would result in a CME in Java.
2020-01-10 16:10:16 -08:00
Peter Johnson
10e8fdb724 Make C++ IterativeRobotBase and RobotBase constructor and destructor public (#2242) 2020-01-08 23:17:12 -08:00
Peter Johnson
790dc552ca Add quirks support for Pi camera (#2241)
- Valid video modes (native modes plus some low-res modes)
- Exposure setting
2020-01-07 20:21:28 -08:00
Peter Johnson
0ec8ed6c05 Make C++ controller using declarations public (#2240) 2020-01-06 23:30:47 -08:00
Tyler Veness
832693617f Add missing definition for PIDController::SetPID() (#2239)
Fixes #2238.
2020-01-06 21:17:16 -08:00
sciencewhiz
772ef8f961 Update Maven location to artifactory (#2235) 2020-01-06 20:13:42 -08:00
Peter Johnson
95b6cd2dd9 TrajectoryGenerator: Allow replacement of error reporting function (#2234)
This is needed to avoid use of DriverStation if used from desktop applications
such as PathWeaver.
2020-01-05 16:01:31 -08:00
sciencewhiz
ce1ac17dfb Remove experimental from new command example descriptions (#2226) 2020-01-04 19:57:31 -08:00
Thad House
b2f7a6b651 Add clarification to LED about length and # of drivers (#2231) 2020-01-04 19:57:10 -08:00
Peter Johnson
bedbef7999 Revert "Remove -no-module-directories flag from javadoc build (#2201)" (#2229)
This reverts commit f9a11cce5e.
2020-01-04 19:52:43 -08:00
Thad House
bc159a92a7 Default sim voltage to 12v, make user rails active (#2224) 2020-01-04 15:07:47 -08:00
Austin Shalit
f50d710a5e Make color ctor public (#2222) 2020-01-04 08:28:18 -08:00
Peter Johnson
bc8f68bec7 Add sim HAL_WaitForCachedControlData (#2221) 2020-01-03 22:38:45 -08:00
58 changed files with 568 additions and 289 deletions

View File

@@ -0,0 +1,10 @@
name: "Validate Gradle Wrapper"
on: [push]
jobs:
validation:
name: "Validation"
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v2
- uses: gradle/wrapper-validation-action@v1

View File

@@ -5,8 +5,8 @@ WPILib publishes its built artifacts to our Maven server for use by downstream p
## Repositories
We provide two repositories. These repositories are:
* (Release) https://first.wpi.edu/FRC/roborio/maven/release/
* (Development) https://first.wpi.edu/FRC/roborio/maven/development/
* (Release) https://frcmaven.wpi.edu/artifactory/release/
* (Development) https://frcmaven.wpi.edu/artifactory/development/
The release repository is where official WPILib releases are pushed.
The development repository is where development releases of every commit to [master](https://github.com/wpilibsuite/allwpilib/tree/master) is pushed.

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2020 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. */
@@ -102,7 +102,7 @@ static bool IsPercentageProperty(wpi::StringRef name) {
if (name.startswith("raw_")) name = name.substr(4);
return name == "brightness" || name == "contrast" || name == "saturation" ||
name == "hue" || name == "sharpness" || name == "gain" ||
name == "exposure_absolute";
name == "exposure_absolute" || name == "exposure_time_absolute";
}
static constexpr const int quirkLifeCamHd3000[] = {
@@ -112,6 +112,11 @@ static constexpr char const* quirkPS3EyePropExAuto = "auto_exposure";
static constexpr char const* quirkPS3EyePropExValue = "exposure";
static constexpr const int quirkPS3EyePropExAutoOn = 0;
static constexpr const int quirkPS3EyePropExAutoOff = 1;
static constexpr char const* quirkPiCameraPropExAuto = "auto_exposure";
static constexpr char const* quirkPiCameraPropExValue =
"exposure_time_absolute";
static constexpr const int quirkPiCameraPropExAutoOn = 0;
static constexpr const int quirkPiCameraPropExAutoOff = 1;
int UsbCameraImpl::RawToPercentage(const UsbCameraProperty& rawProp,
int rawValue) {
@@ -1112,6 +1117,25 @@ void UsbCameraImpl::DeviceCacheVideoModes() {
}
}
// The Pi camera reports mode ranges, which we don't currently handle, so only
// provide a set of discrete modes; list based on
// https://picamera.readthedocs.io/en/release-1.10/fov.html
if (modes.empty() && m_picamera) {
for (VideoMode::PixelFormat pixelFormat :
{VideoMode::kYUYV, VideoMode::kMJPEG, VideoMode::kBGR}) {
modes.emplace_back(pixelFormat, 1920, 1080, 30);
modes.emplace_back(pixelFormat, 2592, 1944, 15);
modes.emplace_back(pixelFormat, 1296, 972, 42);
modes.emplace_back(pixelFormat, 1296, 730, 49);
modes.emplace_back(pixelFormat, 640, 480, 90);
modes.emplace_back(pixelFormat, 320, 240, 90);
modes.emplace_back(pixelFormat, 160, 120, 90);
modes.emplace_back(pixelFormat, 640, 480, 60);
modes.emplace_back(pixelFormat, 320, 240, 60);
modes.emplace_back(pixelFormat, 160, 120, 60);
}
}
{
std::scoped_lock lock(m_mutex);
m_videoModes.swap(modes);
@@ -1192,6 +1216,7 @@ void UsbCameraImpl::SetQuirks() {
wpi::StringRef desc = GetDescription(descbuf);
m_lifecam_exposure =
desc.endswith("LifeCam HD-3000") || desc.endswith("LifeCam Cinema (TM)");
m_picamera = desc.startswith("mmal service");
int deviceNum = GetDeviceNum(m_path.c_str());
if (deviceNum >= 0) {
@@ -1248,7 +1273,9 @@ void UsbCameraImpl::SetExposureAuto(CS_Status* status) {
if (m_ps3eyecam_exposure) {
SetProperty(GetPropertyIndex(quirkPS3EyePropExAuto),
quirkPS3EyePropExAutoOn, status);
} else if (m_picamera) {
SetProperty(GetPropertyIndex(quirkPiCameraPropExAuto),
quirkPiCameraPropExAutoOn, status);
} else {
SetProperty(GetPropertyIndex(kPropExAuto), 3, status);
}
@@ -1258,6 +1285,9 @@ void UsbCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
if (m_ps3eyecam_exposure) {
SetProperty(GetPropertyIndex(quirkPS3EyePropExAuto),
quirkPS3EyePropExAutoOff, status); // manual
} else if (m_picamera) {
SetProperty(GetPropertyIndex(quirkPiCameraPropExAuto),
quirkPiCameraPropExAutoOff, status); // manual
} else {
SetProperty(GetPropertyIndex(kPropExAuto), 1, status); // manual
}
@@ -1267,6 +1297,9 @@ void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
if (m_ps3eyecam_exposure) {
SetProperty(GetPropertyIndex(quirkPS3EyePropExAuto),
quirkPS3EyePropExAutoOff, status); // manual
} else if (m_picamera) {
SetProperty(GetPropertyIndex(quirkPiCameraPropExAuto),
quirkPiCameraPropExAutoOff, status); // manual
} else {
SetProperty(GetPropertyIndex(kPropExAuto), 1, status); // manual
}
@@ -1277,6 +1310,8 @@ void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
}
if (m_ps3eyecam_exposure) {
SetProperty(GetPropertyIndex(quirkPS3EyePropExValue), value, status);
} else if (m_picamera) {
SetProperty(GetPropertyIndex(quirkPiCameraPropExValue), value, status);
} else {
SetProperty(GetPropertyIndex(kPropExValue), value, status);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2020 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. */
@@ -166,6 +166,7 @@ class UsbCameraImpl : public SourceImpl {
// Quirks
bool m_lifecam_exposure{false}; // Microsoft LifeCam exposure
bool m_ps3eyecam_exposure{false}; // PS3 Eyecam exposure
bool m_picamera{false}; // Raspberry Pi camera
//
// Variables protected by m_mutex

View File

@@ -125,6 +125,7 @@ task generateJavaDocs(type: Javadoc) {
ext.entryPoint = "$destinationDir/index.html"
if (JavaVersion.current().isJava11Compatible()) {
options.addBooleanOption('-no-module-directories', true)
doLast {
// This is a work-around for https://bugs.openjdk.java.net/browse/JDK-8211194. Can be removed once that issue is fixed on JDK's side
// Since JDK 11, package-list is missing from javadoc output files and superseded by element-list file, but a lot of external tools still need it

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -75,6 +75,9 @@ void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle) {
dutyCycleHandles->Free(dutyCycleHandle);
}
void HAL_SetDutyCycleSimDevice(HAL_EncoderHandle handle,
HAL_SimDeviceHandle device) {}
int32_t HAL_GetDutyCycleFrequency(HAL_DutyCycleHandle dutyCycleHandle,
int32_t* status) {
auto dutyCycle = dutyCycleHandles->Get(dutyCycleHandle);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -230,6 +230,10 @@ static int& GetThreadLocalLastCount() {
return lastCount;
}
void HAL_WaitForCachedControlData(void) {
HAL_WaitForCachedControlDataTimeout(0);
}
HAL_Bool HAL_WaitForCachedControlDataTimeout(double timeout) {
int& lastCount = GetThreadLocalLastCount();
std::unique_lock lock(newDSDataAvailableMutex);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2020 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. */
@@ -17,7 +17,7 @@ constexpr int32_t kNumAnalogOutputs = 2;
constexpr int32_t kNumCounters = 8;
constexpr int32_t kNumDigitalHeaders = 10;
constexpr int32_t kNumPWMHeaders = 10;
constexpr int32_t kNumDigitalChannels = 26;
constexpr int32_t kNumDigitalChannels = 31;
constexpr int32_t kNumPWMChannels = 20;
constexpr int32_t kNumDigitalPWMOutputs = 6;
constexpr int32_t kNumEncoders = 8;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -22,17 +22,17 @@ void InitializeRoboRioData() {
RoboRioData* hal::SimRoboRioData;
void RoboRioData::ResetData() {
fpgaButton.Reset(false);
vInVoltage.Reset(0.0);
vInVoltage.Reset(12.0);
vInCurrent.Reset(0.0);
userVoltage6V.Reset(6.0);
userCurrent6V.Reset(0.0);
userActive6V.Reset(false);
userActive6V.Reset(true);
userVoltage5V.Reset(5.0);
userCurrent5V.Reset(0.0);
userActive5V.Reset(false);
userActive5V.Reset(true);
userVoltage3V3.Reset(3.3);
userCurrent3V3.Reset(0.0);
userActive3V3.Reset(false);
userActive3V3.Reset(true);
userFaults6V.Reset(0);
userFaults5V.Reset(0);
userFaults3V3.Reset(0);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -30,22 +30,22 @@ class RoboRioData {
public:
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetFPGAButtonName> fpgaButton{false};
SimDataValue<double, HAL_MakeDouble, GetVInVoltageName> vInVoltage{0.0};
SimDataValue<double, HAL_MakeDouble, GetVInVoltageName> vInVoltage{12.0};
SimDataValue<double, HAL_MakeDouble, GetVInCurrentName> vInCurrent{0.0};
SimDataValue<double, HAL_MakeDouble, GetUserVoltage6VName> userVoltage6V{6.0};
SimDataValue<double, HAL_MakeDouble, GetUserCurrent6VName> userCurrent6V{0.0};
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetUserActive6VName> userActive6V{
false};
true};
SimDataValue<double, HAL_MakeDouble, GetUserVoltage5VName> userVoltage5V{5.0};
SimDataValue<double, HAL_MakeDouble, GetUserCurrent5VName> userCurrent5V{0.0};
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetUserActive5VName> userActive5V{
false};
true};
SimDataValue<double, HAL_MakeDouble, GetUserVoltage3V3Name> userVoltage3V3{
3.3};
SimDataValue<double, HAL_MakeDouble, GetUserCurrent3V3Name> userCurrent3V3{
0.0};
SimDataValue<HAL_Bool, HAL_MakeBoolean, GetUserActive3V3Name> userActive3V3{
false};
true};
SimDataValue<int32_t, HAL_MakeInt, GetUserFaults6VName> userFaults6V{0};
SimDataValue<int32_t, HAL_MakeInt, GetUserFaults5VName> userFaults5V{0};
SimDataValue<int32_t, HAL_MakeInt, GetUserFaults3V3Name> userFaults3V3{0};

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -301,6 +301,12 @@ bool HALSimGui::Initialize() {
// Set initial window settings
glfwWindowHint(GLFW_MAXIMIZED, gWindowMaximized ? GLFW_TRUE : GLFW_FALSE);
if (gWindowWidth == 0 || gWindowHeight == 0) {
gWindowWidth = 1280;
gWindowHeight = 720;
gWindowLoadedWidthHeight = false;
}
float windowScale = 1.0;
if (!gWindowLoadedWidthHeight) {
glfwWindowHint(GLFW_SCALE_TO_MONITOR, GLFW_TRUE);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -24,6 +24,7 @@ import edu.wpi.first.hal.HAL;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.wpilibj.RobotState;
import edu.wpi.first.wpilibj.Sendable;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
@@ -35,7 +36,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
* Subsystem#periodic()} methods to be called and for their default commands to be scheduled.
*/
@SuppressWarnings({"PMD.GodClass", "PMD.TooManyMethods", "PMD.TooManyFields"})
public final class CommandScheduler implements Sendable {
public final class CommandScheduler implements Sendable, AutoCloseable {
/**
* The Singleton Instance.
*/
@@ -70,11 +71,6 @@ public final class CommandScheduler implements Sendable {
private boolean m_disabled;
//NetworkTable entries for use in Sendable impl
private NetworkTableEntry m_namesEntry;
private NetworkTableEntry m_idsEntry;
private NetworkTableEntry m_cancelEntry;
//Lists of user-supplied actions to be executed on scheduling events for every command.
private final List<Consumer<Command>> m_initActions = new ArrayList<>();
private final List<Consumer<Command>> m_executeActions = new ArrayList<>();
@@ -91,6 +87,20 @@ public final class CommandScheduler implements Sendable {
CommandScheduler() {
HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand2_Scheduler);
SendableRegistry.addLW(this, "Scheduler");
LiveWindow.setEnabledListener(() -> {
disable();
cancelAll();
});
LiveWindow.setDisabledListener(() -> {
enable();
});
}
@Override
public void close() {
SendableRegistry.remove(this);
LiveWindow.setEnabledListener(null);
LiveWindow.setDisabledListener(null);
}
/**
@@ -375,7 +385,7 @@ public final class CommandScheduler implements Sendable {
* Cancels all commands that are currently scheduled.
*/
public void cancelAll() {
for (Command command : m_scheduledCommands.keySet()) {
for (Command command : m_scheduledCommands.keySet().toArray(new Command[0])) {
cancel(command);
}
}
@@ -473,12 +483,12 @@ public final class CommandScheduler implements Sendable {
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Scheduler");
m_namesEntry = builder.getEntry("Names");
m_idsEntry = builder.getEntry("Ids");
m_cancelEntry = builder.getEntry("Cancel");
final NetworkTableEntry namesEntry = builder.getEntry("Names");
final NetworkTableEntry idsEntry = builder.getEntry("Ids");
final NetworkTableEntry cancelEntry = builder.getEntry("Cancel");
builder.setUpdateTable(() -> {
if (m_namesEntry == null || m_idsEntry == null || m_cancelEntry == null) {
if (namesEntry == null || idsEntry == null || cancelEntry == null) {
return;
}
@@ -489,21 +499,21 @@ public final class CommandScheduler implements Sendable {
ids.put((double) command.hashCode(), command);
}
double[] toCancel = m_cancelEntry.getDoubleArray(new double[0]);
double[] toCancel = cancelEntry.getDoubleArray(new double[0]);
if (toCancel.length > 0) {
for (double hash : toCancel) {
cancel(ids.get(hash));
ids.remove(hash);
}
m_cancelEntry.setDoubleArray(new double[0]);
cancelEntry.setDoubleArray(new double[0]);
}
List<String> names = new ArrayList<>();
ids.values().forEach(command -> names.add(command.getName()));
m_namesEntry.setStringArray(names.toArray(new String[0]));
m_idsEntry.setNumberArray(ids.keySet().toArray(new Double[0]));
namesEntry.setStringArray(names.toArray(new String[0]));
idsEntry.setNumberArray(ids.keySet().toArray(new Double[0]));
});
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -23,7 +23,7 @@ import edu.wpi.first.wpilibj2.command.Subsystem;
* wrapper around Trigger with the method names renamed to fit the Button object use.
*/
@SuppressWarnings("PMD.TooManyMethods")
public abstract class Button extends Trigger {
public class Button extends Trigger {
/**
* Default constructor; creates a button that is never pressed (unless {@link Button#get()} is
* overridden).

View File

@@ -13,7 +13,7 @@
using namespace frc2;
CommandBase::CommandBase() {
frc::SendableRegistry::GetInstance().AddLW(this, GetTypeName(*this));
frc::SendableRegistry::GetInstance().Add(this, GetTypeName(*this));
}
void CommandBase::AddRequirements(

View File

@@ -9,12 +9,14 @@
#include <frc/RobotState.h>
#include <frc/WPIErrors.h>
#include <frc/livewindow/LiveWindow.h>
#include <frc/smartdashboard/SendableBuilder.h>
#include <frc/smartdashboard/SendableRegistry.h>
#include <hal/FRCUsageReporting.h>
#include <hal/HALBase.h>
#include <networktables/NetworkTableEntry.h>
#include <wpi/DenseMap.h>
#include <wpi/SmallVector.h>
#include "frc2/command/CommandGroupBase.h"
#include "frc2/command/CommandState.h"
@@ -42,11 +44,6 @@ class CommandScheduler::Impl {
bool disabled{false};
// NetworkTable entries for use in Sendable impl
nt::NetworkTableEntry namesEntry;
nt::NetworkTableEntry idsEntry;
nt::NetworkTableEntry cancelEntry;
// Lists of user-supplied actions to be executed on scheduling events for
// every command.
wpi::SmallVector<Action, 4> initActions;
@@ -71,9 +68,20 @@ CommandScheduler::CommandScheduler() : m_impl(new Impl) {
HAL_Report(HALUsageReporting::kResourceType_Command,
HALUsageReporting::kCommand2_Scheduler);
frc::SendableRegistry::GetInstance().AddLW(this, "Scheduler");
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = [this] {
this->Disable();
this->CancelAll();
};
scheduler->disabled = [this] { this->Enable(); };
}
CommandScheduler::~CommandScheduler() {}
CommandScheduler::~CommandScheduler() {
frc::SendableRegistry::GetInstance().Remove(this);
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = nullptr;
scheduler->disabled = nullptr;
}
CommandScheduler& CommandScheduler::GetInstance() {
static CommandScheduler scheduler;
@@ -310,9 +318,11 @@ void CommandScheduler::Cancel(std::initializer_list<Command*> commands) {
}
void CommandScheduler::CancelAll() {
wpi::SmallVector<Command*, 16> commands;
for (auto&& command : m_impl->scheduledCommands) {
Cancel(command.first);
commands.emplace_back(command.first);
}
Cancel(commands);
}
double CommandScheduler::TimeSinceScheduled(const Command* command) const {
@@ -379,14 +389,14 @@ void CommandScheduler::OnCommandFinish(Action action) {
void CommandScheduler::InitSendable(frc::SendableBuilder& builder) {
builder.SetSmartDashboardType("Scheduler");
m_impl->namesEntry = builder.GetEntry("Names");
m_impl->idsEntry = builder.GetEntry("Ids");
m_impl->cancelEntry = builder.GetEntry("Cancel");
auto namesEntry = builder.GetEntry("Names");
auto idsEntry = builder.GetEntry("Ids");
auto cancelEntry = builder.GetEntry("Cancel");
builder.SetUpdateTable([this] {
builder.SetUpdateTable([=] {
double tmp[1];
tmp[0] = 0;
auto toCancel = m_impl->cancelEntry.GetDoubleArray(tmp);
auto toCancel = cancelEntry.GetDoubleArray(tmp);
for (auto cancel : toCancel) {
uintptr_t ptrTmp = static_cast<uintptr_t>(cancel);
Command* command = reinterpret_cast<Command*>(ptrTmp);
@@ -394,7 +404,8 @@ void CommandScheduler::InitSendable(frc::SendableBuilder& builder) {
m_impl->scheduledCommands.end()) {
Cancel(command);
}
m_impl->cancelEntry.SetDoubleArray(wpi::ArrayRef<double>{});
nt::NetworkTableEntry(cancelEntry)
.SetDoubleArray(wpi::ArrayRef<double>{});
}
wpi::SmallVector<std::string, 8> names;
@@ -404,8 +415,8 @@ void CommandScheduler::InitSendable(frc::SendableBuilder& builder) {
uintptr_t ptrTmp = reinterpret_cast<uintptr_t>(command.first);
ids.emplace_back(static_cast<double>(ptrTmp));
}
m_impl->namesEntry.SetStringArray(names);
m_impl->idsEntry.SetDoubleArray(ids);
nt::NetworkTableEntry(namesEntry).SetStringArray(names);
nt::NetworkTableEntry(idsEntry).SetDoubleArray(ids);
});
}

View File

@@ -15,8 +15,8 @@ Trigger::Trigger(const Trigger& other) : m_isActive(other.m_isActive) {}
Trigger Trigger::WhenActive(Command* command, bool interruptible) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this, command, interruptible]() mutable {
bool pressed = Get();
[pressedLast = m_isActive(), *this, command, interruptible]() mutable {
bool pressed = m_isActive();
if (!pressedLast && pressed) {
command->Schedule(interruptible);
@@ -41,8 +41,8 @@ Trigger Trigger::WhenActive(std::function<void()> toRun,
Trigger Trigger::WhileActiveContinous(Command* command, bool interruptible) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this, command, interruptible]() mutable {
bool pressed = Get();
[pressedLast = m_isActive(), *this, command, interruptible]() mutable {
bool pressed = m_isActive();
if (pressed) {
command->Schedule(interruptible);
@@ -70,8 +70,8 @@ Trigger Trigger::WhileActiveContinous(std::function<void()> toRun,
Trigger Trigger::WhileActiveOnce(Command* command, bool interruptible) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this, command, interruptible]() mutable {
bool pressed = Get();
[pressedLast = m_isActive(), *this, command, interruptible]() mutable {
bool pressed = m_isActive();
if (!pressedLast && pressed) {
command->Schedule(interruptible);
@@ -86,8 +86,8 @@ Trigger Trigger::WhileActiveOnce(Command* command, bool interruptible) {
Trigger Trigger::WhenInactive(Command* command, bool interruptible) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this, command, interruptible]() mutable {
bool pressed = Get();
[pressedLast = m_isActive(), *this, command, interruptible]() mutable {
bool pressed = m_isActive();
if (pressedLast && !pressed) {
command->Schedule(interruptible);
@@ -111,8 +111,8 @@ Trigger Trigger::WhenInactive(std::function<void()> toRun,
Trigger Trigger::ToggleWhenActive(Command* command, bool interruptible) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this, command, interruptible]() mutable {
bool pressed = Get();
[pressedLast = m_isActive(), *this, command, interruptible]() mutable {
bool pressed = m_isActive();
if (!pressedLast && pressed) {
if (command->IsScheduled()) {
@@ -129,8 +129,8 @@ Trigger Trigger::ToggleWhenActive(Command* command, bool interruptible) {
Trigger Trigger::CancelWhenActive(Command* command) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this, command]() mutable {
bool pressed = Get();
[pressedLast = m_isActive(), *this, command]() mutable {
bool pressed = m_isActive();
if (!pressedLast && pressed) {
command->Cancel();

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -26,12 +26,8 @@ class JoystickButton : public Button {
* @param buttonNumber The number of the button on the joystic.
*/
explicit JoystickButton(frc::GenericHID* joystick, int buttonNumber)
: m_joystick{joystick}, m_buttonNumber{buttonNumber} {}
bool Get() const override { return m_joystick->GetRawButton(m_buttonNumber); }
private:
frc::GenericHID* m_joystick;
int m_buttonNumber;
: Button([joystick, buttonNumber] {
return joystick->GetRawButton(buttonNumber);
}) {}
};
} // namespace frc2

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -27,15 +27,8 @@ class POVButton : public Button {
* @param povNumber The number of the POV on the joystick.
*/
POVButton(frc::GenericHID* joystick, int angle, int povNumber = 0)
: m_joystick{joystick}, m_angle{angle}, m_povNumber{povNumber} {}
bool Get() const override {
return m_joystick->GetPOV(m_povNumber) == m_angle;
}
private:
frc::GenericHID* m_joystick;
int m_angle;
int m_povNumber;
: Button([joystick, angle, povNumber] {
joystick->GetPOV(povNumber) == angle;
}) {}
};
} // namespace frc2

View File

@@ -47,13 +47,6 @@ class Trigger {
Trigger(const Trigger& other);
/**
* Returns whether the trigger is active. Can be overridden by a subclass.
*
* @return Whether the trigger is active.
*/
virtual bool Get() const { return m_isActive(); }
/**
* Binds a command to start when the trigger becomes active. Takes a
* raw pointer, and so is non-owning; users are responsible for the lifespan
@@ -79,11 +72,11 @@ class Trigger {
Command, std::remove_reference_t<T>>>>
Trigger WhenActive(T&& command, bool interruptible = true) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this,
[pressedLast = m_isActive(), *this,
command = std::make_unique<std::remove_reference_t<T>>(
std::forward<T>(command)),
interruptible]() mutable {
bool pressed = Get();
bool pressed = m_isActive();
if (!pressedLast && pressed) {
command->Schedule(interruptible);
@@ -138,11 +131,11 @@ class Trigger {
Command, std::remove_reference_t<T>>>>
Trigger WhileActiveContinous(T&& command, bool interruptible = true) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this,
[pressedLast = m_isActive(), *this,
command = std::make_unique<std::remove_reference_t<T>>(
std::forward<T>(command)),
interruptible]() mutable {
bool pressed = Get();
bool pressed = m_isActive();
if (pressed) {
command->Schedule(interruptible);
@@ -198,11 +191,11 @@ class Trigger {
Command, std::remove_reference_t<T>>>>
Trigger WhileActiveOnce(T&& command, bool interruptible = true) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this,
[pressedLast = m_isActive(), *this,
command = std::make_unique<std::remove_reference_t<T>>(
std::forward<T>(command)),
interruptible]() mutable {
bool pressed = Get();
bool pressed = m_isActive();
if (!pressedLast && pressed) {
command->Schedule(interruptible);
@@ -240,11 +233,11 @@ class Trigger {
Command, std::remove_reference_t<T>>>>
Trigger WhenInactive(T&& command, bool interruptible = true) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this,
[pressedLast = m_isActive(), *this,
command = std::make_unique<std::remove_reference_t<T>>(
std::forward<T>(command)),
interruptible]() mutable {
bool pressed = Get();
bool pressed = m_isActive();
if (pressedLast && !pressed) {
command->Schedule(interruptible);
@@ -298,11 +291,11 @@ class Trigger {
Command, std::remove_reference_t<T>>>>
Trigger ToggleWhenActive(T&& command, bool interruptible = true) {
CommandScheduler::GetInstance().AddButton(
[pressedLast = Get(), *this,
[pressedLast = m_isActive(), *this,
command = std::make_unique<std::remove_reference_t<T>>(
std::forward<T>(command)),
interruptible]() mutable {
bool pressed = Get();
bool pressed = m_isActive();
if (!pressedLast && pressed) {
if (command->IsScheduled()) {
@@ -333,7 +326,7 @@ class Trigger {
* @return A trigger which is active when both component triggers are active.
*/
Trigger operator&&(Trigger rhs) {
return Trigger([*this, rhs] { return Get() && rhs.Get(); });
return Trigger([*this, rhs] { return m_isActive() && rhs.m_isActive(); });
}
/**
@@ -342,7 +335,7 @@ class Trigger {
* @return A trigger which is active when either component trigger is active.
*/
Trigger operator||(Trigger rhs) {
return Trigger([*this, rhs] { return Get() || rhs.Get(); });
return Trigger([*this, rhs] { return m_isActive() || rhs.m_isActive(); });
}
/**
@@ -352,7 +345,7 @@ class Trigger {
* and vice-versa.
*/
Trigger operator!() {
return Trigger([*this] { return !Get(); });
return Trigger([*this] { return !m_isActive(); });
}
private:

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2018-2020 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. */

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2018-2020 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. */
@@ -54,4 +54,22 @@ class SchedulerTest extends CommandTestBase {
scheduler.registerSubsystem(system);
assertDoesNotThrow(() -> scheduler.unregisterSubsystem(system));
}
@Test
void schedulerCancelAllTest() {
CommandScheduler scheduler = new CommandScheduler();
Counter counter = new Counter();
scheduler.onCommandInterrupt(command -> counter.increment());
Command command = new WaitCommand(10);
Command command2 = new WaitCommand(10);
scheduler.schedule(command);
scheduler.schedule(command2);
scheduler.cancelAll();
assertEquals(counter.m_counter, 2);
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -54,3 +54,21 @@ TEST_F(SchedulerTest, UnregisterSubsystemTest) {
EXPECT_NO_FATAL_FAILURE(scheduler.UnregisterSubsystem(&system));
}
TEST_F(SchedulerTest, SchedulerCancelAllTest) {
CommandScheduler scheduler = GetScheduler();
RunCommand command([] {}, {});
RunCommand command2([] {}, {});
int counter = 0;
scheduler.OnCommandInterrupt([&counter](const Command&) { counter++; });
scheduler.Schedule(&command);
scheduler.Schedule(&command2);
scheduler.Run();
scheduler.CancelAll();
EXPECT_EQ(counter, 2);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -17,6 +17,7 @@ import edu.wpi.first.hal.HAL;
import edu.wpi.first.networktables.NetworkTableEntry;
import edu.wpi.first.wpilibj.Sendable;
import edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
import edu.wpi.first.wpilibj.smartdashboard.SendableRegistry;
@@ -81,9 +82,6 @@ public final class Scheduler implements Sendable, AutoCloseable {
*/
@SuppressWarnings({"PMD.LooseCoupling", "PMD.UseArrayListInsteadOfVector"})
private final Vector<Command> m_additions = new Vector<>();
private NetworkTableEntry m_namesEntry;
private NetworkTableEntry m_idsEntry;
private NetworkTableEntry m_cancelEntry;
/**
* A list of all {@link edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler Buttons}. It is
* created lazily.
@@ -98,11 +96,20 @@ public final class Scheduler implements Sendable, AutoCloseable {
private Scheduler() {
HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
SendableRegistry.addLW(this, "Scheduler");
LiveWindow.setEnabledListener(() -> {
disable();
removeAll();
});
LiveWindow.setDisabledListener(() -> {
enable();
});
}
@Override
public void close() {
SendableRegistry.remove(this);
LiveWindow.setEnabledListener(null);
LiveWindow.setDisabledListener(null);
}
/**
@@ -319,13 +326,13 @@ public final class Scheduler implements Sendable, AutoCloseable {
@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("Scheduler");
m_namesEntry = builder.getEntry("Names");
m_idsEntry = builder.getEntry("Ids");
m_cancelEntry = builder.getEntry("Cancel");
final NetworkTableEntry namesEntry = builder.getEntry("Names");
final NetworkTableEntry idsEntry = builder.getEntry("Ids");
final NetworkTableEntry cancelEntry = builder.getEntry("Cancel");
builder.setUpdateTable(() -> {
if (m_namesEntry != null && m_idsEntry != null && m_cancelEntry != null) {
if (namesEntry != null && idsEntry != null && cancelEntry != null) {
// Get the commands to cancel
double[] toCancel = m_cancelEntry.getDoubleArray(new double[0]);
double[] toCancel = cancelEntry.getDoubleArray(new double[0]);
if (toCancel.length > 0) {
for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
for (double d : toCancel) {
@@ -334,7 +341,7 @@ public final class Scheduler implements Sendable, AutoCloseable {
}
}
}
m_cancelEntry.setDoubleArray(new double[0]);
cancelEntry.setDoubleArray(new double[0]);
}
if (m_runningCommandsChanged) {
@@ -351,8 +358,8 @@ public final class Scheduler implements Sendable, AutoCloseable {
ids[number] = e.getData().hashCode();
number++;
}
m_namesEntry.setStringArray(commands);
m_idsEntry.setDoubleArray(ids);
namesEntry.setStringArray(commands);
idsEntry.setDoubleArray(ids);
}
}
});

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2011-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2011-2020 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. */
@@ -20,6 +20,7 @@
#include "frc/buttons/ButtonScheduler.h"
#include "frc/commands/Command.h"
#include "frc/commands/Subsystem.h"
#include "frc/livewindow/LiveWindow.h"
#include "frc/smartdashboard/SendableBuilder.h"
#include "frc/smartdashboard/SendableRegistry.h"
@@ -198,9 +199,20 @@ Scheduler::Scheduler() : m_impl(new Impl) {
HAL_Report(HALUsageReporting::kResourceType_Command,
HALUsageReporting::kCommand_Scheduler);
SendableRegistry::GetInstance().AddLW(this, "Scheduler");
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = [this] {
this->SetEnabled(false);
this->RemoveAll();
};
scheduler->disabled = [this] { this->SetEnabled(true); };
}
Scheduler::~Scheduler() {}
Scheduler::~Scheduler() {
SendableRegistry::GetInstance().Remove(this);
auto scheduler = frc::LiveWindow::GetInstance();
scheduler->enabled = nullptr;
scheduler->disabled = nullptr;
}
void Scheduler::Impl::Remove(Command* command) {
if (!commands.erase(command)) return;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -21,6 +21,7 @@ using namespace frc;
const int SensorUtil::kDigitalChannels = HAL_GetNumDigitalChannels();
const int SensorUtil::kAnalogInputs = HAL_GetNumAnalogInputs();
const int SensorUtil::kAnalogOutputs = HAL_GetNumAnalogOutputs();
const int SensorUtil::kSolenoidChannels = HAL_GetNumSolenoidChannels();
const int SensorUtil::kSolenoidModules = HAL_GetNumPCMModules();
const int SensorUtil::kPwmChannels = HAL_GetNumPWMChannels();

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2020 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. */
@@ -17,25 +17,25 @@ XboxController::XboxController(int port) : GenericHID(port) {
double XboxController::GetX(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawAxis(0);
return GetRawAxis(static_cast<int>(Axis::kLeftX));
} else {
return GetRawAxis(4);
return GetRawAxis(static_cast<int>(Axis::kRightX));
}
}
double XboxController::GetY(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawAxis(1);
return GetRawAxis(static_cast<int>(Axis::kLeftY));
} else {
return GetRawAxis(5);
return GetRawAxis(static_cast<int>(Axis::kRightY));
}
}
double XboxController::GetTriggerAxis(JoystickHand hand) const {
if (hand == kLeftHand) {
return GetRawAxis(2);
return GetRawAxis(static_cast<int>(Axis::kLeftTrigger));
} else {
return GetRawAxis(3);
return GetRawAxis(static_cast<int>(Axis::kRightTrigger));
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -26,6 +26,12 @@ PIDController::PIDController(double Kp, double Ki, double Kd,
frc::SendableRegistry::GetInstance().Add(this, "PIDController", instances);
}
void PIDController::SetPID(double Kp, double Ki, double Kd) {
m_Kp = Kp;
m_Ki = Ki;
m_Kd = Kd;
}
void PIDController::SetP(double Kp) { m_Kp = Kp; }
void PIDController::SetI(double Ki) { m_Ki = Ki; }

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2012-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2012-2020 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. */
@@ -104,10 +104,12 @@ void LiveWindow::SetEnabled(bool enabled) {
// Force table generation now to make sure everything is defined
UpdateValuesUnsafe();
if (enabled) {
if (this->enabled) this->enabled();
} else {
m_impl->registry.ForeachLiveWindow(m_impl->dataHandle, [&](auto& cbdata) {
cbdata.builder.StopLiveWindowMode();
});
if (this->disabled) this->disabled();
}
m_impl->enabledEntry.SetBoolean(enabled);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -32,7 +32,9 @@ void SendableBuilderImpl::UpdateTable() {
for (auto& property : m_properties) {
if (property.update) property.update(property.entry, time);
}
if (m_updateTable) m_updateTable();
for (auto& updateTable : m_updateTables) {
updateTable();
}
}
void SendableBuilderImpl::StartListeners() {
@@ -71,7 +73,7 @@ void SendableBuilderImpl::SetSafeState(std::function<void()> func) {
}
void SendableBuilderImpl::SetUpdateTable(std::function<void()> func) {
m_updateTable = func;
m_updateTables.emplace_back(std::move(func));
}
nt::NetworkTableEntry SendableBuilderImpl::GetEntry(const wpi::Twine& key) {

View File

@@ -9,7 +9,8 @@
#include <utility>
#include "frc/DriverStation.h"
#include <wpi/raw_ostream.h>
#include "frc/spline/SplineHelper.h"
#include "frc/spline/SplineParameterizer.h"
#include "frc/trajectory/TrajectoryParameterizer.h"
@@ -18,6 +19,14 @@ using namespace frc;
const Trajectory TrajectoryGenerator::kDoNothingTrajectory(
std::vector<Trajectory::State>{Trajectory::State()});
std::function<void(const char*)> TrajectoryGenerator::s_errorFunc;
void TrajectoryGenerator::ReportError(const char* error) {
if (s_errorFunc)
s_errorFunc(error);
else
wpi::errs() << "TrajectoryGenerator error: " << error << "\n";
}
Trajectory TrajectoryGenerator::GenerateTrajectory(
Spline<3>::ControlVector initial,
@@ -40,7 +49,7 @@ Trajectory TrajectoryGenerator::GenerateTrajectory(
SplinePointsFromSplines(SplineHelper::CubicSplinesFromControlVectors(
initial, interiorWaypoints, end));
} catch (SplineParameterizer::MalformedSplineException& e) {
DriverStation::ReportError(e.what());
ReportError(e.what());
return kDoNothingTrajectory;
}
@@ -84,7 +93,7 @@ Trajectory TrajectoryGenerator::GenerateTrajectory(
points = SplinePointsFromSplines(
SplineHelper::QuinticSplinesFromControlVectors(controlVectors));
} catch (SplineParameterizer::MalformedSplineException& e) {
DriverStation::ReportError(e.what());
ReportError(e.what());
return kDoNothingTrajectory;
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -25,6 +25,7 @@
#include "frc/WPIErrors.h"
#include "frc/livewindow/LiveWindow.h"
#include "frc/smartdashboard/SmartDashboard.h"
#include "frc/trajectory/TrajectoryGenerator.h"
typedef void (*SetCameraServerSharedFP)(frc::CameraServerShared* shared);
@@ -121,6 +122,8 @@ RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
m_threadId = std::this_thread::get_id();
SetupCameraServerShared();
TrajectoryGenerator::SetErrorHandler(
[](const char* error) { DriverStation::ReportError(error); });
auto inst = nt::NetworkTableInstance::GetDefault();
inst.SetNetworkIdentity("Robot");

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -22,6 +22,8 @@ namespace frc {
/**
* A class for driving addressable LEDs, such as WS2812s and NeoPixels.
*
* <p>Only 1 LED driver is currently supported by the roboRIO.
*/
class AddressableLED : public ErrorBase {
public:
@@ -83,7 +85,7 @@ class AddressableLED : public ErrorBase {
/**
* Constructs a new driver for a specific port.
*
* @param port the output port to use (Must be a PWM port)
* @param port the output port to use (Must be a PWM header)
*/
explicit AddressableLED(int port);
@@ -95,6 +97,8 @@ class AddressableLED : public ErrorBase {
* <p>Calling this is an expensive call, so its best to call it once, then
* just update data.
*
* <p>The max length is 5460 LEDs.
*
* @param length the strip length
*/
void SetLength(int length);

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -100,17 +100,6 @@ class AnalogTrigger : public ErrorBase,
*/
void SetAveraged(bool useAveragedValue);
/**
* Configure the analog trigger to use the duty cycle vs. raw values.
*
* If the value is true, then the duty cycle value is selected for the analog
* trigger, otherwise the immediate value is used.
*
* @param useDutyCycle If true, use the duty cycle value, otherwise use the
* instantaneous reading
*/
void SetDutyCycle(bool useDutyCycle);
/**
* Configure the analog trigger to use a filtered value.
*

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -138,7 +138,6 @@ class IterativeRobotBase : public RobotBase {
*/
virtual void TestPeriodic();
protected:
/**
* Constructor for IterativeRobotBase.
*
@@ -156,6 +155,7 @@ class IterativeRobotBase : public RobotBase {
virtual ~IterativeRobotBase() = default;
protected:
IterativeRobotBase(IterativeRobotBase&&) = default;
IterativeRobotBase& operator=(IterativeRobotBase&&) = default;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -176,7 +176,6 @@ class RobotBase {
static constexpr bool IsSimulation() { return !IsReal(); }
protected:
/**
* Constructor for a generic robot program.
*
@@ -192,6 +191,7 @@ class RobotBase {
virtual ~RobotBase();
protected:
// m_ds isn't moved in these because DriverStation is a singleton; every
// instance of RobotBase has a reference to the same object.
RobotBase(RobotBase&&) noexcept;

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2020 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. */
@@ -244,6 +244,15 @@ class XboxController : public GenericHID {
kBack = 7,
kStart = 8
};
enum class Axis {
kLeftX = 0,
kRightX = 4,
kLeftY = 1,
kRightY = 5,
kLeftTrigger = 2,
kRightTrigger = 3
};
};
} // namespace frc

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -16,6 +16,7 @@ namespace frc {
* a motor acting against the force of gravity on a beam suspended at an angle).
*/
class ArmFeedforward {
public:
using Angle = units::radians;
using Velocity = units::radians_per_second;
using Acceleration = units::compound_unit<units::radians_per_second,
@@ -26,7 +27,6 @@ class ArmFeedforward {
using ka_unit =
units::compound_unit<units::volts, units::inverse<Acceleration>>;
public:
constexpr ArmFeedforward() = default;
/**

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -17,6 +17,7 @@ namespace frc {
*/
template <class Distance>
class ElevatorFeedforward {
public:
using Velocity =
units::compound_unit<Distance, units::inverse<units::seconds>>;
using Acceleration =
@@ -25,7 +26,6 @@ class ElevatorFeedforward {
using ka_unit =
units::compound_unit<units::volts, units::inverse<Acceleration>>;
public:
ElevatorFeedforward() = default;
/**

View File

@@ -33,6 +33,7 @@ template <class Distance>
class ProfiledPIDController
: public Sendable,
public SendableHelper<ProfiledPIDController<Distance>> {
public:
using Distance_t = units::unit_t<Distance>;
using Velocity =
units::compound_unit<Distance, units::inverse<units::seconds>>;
@@ -43,7 +44,6 @@ class ProfiledPIDController
using State = typename TrapezoidProfile<Distance>::State;
using Constraints = typename TrapezoidProfile<Distance>::Constraints;
public:
/**
* Allocates a ProfiledPIDController with the given constants for Kp, Ki, and
* Kd. Users should call reset() when they first start running the controller

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -17,6 +17,7 @@ namespace frc {
*/
template <class Distance>
class SimpleMotorFeedforward {
public:
using Velocity =
units::compound_unit<Distance, units::inverse<units::seconds>>;
using Acceleration =
@@ -25,7 +26,6 @@ class SimpleMotorFeedforward {
using ka_unit =
units::compound_unit<units::volts, units::inverse<Acceleration>>;
public:
constexpr SimpleMotorFeedforward() = default;
/**

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2012-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2012-2020 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. */
@@ -7,6 +7,7 @@
#pragma once
#include <functional>
#include <memory>
namespace frc {
@@ -22,6 +23,9 @@ class LiveWindow {
LiveWindow(const LiveWindow&) = delete;
LiveWindow& operator=(const LiveWindow&) = delete;
std::function<void()> enabled;
std::function<void()> disabled;
/**
* Get an instance of the LiveWindow main class.
*

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -202,7 +202,7 @@ class SendableBuilderImpl : public SendableBuilder {
std::vector<Property> m_properties;
std::function<void()> m_safeState;
std::function<void()> m_updateTable;
std::vector<std::function<void()>> m_updateTables;
std::shared_ptr<nt::NetworkTable> m_table;
nt::NetworkTableEntry m_controllableEntry;
bool m_actuator = false;

View File

@@ -7,6 +7,7 @@
#pragma once
#include <functional>
#include <memory>
#include <utility>
#include <vector>
@@ -114,7 +115,19 @@ class TrajectoryGenerator {
return splinePoints;
}
/**
* Set error reporting function. By default, it is output to stderr.
*
* @param func Error reporting function.
*/
static void SetErrorHandler(std::function<void(const char*)> func) {
s_errorFunc = std::move(func);
}
private:
static void ReportError(const char* error);
static const Trajectory kDoNothingTrajectory;
static std::function<void(const char*)> s_errorFunc;
};
} // namespace frc

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -399,7 +399,7 @@ class Color {
/**
* #20B2AA.
*/
static const Color kLightSeagGeen;
static const Color kLightSeaGreen;
/**
* #87CEFA.
@@ -414,7 +414,7 @@ class Color {
/**
* #B0C4DE.
*/
static const Color kLightSteellue;
static const Color kLightSteelBlue;
/**
* #FFFFE0.
@@ -864,13 +864,13 @@ inline constexpr Color Color::kLightGray{0.827451f, 0.827451f, 0.827451f};
inline constexpr Color Color::kLightGreen{0.5647059f, 0.93333334f, 0.5647059f};
inline constexpr Color Color::kLightPink{1.0f, 0.7137255f, 0.75686276f};
inline constexpr Color Color::kLightSalmon{1.0f, 0.627451f, 0.47843137f};
inline constexpr Color Color::kLightSeagGeen{0.1254902f, 0.69803923f,
inline constexpr Color Color::kLightSeaGreen{0.1254902f, 0.69803923f,
0.6666667f};
inline constexpr Color Color::kLightSkyBlue{0.5294118f, 0.80784315f,
0.98039216f};
inline constexpr Color Color::kLightSlateGray{0.46666667f, 0.53333336f, 0.6f};
inline constexpr Color Color::kLightSteellue{0.6901961f, 0.76862746f,
0.87058824f};
inline constexpr Color Color::kLightSteelBlue{0.6901961f, 0.76862746f,
0.87058824f};
inline constexpr Color Color::kLightYellow{1.0f, 1.0f, 0.8784314f};
inline constexpr Color Color::kLime{0.0f, 1.0f, 0.0f};
inline constexpr Color Color::kLimeGreen{0.19607843f, 0.8039216f, 0.19607843f};

View File

@@ -294,7 +294,7 @@
},
{
"name": "'Traditional' Hatchbot",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new experimental command API. Written in the 'traditional' style, i.e. commands are given their own classes.",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new command framework. Written in the 'traditional' style, i.e. commands are given their own classes.",
"tags": [
"Complete robot",
"Command-based"
@@ -305,7 +305,7 @@
},
{
"name": "'Inlined' Hatchbot",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new experimental command API. Written in the 'inlined' style, i.e. many commands are defined inline with lambdas.",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new command framework. Written in the 'inlined' style, i.e. many commands are defined inline with lambdas.",
"tags": [
"Complete robot",
"Command-based",
@@ -317,7 +317,7 @@
},
{
"name": "Select Command Example",
"description": "An example showing how to use the SelectCommand class from the experimental command framework rewrite.",
"description": "An example showing how to use the SelectCommand class from the new command framework.",
"tags": [
"Command-based"
],
@@ -327,7 +327,7 @@
},
{
"name": "Scheduler Event Logging",
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the experimental command framework rewrite",
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the new command framework",
"tags": [
"Command-based",
"Shuffleboard"

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -14,6 +14,8 @@ import edu.wpi.first.hal.PWMJNI;
/**
* A class for driving addressable LEDs, such as WS2812s and NeoPixels.
*
* <p>Only 1 LED driver is currently supported by the roboRIO.
*/
public class AddressableLED implements AutoCloseable {
private final int m_pwmHandle;
@@ -22,7 +24,7 @@ public class AddressableLED implements AutoCloseable {
/**
* Constructs a new driver for a specific port.
*
* @param port the output port to use (Must be a PWM port)
* @param port the output port to use (Must be a PWM header, not on MXP)
*/
public AddressableLED(int port) {
m_pwmHandle = PWMJNI.initializePWMPort(HAL.getPort((byte) port));
@@ -45,6 +47,8 @@ public class AddressableLED implements AutoCloseable {
*
* <p>Calling this is an expensive call, so its best to call it once, then just update data.
*
* <p>The max length is 5460 LEDs.
*
* @param length the strip length
*/
public void setLength(int length) {

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2016-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2016-2020 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. */
@@ -41,6 +41,25 @@ public class XboxController extends GenericHID {
}
}
/**
* Represents an axis on an XboxController.
*/
public enum Axis {
kLeftX(0),
kRightX(4),
kLeftY(1),
kRightY(5),
kLeftTrigger(2),
kRightTrigger(3);
@SuppressWarnings({"MemberName", "PMD.SingularField"})
public final int value;
Axis(int value) {
this.value = value;
}
}
/**
* Construct an instance of a joystick. The joystick index is the USB port on the drivers
* station.
@@ -62,9 +81,9 @@ public class XboxController extends GenericHID {
@Override
public double getX(Hand hand) {
if (hand.equals(Hand.kLeft)) {
return getRawAxis(0);
return getRawAxis(Axis.kLeftX.value);
} else {
return getRawAxis(4);
return getRawAxis(Axis.kRightX.value);
}
}
@@ -77,9 +96,9 @@ public class XboxController extends GenericHID {
@Override
public double getY(Hand hand) {
if (hand.equals(Hand.kLeft)) {
return getRawAxis(1);
return getRawAxis(Axis.kLeftY.value);
} else {
return getRawAxis(5);
return getRawAxis(Axis.kRightY.value);
}
}
@@ -91,9 +110,9 @@ public class XboxController extends GenericHID {
*/
public double getTriggerAxis(Hand hand) {
if (hand.equals(Hand.kLeft)) {
return getRawAxis(2);
return getRawAxis(Axis.kLeftTrigger.value);
} else {
return getRawAxis(3);
return getRawAxis(Axis.kRightTrigger.value);
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -33,6 +33,9 @@ public class LiveWindow {
private static boolean liveWindowEnabled;
private static boolean telemetryEnabled = true;
private static Runnable enabledListener;
private static Runnable disabledListener;
private static Component getOrAdd(Sendable sendable) {
Component data = (Component) SendableRegistry.getData(sendable, dataHandle);
if (data == null) {
@@ -46,6 +49,14 @@ public class LiveWindow {
throw new UnsupportedOperationException("This is a utility class!");
}
public static synchronized void setEnabledListener(Runnable runnable) {
enabledListener = runnable;
}
public static synchronized void setDisabledListener(Runnable runnable) {
disabledListener = runnable;
}
public static synchronized boolean isEnabled() {
return liveWindowEnabled;
}
@@ -65,11 +76,17 @@ public class LiveWindow {
updateValues(); // Force table generation now to make sure everything is defined
if (enabled) {
System.out.println("Starting live window mode.");
if (enabledListener != null) {
enabledListener.run();
}
} else {
System.out.println("stopping live window mode.");
SendableRegistry.foreachLiveWindow(dataHandle, cbdata -> {
cbdata.builder.stopLiveWindowMode();
});
if (disabledListener != null) {
disabledListener.run();
}
}
enabledEntry.setBoolean(enabled);
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2017-2020 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. */
@@ -55,7 +55,7 @@ public class SendableBuilderImpl implements SendableBuilder {
private final List<Property> m_properties = new ArrayList<>();
private Runnable m_safeState;
private Runnable m_updateTable;
private final List<Runnable> m_updateTables = new ArrayList<>();
private NetworkTable m_table;
private NetworkTableEntry m_controllableEntry;
private boolean m_actuator;
@@ -105,8 +105,8 @@ public class SendableBuilderImpl implements SendableBuilder {
property.m_update.accept(property.m_entry);
}
}
if (m_updateTable != null) {
m_updateTable.run();
for (Runnable updateTable : m_updateTables) {
updateTable.run();
}
}
@@ -207,7 +207,7 @@ public class SendableBuilderImpl implements SendableBuilder {
*/
@Override
public void setUpdateTable(Runnable func) {
m_updateTable = func;
m_updateTables.add(func);
}
/**

View File

@@ -11,6 +11,7 @@ import java.util.ArrayList;
import java.util.Arrays;
import java.util.Collection;
import java.util.List;
import java.util.function.BiConsumer;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.geometry.Pose2d;
@@ -26,6 +27,7 @@ import edu.wpi.first.wpilibj.spline.SplineParameterizer.MalformedSplineException
public final class TrajectoryGenerator {
private static final Trajectory kDoNothingTrajectory =
new Trajectory(Arrays.asList(new Trajectory.State()));
private static BiConsumer<String, StackTraceElement[]> errorFunc;
/**
* Private constructor because this is a utility class.
@@ -33,6 +35,23 @@ public final class TrajectoryGenerator {
private TrajectoryGenerator() {
}
private static void reportError(String error, StackTraceElement[] stackTrace) {
if (errorFunc != null) {
errorFunc.accept(error, stackTrace);
} else {
DriverStation.reportError(error, stackTrace);
}
}
/**
* Set error reporting function. By default, DriverStation.reportError() is used.
*
* @param func Error reporting function, arguments are error and stackTrace.
*/
public static void setErrorHandler(BiConsumer<String, StackTraceElement[]> func) {
errorFunc = func;
}
/**
* Generates a trajectory from the given control vectors and config. This method uses clamped
* cubic splines -- a method in which the exterior control vectors and interior waypoints
@@ -71,7 +90,7 @@ public final class TrajectoryGenerator {
points = splinePointsFromSplines(SplineHelper.getCubicSplinesFromControlVectors(newInitial,
interiorWaypoints.toArray(new Translation2d[0]), newEnd));
} catch (MalformedSplineException ex) {
DriverStation.reportError(ex.getMessage(), ex.getStackTrace());
reportError(ex.getMessage(), ex.getStackTrace());
return kDoNothingTrajectory;
}
@@ -147,7 +166,7 @@ public final class TrajectoryGenerator {
newControlVectors.toArray(new Spline.ControlVector[]{})
));
} catch (MalformedSplineException ex) {
DriverStation.reportError(ex.getMessage(), ex.getStackTrace());
reportError(ex.getMessage(), ex.getStackTrace());
return kDoNothingTrajectory;
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2019-2020 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. */
@@ -18,6 +18,61 @@ import edu.wpi.first.wpiutil.math.MathUtil;
*/
@SuppressWarnings("MemberName")
public class Color {
private static final double kPrecision = Math.pow(2, -12);
public final double red;
public final double green;
public final double blue;
/**
* Constructs a Color.
*
* @param red Red value (0-1)
* @param green Green value (0-1)
* @param blue Blue value (0-1)
*/
public Color(double red, double green, double blue) {
this.red = roundAndClamp(red);
this.green = roundAndClamp(green);
this.blue = roundAndClamp(blue);
}
/**
* Constructs a Color from a Color8Bit.
*
* @param color The color
*/
public Color(Color8Bit color) {
this(color.red / 255.0,
color.green / 255.0,
color.blue / 255.0);
}
@Override
public boolean equals(Object other) {
if (this == other) {
return true;
}
if (other == null || getClass() != other.getClass()) {
return false;
}
Color color = (Color) other;
return Double.compare(color.red, red) == 0
&& Double.compare(color.green, green) == 0
&& Double.compare(color.blue, blue) == 0;
}
@Override
public int hashCode() {
return Objects.hash(red, green, blue);
}
private static double roundAndClamp(double value) {
final var rounded = Math.round(value / kPrecision) * kPrecision;
return MathUtil.clamp(rounded, 0.0, 1.0);
}
/*
* FIRST Colors
*/
@@ -399,7 +454,7 @@ public class Color {
/**
* #20B2AA.
*/
public static final Color kLightSeagGeen = new Color(0.1254902f, 0.69803923f, 0.6666667f);
public static final Color kLightSeaGreen = new Color(0.1254902f, 0.69803923f, 0.6666667f);
/**
* #87CEFA.
@@ -414,7 +469,7 @@ public class Color {
/**
* #B0C4DE.
*/
public static final Color kLightSteellue = new Color(0.6901961f, 0.76862746f, 0.87058824f);
public static final Color kLightSteelBlue = new Color(0.6901961f, 0.76862746f, 0.87058824f);
/**
* #FFFFE0.
@@ -740,59 +795,4 @@ public class Color {
* #9ACD32.
*/
public static final Color kYellowGreen = new Color(0.6039216f, 0.8039216f, 0.19607843f);
public final double red;
public final double green;
public final double blue;
private static final double kPrecision = Math.pow(2, -12);
/**
* Constructs a Color.
*
* @param red Red value (0-1)
* @param green Green value (0-1)
* @param blue Blue value (0-1)
*/
Color(double red, double green, double blue) {
this.red = roundAndClamp(red);
this.green = roundAndClamp(green);
this.blue = roundAndClamp(blue);
}
/**
* Constructs a Color from a Color8Bit.
*
* @param color The color
*/
public Color(Color8Bit color) {
this(color.red / 255.0,
color.green / 255.0,
color.blue / 255.0);
}
@Override
public boolean equals(Object other) {
if (this == other) {
return true;
}
if (other == null || getClass() != other.getClass()) {
return false;
}
Color color = (Color) other;
return Double.compare(color.red, red) == 0
&& Double.compare(color.green, green) == 0
&& Double.compare(color.blue, blue) == 0;
}
@Override
public int hashCode() {
return Objects.hash(red, green, blue);
}
private static double roundAndClamp(double value) {
final var rounded = Math.round(value / kPrecision) * kPrecision;
return MathUtil.clamp(rounded, 0.0, 1.0);
}
}

View File

@@ -0,0 +1,50 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2020 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.util;
import java.util.stream.Stream;
import org.junit.jupiter.params.ParameterizedTest;
import org.junit.jupiter.params.provider.Arguments;
import org.junit.jupiter.params.provider.MethodSource;
import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.params.provider.Arguments.arguments;
class ColorTest {
private static final double kEpsilon = 1e-3;
void assertColorMatches(double red, double green, double blue, Color color) {
assertAll(
() -> assertEquals(red, color.red, kEpsilon),
() -> assertEquals(green, color.green, kEpsilon),
() -> assertEquals(blue, color.blue, kEpsilon)
);
}
@ParameterizedTest
@MethodSource("staticColorProvider")
void staticColorTest(double red, double green, double blue, Color color) {
assertColorMatches(red, green, blue, color);
}
@ParameterizedTest
@MethodSource("staticColorProvider")
void colorEqualsTest(double red, double green, double blue, Color color) {
assertEquals(color, new Color(red, green, blue));
}
static Stream<Arguments> staticColorProvider() {
return Stream.of(
arguments(0.0823529412, 0.376470589, 0.7411764706, Color.kDenim),
arguments(0.0, 0.4, 0.7019607844, Color.kFirstBlue),
arguments(0.9294117648, 0.1098039216, 0.1411764706, Color.kFirstRed)
);
}
}

View File

@@ -309,7 +309,7 @@
},
{
"name": "'Traditional' Hatchbot",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new experimental command API. Written in the 'traditional' style, i.e. commands are given their own classes.",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new command framework. Written in the 'traditional' style, i.e. commands are given their own classes.",
"tags": [
"Complete robot",
"Command-based"
@@ -321,7 +321,7 @@
},
{
"name": "'Inlined' Hatchbot",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new experimental command API. Written in the 'inlined' style, i.e. many commands are defined inline with lambdas.",
"description": "A fully-functional command-based hatchbot for the 2019 game using the new command framework. Written in the 'inlined' style, i.e. many commands are defined inline with lambdas.",
"tags": [
"Complete robot",
"Command-based",
@@ -334,7 +334,7 @@
},
{
"name": "Select Command Example",
"description": "An example showing how to use the SelectCommand class from the experimental command framework rewrite.",
"description": "An example showing how to use the SelectCommand class from the new command framework.",
"tags": [
"Command-based"
],
@@ -345,7 +345,7 @@
},
{
"name": "Scheduler Event Logging",
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the experimental command framework rewrite",
"description": "An example showing how to use Shuffleboard to log Command events from the CommandScheduler in the new command framework",
"tags": [
"Command-based",
"Shuffleboard"

View File

@@ -2042,7 +2042,7 @@ namespace units
{
return detail::abs(nls::m_value - units::convert<UnitsRhs, Units>(rhs.m_value)) < std::numeric_limits<T>::epsilon() *
detail::abs(nls::m_value + units::convert<UnitsRhs, Units>(rhs.m_value)) ||
detail::abs(nls::m_value - units::convert<UnitsRhs, Units>(rhs.m_value)) < std::numeric_limits<T>::min();
detail::abs(nls::m_value - units::convert<UnitsRhs, Units>(rhs.m_value)) < (std::numeric_limits<T>::min)();
}
template<class UnitsRhs, typename Ty, template<typename> class NlsRhs, std::enable_if_t<std::is_integral<T>::value && std::is_integral<Ty>::value, int> = 0>
@@ -2656,14 +2656,14 @@ namespace units
constexpr bool operator==(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept
{
return detail::abs(lhs - static_cast<UNIT_LIB_DEFAULT_TYPE>(rhs)) < std::numeric_limits<UNIT_LIB_DEFAULT_TYPE>::epsilon() * detail::abs(lhs + static_cast<UNIT_LIB_DEFAULT_TYPE>(rhs)) ||
detail::abs(lhs - static_cast<UNIT_LIB_DEFAULT_TYPE>(rhs)) < std::numeric_limits<UNIT_LIB_DEFAULT_TYPE>::min();
detail::abs(lhs - static_cast<UNIT_LIB_DEFAULT_TYPE>(rhs)) < (std::numeric_limits<UNIT_LIB_DEFAULT_TYPE>::min)();
}
template<typename Units, class = std::enable_if_t<units::traits::is_dimensionless_unit<Units>::value>>
constexpr bool operator==(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept
{
return detail::abs(static_cast<UNIT_LIB_DEFAULT_TYPE>(lhs) - rhs) < std::numeric_limits<UNIT_LIB_DEFAULT_TYPE>::epsilon() * detail::abs(static_cast<UNIT_LIB_DEFAULT_TYPE>(lhs) + rhs) ||
detail::abs(static_cast<UNIT_LIB_DEFAULT_TYPE>(lhs) - rhs) < std::numeric_limits<UNIT_LIB_DEFAULT_TYPE>::min();
detail::abs(static_cast<UNIT_LIB_DEFAULT_TYPE>(lhs) - rhs) < (std::numeric_limits<UNIT_LIB_DEFAULT_TYPE>::min)();
}
template<typename Units, class = std::enable_if_t<units::traits::is_dimensionless_unit<Units>::value>>
@@ -4166,7 +4166,7 @@ namespace units
//----------------------------------
template<class UnitTypeLhs, class UnitTypeRhs>
UnitTypeLhs min(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs)
UnitTypeLhs (min)(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs)
{
static_assert(traits::is_convertible_unit_t<UnitTypeLhs, UnitTypeRhs>::value, "Unit types are not compatible.");
UnitTypeLhs r(rhs);
@@ -4174,7 +4174,7 @@ namespace units
}
template<class UnitTypeLhs, class UnitTypeRhs>
UnitTypeLhs max(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs)
UnitTypeLhs (max)(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs)
{
static_assert(traits::is_convertible_unit_t<UnitTypeLhs, UnitTypeRhs>::value, "Unit types are not compatible.");
UnitTypeLhs r(rhs);
@@ -4806,13 +4806,13 @@ namespace std
class numeric_limits<units::unit_t<Units, T, NonLinearScale>>
{
public:
static constexpr units::unit_t<Units, T, NonLinearScale> min()
static constexpr units::unit_t<Units, T, NonLinearScale> (min)()
{
return units::unit_t<Units, T, NonLinearScale>(std::numeric_limits<T>::min());
return units::unit_t<Units, T, NonLinearScale>((std::numeric_limits<T>::min)());
}
static constexpr units::unit_t<Units, T, NonLinearScale> max()
static constexpr units::unit_t<Units, T, NonLinearScale> (max)()
{
return units::unit_t<Units, T, NonLinearScale>(std::numeric_limits<T>::max());
return units::unit_t<Units, T, NonLinearScale>((std::numeric_limits<T>::max)());
}
static constexpr units::unit_t<Units, T, NonLinearScale> lowest()
{

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -10,6 +10,8 @@
#include <string>
#include "wpi/Twine.h"
namespace wpi {
/**
@@ -18,7 +20,7 @@ namespace wpi {
* @param mangledSymbol the mangled symbol.
* @return The demangled symbol, or mangledSymbol if demangling fails.
*/
std::string Demangle(char const* mangledSymbol);
std::string Demangle(const Twine& mangledSymbol);
} // namespace wpi

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -11,26 +11,26 @@
#include <cstdio>
#include "wpi/SmallString.h"
namespace wpi {
std::string Demangle(char const* mangledSymbol) {
char buffer[256];
std::string Demangle(const Twine& mangledSymbol) {
SmallString<128> buf;
size_t length;
int32_t status;
if (std::sscanf(mangledSymbol, "%*[^(]%*[(]%255[^)+]", buffer)) {
char* symbol = abi::__cxa_demangle(buffer, nullptr, &length, &status);
if (status == 0) {
return symbol;
} else {
// If the symbol couldn't be demangled, it's probably a C function,
// so just return it as-is.
return buffer;
}
char* symbol =
abi::__cxa_demangle(mangledSymbol.toNullTerminatedStringRef(buf).data(),
nullptr, &length, &status);
if (status == 0) {
std::string rv{symbol};
std::free(symbol);
return rv;
}
// If everything else failed, just return the mangled symbol
return mangledSymbol;
return mangledSymbol.str();
}
} // namespace wpi

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -11,6 +11,7 @@
#include "wpi/Demangle.h"
#include "wpi/SmallString.h"
#include "wpi/StringRef.h"
#include "wpi/raw_ostream.h"
namespace wpi {
@@ -25,7 +26,11 @@ std::string GetStackTrace(int offset) {
for (int i = offset; i < stackSize; i++) {
// Only print recursive functions once in a row.
if (i == 0 || stackTrace[i] != stackTrace[i - 1]) {
trace << "\tat " << Demangle(mangledSymbols[i]) << "\n";
// extract just function name from "pathToExe(functionName+offset)"
StringRef sym{mangledSymbols[i]};
sym = sym.split('(').second;
sym = sym.split('+').first;
trace << "\tat " << Demangle(sym) << "\n";
}
}

View File

@@ -1,5 +1,5 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2008-2019 FIRST. All Rights Reserved. */
/* Copyright (c) 2008-2020 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. */
@@ -11,19 +11,22 @@
#include <dbghelp.h>
#include "wpi/SmallString.h"
#include "wpi/mutex.h"
#pragma comment(lib, "Dbghelp.lib")
namespace wpi {
std::string Demangle(char const* mangledSymbol) {
std::string Demangle(const Twine& mangledSymbol) {
static wpi::mutex m;
std::scoped_lock lock(m);
SmallString<128> buf;
char buffer[256];
DWORD sz = UnDecorateSymbolName(mangledSymbol, buffer, sizeof(buffer),
UNDNAME_COMPLETE);
if (sz == 0) return mangledSymbol;
DWORD sz =
UnDecorateSymbolName(mangledSymbol.toNullTerminatedStringRef(buf).data(),
buffer, sizeof(buffer), UNDNAME_COMPLETE);
if (sz == 0) return mangledSymbol.str();
return std::string(buffer, sz);
}