Merge changes I7f67fba2,I4b4fd4d1
* changes:
Delete unused //build_tests:karma
Prepare for migration from ts_library to ts_project
diff --git a/WORKSPACE b/WORKSPACE
index d6a50c7..2b3531c 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -750,9 +750,9 @@
deps = ["@//third_party/allwpilib/wpimath"],
)
""",
- sha256 = "d9d6c48df9318cf106237a44bf7ad95e4092618bc3ab731092e9b733cacb1ffc",
+ sha256 = "7ffc54bf40814a5c101ea3159af15215f15087298cfc2ae65826f987ccf65499",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/api-cpp/23.0.1/api-cpp-23.0.1-headers.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/api-cpp/23.0.5/api-cpp-23.0.5-headers.zip",
],
)
@@ -774,9 +774,9 @@
target_compatible_with = ['@//tools/platforms/hardware:roborio'],
)
""",
- sha256 = "3d228fdf8565de5411a739fa2670d4ef5390acb15ceb4d3cbef8c76b5adc7682",
+ sha256 = "1e8a487cb538388de437d04985512533a9dea79e6c56ee0f319c5eb80260fcab",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/api-cpp/23.0.1/api-cpp-23.0.1-linuxathena.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/api-cpp/23.0.5/api-cpp-23.0.5-linuxathena.zip",
],
)
@@ -789,9 +789,9 @@
hdrs = glob(['ctre/**/*.h', 'ctre/**/*.hpp']),
)
""",
- sha256 = "74d79bb3e739d9d6b87311656b0530aaefc211952cc647a3d57776a0cee9efce",
+ sha256 = "51c52dfce4c2491887a7b7380e2f17e93a4092b6ac9f60d716738447a8ebedd7",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/tools/23.0.1/tools-23.0.1-headers.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/tools/23.0.5/tools-23.0.5-headers.zip",
],
)
@@ -813,9 +813,9 @@
target_compatible_with = ['@//tools/platforms/hardware:roborio'],
)
""",
- sha256 = "1791b35fdf76aa08ad120e4d689d9440bd386542f63f5c44e4047a06e2e05b9a",
+ sha256 = "9fb137321745c1eff63bdcfe486806afb46ede11ea4d4c59461320845698cc1e",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/tools/23.0.1/tools-23.0.1-linuxathena.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenixpro/tools/23.0.5/tools-23.0.5-linuxathena.zip",
],
)
diff --git a/aos/BUILD b/aos/BUILD
index b8468bd..0792e67 100644
--- a/aos/BUILD
+++ b/aos/BUILD
@@ -411,9 +411,11 @@
],
data = [
":json_to_flatbuffer_fbs_reflection_out",
+ ":json_to_flatbuffer_test_spaces.json",
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
+ ":flatbuffer_merge",
":json_to_flatbuffer",
":json_to_flatbuffer_fbs",
"//aos/testing:googletest",
diff --git a/aos/events/logging/timestamp_plot.cc b/aos/events/logging/timestamp_plot.cc
index 1239eb2..ddc8381 100644
--- a/aos/events/logging/timestamp_plot.cc
+++ b/aos/events/logging/timestamp_plot.cc
@@ -48,9 +48,13 @@
std::string_view node1, std::string_view node2, bool flip) {
std::vector<double> samplefile12_t;
std::vector<double> samplefile12_o;
+ const std::string path = SampleFile(node1, node2);
- const std::string file =
- aos::util::ReadFileToStringOrDie(SampleFile(node1, node2));
+ if (!aos::util::PathExists(path)) {
+ return {};
+ }
+
+ const std::string file = aos::util::ReadFileToStringOrDie(path);
bool first = true;
std::vector<std::string_view> lines = absl::StrSplit(file, '\n');
samplefile12_t.reserve(lines.size());
@@ -91,7 +95,8 @@
for (size_t j = 0; j < i; ++j) {
const std::string_view node1 = nodes[j];
const std::string_view node2 = nodes[i];
- if (aos::util::PathExists(SampleFile(node1, node2))) {
+ if (aos::util::PathExists(SampleFile(node1, node2)) ||
+ aos::util::PathExists(SampleFile(node2, node1))) {
result.emplace_back(node1, node2);
LOG(INFO) << "Found pairing " << node1 << ", " << node2;
}
@@ -152,9 +157,13 @@
std::string_view node1, std::string_view node2, bool flip) {
std::vector<double> samplefile12_t;
std::vector<double> samplefile12_o;
+ const std::string path = absl::StrCat("/tmp/timestamp_noncausal_", node1, "_", node2, ".csv");
- const std::string file = aos::util::ReadFileToStringOrDie(
- absl::StrCat("/tmp/timestamp_noncausal_", node1, "_", node2, ".csv"));
+ if (!aos::util::PathExists(path)) {
+ return {};
+ }
+
+ const std::string file = aos::util::ReadFileToStringOrDie(path);
bool first = true;
std::vector<std::string_view> lines = absl::StrSplit(file, '\n');
samplefile12_t.reserve(lines.size());
@@ -306,9 +315,14 @@
NodePlotter plotter;
if (FLAGS_all) {
- for (std::pair<std::string, std::string> ab : NodeConnections()) {
+ const std::vector<std::pair<std::string, std::string>> connections =
+ NodeConnections();
+ for (std::pair<std::string, std::string> ab : connections) {
plotter.AddNodes(ab.first, ab.second);
}
+ if (connections.size() == 0) {
+ LOG(WARNING) << "No connections found, is something wrong?";
+ }
} else {
CHECK_EQ(argc, 3);
diff --git a/aos/json_to_flatbuffer.h b/aos/json_to_flatbuffer.h
index d5e1039..6eab22a 100644
--- a/aos/json_to_flatbuffer.h
+++ b/aos/json_to_flatbuffer.h
@@ -109,10 +109,8 @@
template <typename T>
inline FlatbufferDetachedBuffer<T> JsonFileToFlatbuffer(
const std::string_view path) {
- std::ifstream t{std::string(path)};
- std::istream_iterator<char> start(t), end;
- std::string result(start, end);
- return FlatbufferDetachedBuffer<T>(JsonToFlatbuffer<T>(result));
+ return FlatbufferDetachedBuffer<T>(
+ JsonToFlatbuffer<T>(util::ReadFileToStringOrDie(path)));
}
// Parses a file as a binary flatbuffer or dies.
diff --git a/aos/json_to_flatbuffer_test.cc b/aos/json_to_flatbuffer_test.cc
index 6772826..fddb431 100644
--- a/aos/json_to_flatbuffer_test.cc
+++ b/aos/json_to_flatbuffer_test.cc
@@ -1,5 +1,6 @@
#include "aos/json_to_flatbuffer.h"
+#include "aos/flatbuffer_merge.h"
#include "aos/json_to_flatbuffer_generated.h"
#include "aos/testing/path.h"
#include "flatbuffers/minireflect.h"
@@ -301,5 +302,20 @@
ConfigurationTypeTable()));
}
+TEST_F(JsonToFlatbufferTest, SpacedData) {
+ EXPECT_TRUE(CompareFlatBuffer(
+ FlatbufferDetachedBuffer<VectorOfStrings>(
+ JsonToFlatbuffer<VectorOfStrings>(R"json({
+ "str": [
+ "f o o",
+ "b a r",
+ "foo bar",
+ "bar foo"
+ ]
+})json")),
+ JsonFileToFlatbuffer<VectorOfStrings>(
+ ArtifactPath("aos/json_to_flatbuffer_test_spaces.json"))));
+}
+
} // namespace testing
} // namespace aos
diff --git a/aos/json_to_flatbuffer_test_spaces.json b/aos/json_to_flatbuffer_test_spaces.json
new file mode 100644
index 0000000..c864037
--- /dev/null
+++ b/aos/json_to_flatbuffer_test_spaces.json
@@ -0,0 +1,8 @@
+{
+ "str": [
+ "f o o",
+ "b a r",
+ "foo bar",
+ "bar foo"
+ ]
+}
diff --git a/aos/network/www/aos_plotter.ts b/aos/network/www/aos_plotter.ts
index cd2e131..13bf343 100644
--- a/aos/network/www/aos_plotter.ts
+++ b/aos/network/www/aos_plotter.ts
@@ -23,11 +23,11 @@
// The demo_plot.ts script has a basic example of using this library, with all
// the required boilerplate, as well as some extra examples about how to
// add axis labels and the such.
-import {Channel, Configuration} from 'org_frc971/aos/configuration_generated';
-import {Line, Plot, Point} from 'org_frc971/aos/network/www/plotter';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
-import {SubscriberRequest, ChannelRequest, TransferMethod} from 'org_frc971/aos/network/web_proxy_generated';
-import {Parser, Table} from 'org_frc971/aos/network/www/reflection'
+import {Channel, Configuration} from '../../configuration_generated';
+import {Line, Plot, Point} from './plotter';
+import {Connection} from './proxy';
+import {SubscriberRequest, ChannelRequest, TransferMethod} from '../web_proxy_generated';
+import {Parser, Table} from './reflection'
import {Schema} from 'flatbuffers_reflection/reflection_generated';
import {ByteBuffer} from 'flatbuffers';
diff --git a/aos/network/www/config_handler.ts b/aos/network/www/config_handler.ts
index a7c2149..fba7be3 100644
--- a/aos/network/www/config_handler.ts
+++ b/aos/network/www/config_handler.ts
@@ -1,6 +1,6 @@
import {ByteBuffer} from 'flatbuffers';
-import {Configuration} from 'org_frc971/aos/configuration_generated';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Configuration} from '../../configuration_generated';
+import {Connection} from './proxy';
import {Parser, Table} from './reflection'
diff --git a/aos/network/www/demo_plot.ts b/aos/network/www/demo_plot.ts
index ecd4da6..b586411 100644
--- a/aos/network/www/demo_plot.ts
+++ b/aos/network/www/demo_plot.ts
@@ -12,9 +12,9 @@
// This example shows how to:
// (a) Make use of the AosPlotter to plot a shmem message as a time-series.
// (b) Define your own custom plot with whatever data you want.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {Plot, Point} from 'org_frc971/aos/network/www/plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {AosPlotter} from './aos_plotter';
+import {Plot, Point} from './plotter';
+import * as proxy from './proxy';
import Connection = proxy.Connection;
diff --git a/aos/network/www/ping_handler.ts b/aos/network/www/ping_handler.ts
index 60e7c4a..224e432 100644
--- a/aos/network/www/ping_handler.ts
+++ b/aos/network/www/ping_handler.ts
@@ -1,4 +1,4 @@
-import {Ping} from 'org_frc971/aos/events/ping_generated';
+import {Ping} from '../../events/ping_generated';
import {ByteBuffer} from 'flatbuffers';
export function HandlePing(data: Uint8Array) {
diff --git a/aos/network/www/plotter.ts b/aos/network/www/plotter.ts
index 17bffa3..536322f 100644
--- a/aos/network/www/plotter.ts
+++ b/aos/network/www/plotter.ts
@@ -1,4 +1,5 @@
-import * as Colors from 'org_frc971/aos/network/www/colors';
+import * as Colors from './colors';
+
// Multiplies all the values in the provided array by scale.
function scaleVec(vec: number[], scale: number): number[] {
const scaled: number[] = [];
diff --git a/aos/network/www/proxy.ts b/aos/network/www/proxy.ts
index 0bda8b9..99a9a18 100644
--- a/aos/network/www/proxy.ts
+++ b/aos/network/www/proxy.ts
@@ -1,6 +1,6 @@
import {Builder, ByteBuffer, Offset} from 'flatbuffers';
-import {Channel as ChannelFb, Configuration} from 'org_frc971/aos/configuration_generated';
-import {ChannelRequest as ChannelRequestFb, ChannelState, MessageHeader, Payload, SdpType, SubscriberRequest, TransferMethod, WebSocketIce, WebSocketMessage, WebSocketSdp} from 'org_frc971/aos/network/web_proxy_generated';
+import {Channel as ChannelFb, Configuration} from '../../configuration_generated';
+import {ChannelRequest as ChannelRequestFb, ChannelState, MessageHeader, Payload, SdpType, SubscriberRequest, TransferMethod, WebSocketIce, WebSocketMessage, WebSocketSdp} from '../web_proxy_generated';
import {Schema} from 'flatbuffers_reflection/reflection_generated';
// There is one handler for each DataChannel, it maintains the state of
diff --git a/aos/network/www/reflection_test_main.ts b/aos/network/www/reflection_test_main.ts
index 8fb041e..092c9c2 100644
--- a/aos/network/www/reflection_test_main.ts
+++ b/aos/network/www/reflection_test_main.ts
@@ -1,6 +1,6 @@
import {Builder, ByteBuffer} from 'flatbuffers';
-import {Configuration} from 'org_frc971/aos/configuration_generated'
-import {BaseType, Configuration as TestTable, FooStruct, Location, Map, VectorOfStrings, VectorOfVectorOfString} from 'org_frc971/aos/json_to_flatbuffer_generated'
+import {Configuration} from '../../configuration_generated'
+import {BaseType, Configuration as TestTable, FooStruct, Location, Map, VectorOfStrings, VectorOfVectorOfString} from '../../json_to_flatbuffer_generated'
import {Connection} from './proxy';
import {Parser, Table} from './reflection'
diff --git a/aos/starter/BUILD b/aos/starter/BUILD
index 5690bda..8d3f4f5 100644
--- a/aos/starter/BUILD
+++ b/aos/starter/BUILD
@@ -226,6 +226,9 @@
srcs = [
"irq_affinity.cc",
],
+ data = [
+ "//aos/starter:rockpi_config.json",
+ ],
visibility = ["//visibility:public"],
deps = [
":irq_affinity_lib",
diff --git a/aos/starter/irq_affinity.cc b/aos/starter/irq_affinity.cc
index 3f32ec9..5c70e9e 100644
--- a/aos/starter/irq_affinity.cc
+++ b/aos/starter/irq_affinity.cc
@@ -14,6 +14,8 @@
DEFINE_string(user, "",
"Starter runs as though this user ran a SUID binary if set.");
+DEFINE_string(irq_config, "rockpi_config.json",
+ "File path of rockpi configuration");
namespace aos {
@@ -265,117 +267,10 @@
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
aos::configuration::ReadConfig(FLAGS_config);
- // TODO(austin): File instead of hard-coded JSON.
aos::FlatbufferDetachedBuffer<aos::starter::IrqAffinityConfig>
irq_affinity_config =
- aos::JsonToFlatbuffer<aos::starter::IrqAffinityConfig>(
- R"json({
- "irqs": [
- {
- "name": "ttyS2",
- "affinity": [1]
- },
- {
- "name": "dw-mci",
- "affinity": [1]
- },
- {
- "name": "mmc1",
- "affinity": [1]
- },
- {
- "name": "rkisp1",
- "affinity": [2]
- },
- {
- "name": "ff3c0000.i2c",
- "affinity": [2]
- },
- {
- "name": "ff3d0000.i2c",
- "affinity": [2]
- },
- {
- "name": "ff6e0000.dma-controller",
- "affinity": [0]
- },
- {
- "name": "ff1d0000.spi",
- "affinity": [0]
- },
- {
- "name": "eth0",
- "affinity": [1]
- }
- ],
- "kthreads": [
- {
- "name": "irq/*-ff940000.hdmi",
- "scheduler": "SCHEDULER_OTHER"
- },
- {
- "name": "irq/*-rockchip_usb2phy",
- "scheduler": "SCHEDULER_OTHER"
- },
- {
- "name": "irq/*-mmc0",
- "scheduler": "SCHEDULER_OTHER"
- },
- {
- "name": "irq/*-mmc1",
- "scheduler": "SCHEDULER_OTHER"
- },
- {
- "name": "irq/*-fe320000.mmc cd",
- "scheduler": "SCHEDULER_OTHER"
- },
- {
- "name": "irq/*-vc4 crtc",
- "scheduler": "SCHEDULER_OTHER"
- },
- {
- "name": "irq/*-rkisp1",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 60,
- "affinity": [2]
- },
- {
- "name": "irq/*-ff3c0000.i2c",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 51,
- "affinity": [2]
- },
- {
- "name": "irq/*-adis16505",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 59,
- "affinity": [0]
- },
- {
- "name": "irq/*-ff6e0000.dma-controller",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 59,
- "affinity": [0]
- },
- {
- "name": "spi0",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 57,
- "affinity": [0]
- },
- {
- "name": "irq/*-eth0",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 10,
- "affinity": [1]
- },
- {
- "name": "irq/*-rockchip_thermal",
- "scheduler": "SCHEDULER_FIFO",
- "priority": 1
- }
- ]
-})json");
+ aos::JsonFileToFlatbuffer<aos::starter::IrqAffinityConfig>(
+ FLAGS_irq_config);
aos::ShmEventLoop shm_event_loop(&config.message());
diff --git a/aos/starter/rockpi_config.json b/aos/starter/rockpi_config.json
new file mode 100644
index 0000000..d4cbaae
--- /dev/null
+++ b/aos/starter/rockpi_config.json
@@ -0,0 +1,107 @@
+{
+ "irqs": [
+ {
+ "name": "ttyS2",
+ "affinity": [1]
+ },
+ {
+ "name": "dw-mci",
+ "affinity": [1]
+ },
+ {
+ "name": "mmc1",
+ "affinity": [1]
+ },
+ {
+ "name": "rkisp1",
+ "affinity": [2]
+ },
+ {
+ "name": "ff3c0000.i2c",
+ "affinity": [2]
+ },
+ {
+ "name": "ff3d0000.i2c",
+ "affinity": [2]
+ },
+ {
+ "name": "ff6e0000.dma-controller",
+ "affinity": [0]
+ },
+ {
+ "name": "ff1d0000.spi",
+ "affinity": [0]
+ },
+ {
+ "name": "eth0",
+ "affinity": [1]
+ }
+ ],
+ "kthreads": [
+ {
+ "name": "irq/*-ff940000.hdmi",
+ "scheduler": "SCHEDULER_OTHER"
+ },
+ {
+ "name": "irq/*-rockchip_usb2phy",
+ "scheduler": "SCHEDULER_OTHER"
+ },
+ {
+ "name": "irq/*-mmc0",
+ "scheduler": "SCHEDULER_OTHER"
+ },
+ {
+ "name": "irq/*-mmc1",
+ "scheduler": "SCHEDULER_OTHER"
+ },
+ {
+ "name": "irq/*-fe320000.mmc cd",
+ "scheduler": "SCHEDULER_OTHER"
+ },
+ {
+ "name": "irq/*-vc4 crtc",
+ "scheduler": "SCHEDULER_OTHER"
+ },
+ {
+ "name": "irq/*-rkisp1",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 60,
+ "affinity": [2]
+ },
+ {
+ "name": "irq/*-ff3c0000.i2c",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 51,
+ "affinity": [2]
+ },
+ {
+ "name": "irq/*-adis16505",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 59,
+ "affinity": [0]
+ },
+ {
+ "name": "irq/*-ff6e0000.dma-controller",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 59,
+ "affinity": [0]
+ },
+ {
+ "name": "spi0",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 57,
+ "affinity": [0]
+ },
+ {
+ "name": "irq/*-eth0",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 10,
+ "affinity": [1]
+ },
+ {
+ "name": "irq/*-rockchip_thermal",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 1
+ }
+ ]
+}
diff --git a/frc971/analysis/cpp_plot/cpp_plot.ts b/frc971/analysis/cpp_plot/cpp_plot.ts
index a704e89..08e2b1c 100644
--- a/frc971/analysis/cpp_plot/cpp_plot.ts
+++ b/frc971/analysis/cpp_plot/cpp_plot.ts
@@ -1,7 +1,7 @@
// Plotter for the C++ in-process plotter.
-import {Configuration} from 'org_frc971/aos/configuration_generated';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
-import {plotData} from 'org_frc971/frc971/analysis/plot_data_utils';
+import {Configuration} from '../../../aos/configuration_generated';
+import {Connection} from '../../../aos/network/www/proxy';
+import {plotData} from '../plot_data_utils';
const rootDiv = document.createElement('div');
rootDiv.classList.add('aos_cpp_plot');
diff --git a/frc971/analysis/plot_data_utils.ts b/frc971/analysis/plot_data_utils.ts
index 1362a09..25131fb 100644
--- a/frc971/analysis/plot_data_utils.ts
+++ b/frc971/analysis/plot_data_utils.ts
@@ -1,10 +1,10 @@
// Provides a plot which handles plotting the plot defined by a
// frc971.analysis.Plot message.
-import {Plot as PlotFb} from 'org_frc971/frc971/analysis/plot_data_generated';
-import {MessageHandler, TimestampedMessage} from 'org_frc971/aos/network/www/aos_plotter';
+import {Plot as PlotFb} from './plot_data_generated';
+import {MessageHandler, TimestampedMessage} from '../../aos/network/www/aos_plotter';
import {ByteBuffer} from 'flatbuffers';
-import {Plot, Point} from 'org_frc971/aos/network/www/plotter';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Plot, Point} from '../../aos/network/www/plotter';
+import {Connection} from '../../aos/network/www/proxy';
import {Schema} from 'flatbuffers_reflection/reflection_generated';
export function plotData(conn: Connection, parentDiv: Element) {
diff --git a/frc971/analysis/plot_index.ts b/frc971/analysis/plot_index.ts
index af9bd73..ab00b99 100644
--- a/frc971/analysis/plot_index.ts
+++ b/frc971/analysis/plot_index.ts
@@ -20,41 +20,41 @@
// each robot year, and may even end up allowing plots to be specified solely
// using JSON rather than requiring people to write a script just to create
// a plot.
-import {Configuration} from 'org_frc971/aos/configuration_generated';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
-import {plotImu} from 'org_frc971/frc971/wpilib/imu_plotter';
-import {plotDrivetrain} from 'org_frc971/frc971/control_loops/drivetrain/drivetrain_plotter';
-import {plotSpline} from 'org_frc971/frc971/control_loops/drivetrain/spline_plotter';
-import {plotDownEstimator} from 'org_frc971/frc971/control_loops/drivetrain/down_estimator_plotter';
+import {Configuration} from '../../aos/configuration_generated';
+import {Connection} from '../../aos/network/www/proxy';
+import {plotImu} from '../wpilib/imu_plotter';
+import {plotDrivetrain} from '../control_loops/drivetrain/drivetrain_plotter';
+import {plotSpline} from '../control_loops/drivetrain/spline_plotter';
+import {plotDownEstimator} from '../control_loops/drivetrain/down_estimator_plotter';
import {plotRobotState} from
- 'org_frc971/frc971/control_loops/drivetrain/robot_state_plotter'
+ '../control_loops/drivetrain/robot_state_plotter'
import {plotFinisher as plot2020Finisher} from
- 'org_frc971/y2020/control_loops/superstructure/finisher_plotter'
+ '../../y2020/control_loops/superstructure/finisher_plotter'
import {plotTurret as plot2020Turret} from
- 'org_frc971/y2020/control_loops/superstructure/turret_plotter'
+ '../../y2020/control_loops/superstructure/turret_plotter'
import {plotLocalizer as plot2020Localizer} from
- 'org_frc971/y2020/control_loops/drivetrain/localizer_plotter'
+ '../../y2020/control_loops/drivetrain/localizer_plotter'
import {plotAccelerator as plot2020Accelerator} from
- 'org_frc971/y2020/control_loops/superstructure/accelerator_plotter'
+ '../../y2020/control_loops/superstructure/accelerator_plotter'
import {plotHood as plot2020Hood} from
- 'org_frc971/y2020/control_loops/superstructure/hood_plotter'
+ '../../y2020/control_loops/superstructure/hood_plotter'
import {plotSuperstructure as plot2021Superstructure} from
- 'org_frc971/y2021_bot3/control_loops/superstructure/superstructure_plotter';
+ '../../y2021_bot3/control_loops/superstructure/superstructure_plotter';
import {plotTurret as plot2022Turret} from
- 'org_frc971/y2022/control_loops/superstructure/turret_plotter'
+ '../../y2022/control_loops/superstructure/turret_plotter'
import {plotSuperstructure as plot2022Superstructure} from
- 'org_frc971/y2022/control_loops/superstructure/superstructure_plotter'
+ '../../y2022/control_loops/superstructure/superstructure_plotter'
import {plotCatapult as plot2022Catapult} from
- 'org_frc971/y2022/control_loops/superstructure/catapult_plotter'
+ '../../y2022/control_loops/superstructure/catapult_plotter'
import {plotIntakeFront as plot2022IntakeFront, plotIntakeBack as plot2022IntakeBack} from
- 'org_frc971/y2022/control_loops/superstructure/intake_plotter'
+ '../../y2022/control_loops/superstructure/intake_plotter'
import {plotClimber as plot2022Climber} from
- 'org_frc971/y2022/control_loops/superstructure/climber_plotter'
+ '../../y2022/control_loops/superstructure/climber_plotter'
import {plotLocalizer as plot2022Localizer} from
- 'org_frc971/y2022/localizer/localizer_plotter'
+ '../../y2022/localizer/localizer_plotter'
import {plotVision as plot2022Vision} from
- 'org_frc971/y2022/vision/vision_plotter'
-import {plotDemo} from 'org_frc971/aos/network/www/demo_plot';
+ '../../y2022/vision/vision_plotter'
+import {plotDemo} from '../../aos/network/www/demo_plot';
const rootDiv = document.createElement('div');
rootDiv.style.width = '100%';
diff --git a/frc971/constants/BUILD b/frc971/constants/BUILD
index c17dc31..3a7e73a 100644
--- a/frc971/constants/BUILD
+++ b/frc971/constants/BUILD
@@ -45,6 +45,7 @@
],
data = [
"//frc971/constants/testdata:aos_config",
+ "//frc971/constants/testdata:syntax_error.json",
"//frc971/constants/testdata:test_constants.json",
],
target_compatible_with = ["@platforms//os:linux"],
diff --git a/frc971/constants/constants_sender_test.cc b/frc971/constants/constants_sender_test.cc
index 1441767..512cb68 100644
--- a/frc971/constants/constants_sender_test.cc
+++ b/frc971/constants/constants_sender_test.cc
@@ -113,11 +113,11 @@
({
ConstantSender<testdata::ConstantsData, testdata::ConstantsList>
test_syntax(constants_sender_event_loop_.get(),
- "frc971/constants/testdata/syntaxerror.json", 971,
+ "frc971/constants/testdata/syntax_error.json", 971,
"/constants");
event_loop_factory_.RunFor(std::chrono::seconds(1));
}),
- "Error on line 0");
+ "Invalid field name");
}
} // namespace testing
diff --git a/frc971/constants/testdata/BUILD b/frc971/constants/testdata/BUILD
index 04cf8d3..a20264c 100644
--- a/frc971/constants/testdata/BUILD
+++ b/frc971/constants/testdata/BUILD
@@ -1,7 +1,10 @@
load("//aos:config.bzl", "aos_config")
load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
-exports_files(["test_constants.json"])
+exports_files([
+ "test_constants.json",
+ "syntax_error.json",
+])
flatbuffer_cc_library(
name = "constants_list_fbs",
diff --git a/frc971/control_loops/double_jointed_arm/BUILD b/frc971/control_loops/double_jointed_arm/BUILD
new file mode 100644
index 0000000..c7fcefc
--- /dev/null
+++ b/frc971/control_loops/double_jointed_arm/BUILD
@@ -0,0 +1,121 @@
+cc_library(
+ name = "trajectory",
+ srcs = [
+ "trajectory.cc",
+ ],
+ hdrs = [
+ "trajectory.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":dynamics",
+ "//aos/logging",
+ "//frc971/control_loops:dlqr",
+ "//frc971/control_loops:jacobian",
+ "@org_tuxfamily_eigen//:eigen",
+ ],
+)
+
+cc_test(
+ name = "trajectory_test",
+ srcs = [
+ "trajectory_test.cc",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":demo_path",
+ ":dynamics",
+ ":ekf",
+ ":test_constants",
+ ":trajectory",
+ "//aos/testing:googletest",
+ "@org_tuxfamily_eigen//:eigen",
+ ],
+)
+
+cc_library(
+ name = "dynamics",
+ srcs = [
+ "dynamics.cc",
+ ],
+ hdrs = [
+ "dynamics.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops:runge_kutta",
+ "@com_github_gflags_gflags//:gflags",
+ "@org_tuxfamily_eigen//:eigen",
+ ],
+)
+
+cc_library(
+ name = "demo_path",
+ srcs = [
+ "demo_path.cc",
+ ],
+ hdrs = ["demo_path.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [":trajectory"],
+)
+
+cc_test(
+ name = "dynamics_test",
+ srcs = [
+ "dynamics_test.cc",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":dynamics",
+ ":test_constants",
+ "//aos/testing:googletest",
+ ],
+)
+
+cc_library(
+ name = "ekf",
+ srcs = [
+ "ekf.cc",
+ ],
+ hdrs = [
+ "ekf.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":dynamics",
+ "//frc971/control_loops:jacobian",
+ "@org_tuxfamily_eigen//:eigen",
+ ],
+)
+
+cc_library(
+ name = "graph",
+ srcs = ["graph.cc"],
+ hdrs = ["graph.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
+cc_test(
+ name = "graph_test",
+ srcs = ["graph_test.cc"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":graph",
+ "//aos/testing:googletest",
+ ],
+)
+
+cc_library(
+ name = "test_constants",
+ hdrs = ["test_constants.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":dynamics",
+ ],
+)
diff --git a/y2018/control_loops/superstructure/arm/demo_path.cc b/frc971/control_loops/double_jointed_arm/demo_path.cc
similarity index 98%
rename from y2018/control_loops/superstructure/arm/demo_path.cc
rename to frc971/control_loops/double_jointed_arm/demo_path.cc
index 03856c9..8d549d1 100644
--- a/y2018/control_loops/superstructure/arm/demo_path.cc
+++ b/frc971/control_loops/double_jointed_arm/demo_path.cc
@@ -1,12 +1,11 @@
-#include "y2018/control_loops/superstructure/arm/demo_path.h"
+#include "frc971/control_loops/double_jointed_arm/demo_path.h"
#include <array>
#include <initializer_list>
#include <memory>
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
::std::vector<::std::array<double, 6>> FlipPath(
@@ -25,7 +24,6 @@
return result;
}
-
::std::unique_ptr<Path> MakeDemoPath() {
return ::std::unique_ptr<Path>(new Path(FlipPath(
{{{1.3583511559969876, 0.99753029519739866, 0.63708920330895369,
@@ -213,6 +211,5 @@
}
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
diff --git a/frc971/control_loops/double_jointed_arm/demo_path.h b/frc971/control_loops/double_jointed_arm/demo_path.h
new file mode 100644
index 0000000..9a9d393
--- /dev/null
+++ b/frc971/control_loops/double_jointed_arm/demo_path.h
@@ -0,0 +1,19 @@
+#ifndef FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DEMO_PATH_H_
+#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DEMO_PATH_H_
+
+#include <memory>
+
+#include "frc971/control_loops/double_jointed_arm/trajectory.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace arm {
+
+::std::unique_ptr<Path> MakeDemoPath();
+::std::unique_ptr<Path> MakeReversedDemoPath();
+
+} // namespace arm
+} // namespace control_loops
+} // namespace frc971
+
+#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DEMO_PATH_H_
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.cc b/frc971/control_loops/double_jointed_arm/dynamics.cc
new file mode 100644
index 0000000..b5b6c8d
--- /dev/null
+++ b/frc971/control_loops/double_jointed_arm/dynamics.cc
@@ -0,0 +1,37 @@
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+
+DEFINE_bool(gravity, true, "If true, enable gravity.");
+
+namespace frc971 {
+namespace control_loops {
+namespace arm {
+
+Dynamics::Dynamics(ArmConstants arm_constants)
+ : arm_constants_(arm_constants),
+
+ K3_((::Eigen::Matrix<double, 2, 2>() << arm_constants_.g1 *
+ arm_constants_.Kt /
+ arm_constants_.resistance,
+ 0.0, 0.0,
+ arm_constants_.g2 * arm_constants_.num_distal_motors *
+ arm_constants_.Kt / arm_constants_.resistance)
+ .finished()),
+
+ K3_inverse_(K3_.inverse()),
+ K4_((::Eigen::Matrix<double, 2, 2>()
+ << arm_constants_.g1 * arm_constants_.g1 * arm_constants_.Kt /
+ (arm_constants_.Kv * arm_constants_.resistance),
+ 0.0, 0.0,
+ arm_constants_.g2 * arm_constants_.g2 * arm_constants_.Kt *
+ arm_constants_.num_distal_motors /
+ (arm_constants_.Kv * arm_constants_.resistance))
+ .finished()),
+ alpha_(arm_constants_.j1 +
+ arm_constants_.r1 * arm_constants_.r1 * arm_constants_.m1 +
+ arm_constants_.l1 * arm_constants_.l1 * arm_constants_.m2),
+ beta_(arm_constants_.l1 * arm_constants_.r2 * arm_constants_.m2),
+ gamma_(arm_constants_.j2 +
+ arm_constants_.r2 * arm_constants_.r2 * arm_constants_.m2) {}
+} // namespace arm
+} // namespace control_loops
+} // namespace frc971
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.h b/frc971/control_loops/double_jointed_arm/dynamics.h
new file mode 100644
index 0000000..1e934bc
--- /dev/null
+++ b/frc971/control_loops/double_jointed_arm/dynamics.h
@@ -0,0 +1,195 @@
+#ifndef FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DYNAMICS_H_
+#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DYNAMICS_H_
+
+#include "Eigen/Dense"
+#include "frc971/control_loops/runge_kutta.h"
+#include "gflags/gflags.h"
+
+DECLARE_bool(gravity);
+
+namespace frc971 {
+namespace control_loops {
+namespace arm {
+
+struct ArmConstants {
+ // Below, 1 refers to the proximal joint, and 2 refers to the distal joint.
+ // Length of the joints in meters.
+ double l1;
+ double l2;
+
+ // Mass of the joints in kilograms.
+ double m1;
+ double m2;
+
+ // Moment of inertia of the joints in kg m^2
+ double j1;
+ double j2;
+
+ // Radius of the center of mass of the joints in meters.
+ double r1;
+ double r2;
+
+ // Gear ratios for the two joints.
+ double g1;
+ double g2;
+
+ // motor constants.
+ double efficiency_tweak;
+ double stall_torque;
+ double free_speed;
+ double stall_current;
+ double resistance;
+ double Kv;
+ double Kt;
+
+ // Number of motors on the distal joint.
+ double num_distal_motors;
+};
+
+// This class captures the dynamics of our system. It doesn't actually need to
+// store state yet, so everything can be constexpr and/or static.
+class Dynamics {
+ public:
+ Dynamics(ArmConstants arm_constants);
+ // Generates K1-2 for the arm ODE.
+ // K1 * d^2 theta / dt^2 + K2 * d theta / dt = K3 * V - K4 * d theta/dt
+ // These matricies are missing the velocity factor for K2[1, 0], and K2[0, 1].
+ // You probbaly want MatriciesForState.
+ void NormilizedMatriciesForState(const ::Eigen::Matrix<double, 4, 1> &X,
+ ::Eigen::Matrix<double, 2, 2> *K1_result,
+ ::Eigen::Matrix<double, 2, 2> *K2_result) const {
+ const double angle = X(0, 0) - X(2, 0);
+ const double s = ::std::sin(angle);
+ const double c = ::std::cos(angle);
+ *K1_result << alpha_, c * beta_, c * beta_, gamma_;
+ *K2_result << 0.0, s * beta_, -s * beta_, 0.0;
+ }
+
+ // Generates K1-2 for the arm ODE.
+ // K1 * d^2 theta / dt^2 + K2 * d theta / dt = K3 * V - K4 * d theta/dt
+ void MatriciesForState(const ::Eigen::Matrix<double, 4, 1> &X,
+ ::Eigen::Matrix<double, 2, 2> *K1_result,
+ ::Eigen::Matrix<double, 2, 2> *K2_result) const {
+ NormilizedMatriciesForState(X, K1_result, K2_result);
+ (*K2_result)(1, 0) *= X(1, 0);
+ (*K2_result)(0, 1) *= X(3, 0);
+ }
+
+ // TODO(austin): We may want a way to provide K1 and K2 to save CPU cycles.
+
+ // Calculates the acceleration given the current state and control input.
+ const ::Eigen::Matrix<double, 4, 1> Acceleration(
+ const ::Eigen::Matrix<double, 4, 1> &X,
+ const ::Eigen::Matrix<double, 2, 1> &U) const {
+ ::Eigen::Matrix<double, 2, 2> K1;
+ ::Eigen::Matrix<double, 2, 2> K2;
+
+ MatriciesForState(X, &K1, &K2);
+
+ const ::Eigen::Matrix<double, 2, 1> velocity =
+ (::Eigen::Matrix<double, 2, 1>() << X(1, 0), X(3, 0)).finished();
+
+ const ::Eigen::Matrix<double, 2, 1> torque = K3_ * U - K4_ * velocity;
+ const ::Eigen::Matrix<double, 2, 1> gravity_torque = GravityTorque(X);
+
+ const ::Eigen::Matrix<double, 2, 1> accel =
+ K1.inverse() * (torque + gravity_torque - K2 * velocity);
+
+ return (::Eigen::Matrix<double, 4, 1>() << X(1, 0), accel(0, 0), X(3, 0),
+ accel(1, 0))
+ .finished();
+ }
+
+ // Calculates the acceleration given the current augmented kalman filter state
+ // and control input.
+ const ::Eigen::Matrix<double, 6, 1> EKFAcceleration(
+ const ::Eigen::Matrix<double, 6, 1> &X,
+ const ::Eigen::Matrix<double, 2, 1> &U) const {
+ ::Eigen::Matrix<double, 2, 2> K1;
+ ::Eigen::Matrix<double, 2, 2> K2;
+
+ MatriciesForState(X.block<4, 1>(0, 0), &K1, &K2);
+
+ const ::Eigen::Matrix<double, 2, 1> velocity =
+ (::Eigen::Matrix<double, 2, 1>() << X(1, 0), X(3, 0)).finished();
+
+ const ::Eigen::Matrix<double, 2, 1> torque =
+ K3_ *
+ (U +
+ (::Eigen::Matrix<double, 2, 1>() << X(4, 0), X(5, 0)).finished()) -
+ K4_ * velocity;
+ const ::Eigen::Matrix<double, 2, 1> gravity_torque =
+ GravityTorque(X.block<4, 1>(0, 0));
+
+ const ::Eigen::Matrix<double, 2, 1> accel =
+ K1.inverse() * (torque + gravity_torque - K2 * velocity);
+
+ return (::Eigen::Matrix<double, 6, 1>() << X(1, 0), accel(0, 0), X(3, 0),
+ accel(1, 0), 0.0, 0.0)
+ .finished();
+ }
+
+ // Calculates the voltage required to follow the trajectory. This requires
+ // knowing the current state, desired angular velocity and acceleration.
+ const ::Eigen::Matrix<double, 2, 1> FF_U(
+ const ::Eigen::Matrix<double, 4, 1> &X,
+ const ::Eigen::Matrix<double, 2, 1> &omega_t,
+ const ::Eigen::Matrix<double, 2, 1> &alpha_t) const {
+ ::Eigen::Matrix<double, 2, 2> K1;
+ ::Eigen::Matrix<double, 2, 2> K2;
+
+ MatriciesForState(X, &K1, &K2);
+
+ const ::Eigen::Matrix<double, 2, 1> gravity_torque = GravityTorque(X);
+
+ return K3_inverse_ *
+ (K1 * alpha_t + K2 * omega_t + K4_ * omega_t - gravity_torque);
+ }
+
+ const ::Eigen::Matrix<double, 2, 1> GravityTorque(
+ const ::Eigen::Matrix<double, 4, 1> &X) const {
+ const double accel_due_to_gravity = 9.8 * arm_constants_.efficiency_tweak;
+ return (::Eigen::Matrix<double, 2, 1>()
+ << (arm_constants_.r1 * arm_constants_.m1 +
+ arm_constants_.l1 * arm_constants_.m2) *
+ ::std::sin(X(0)) * accel_due_to_gravity,
+ arm_constants_.r2 * arm_constants_.m2 * ::std::sin(X(2)) *
+ accel_due_to_gravity)
+ .finished() *
+ (FLAGS_gravity ? 1.0 : 0.0);
+ }
+
+ const ::Eigen::Matrix<double, 4, 1> UnboundedDiscreteDynamics(
+ const ::Eigen::Matrix<double, 4, 1> &X,
+ const ::Eigen::Matrix<double, 2, 1> &U, double dt) const {
+ return ::frc971::control_loops::RungeKuttaU(
+ [this](const auto &X, const auto &U) { return Acceleration(X, U); }, X,
+ U, dt);
+ }
+
+ const ::Eigen::Matrix<double, 6, 1> UnboundedEKFDiscreteDynamics(
+ const ::Eigen::Matrix<double, 6, 1> &X,
+ const ::Eigen::Matrix<double, 2, 1> &U, double dt) const {
+ return ::frc971::control_loops::RungeKuttaU(
+ [this](const auto &X, const auto &U) { return EKFAcceleration(X, U); },
+ X, U, dt);
+ }
+
+ const ArmConstants arm_constants_;
+
+ // K3, K4 matricies described above.
+ const ::Eigen::Matrix<double, 2, 2> K3_;
+ const ::Eigen::Matrix<double, 2, 2> K3_inverse_;
+ const ::Eigen::Matrix<double, 2, 2> K4_;
+
+ private:
+ const double alpha_;
+ const double beta_;
+ const double gamma_;
+};
+
+} // namespace arm
+} // namespace control_loops
+} // namespace frc971
+
+#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DYNAMICS_H_
diff --git a/frc971/control_loops/double_jointed_arm/dynamics_test.cc b/frc971/control_loops/double_jointed_arm/dynamics_test.cc
new file mode 100644
index 0000000..6e12f75
--- /dev/null
+++ b/frc971/control_loops/double_jointed_arm/dynamics_test.cc
@@ -0,0 +1,53 @@
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/test_constants.h"
+
+#include "gtest/gtest.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace arm {
+namespace testing {
+
+// Tests that zero inputs result in no acceleration and no motion.
+// This isn't all that rigerous, but it's a good start.
+TEST(DynamicsTest, Acceleration) {
+ Dynamics dynamics(kArmConstants);
+
+ EXPECT_TRUE(dynamics
+ .Acceleration(::Eigen::Matrix<double, 4, 1>::Zero(),
+ ::Eigen::Matrix<double, 2, 1>::Zero())
+ .isApprox(::Eigen::Matrix<double, 4, 1>::Zero()));
+
+ EXPECT_TRUE(
+ dynamics
+ .UnboundedDiscreteDynamics(::Eigen::Matrix<double, 4, 1>::Zero(),
+ ::Eigen::Matrix<double, 2, 1>::Zero(), 0.1)
+ .isApprox(::Eigen::Matrix<double, 4, 1>::Zero()));
+
+ const ::Eigen::Matrix<double, 4, 1> X =
+ (::Eigen::Matrix<double, 4, 1>() << M_PI / 2.0, 0.0, 0.0, 0.0).finished();
+
+ ::std::cout << dynamics.FF_U(X, ::Eigen::Matrix<double, 2, 1>::Zero(),
+ ::Eigen::Matrix<double, 2, 1>::Zero())
+ << ::std::endl;
+
+ ::std::cout << dynamics.UnboundedDiscreteDynamics(
+ X,
+ dynamics.FF_U(X, ::Eigen::Matrix<double, 2, 1>::Zero(),
+ ::Eigen::Matrix<double, 2, 1>::Zero()),
+ 0.01)
+ << ::std::endl;
+
+ EXPECT_TRUE(dynamics
+ .UnboundedDiscreteDynamics(
+ X,
+ dynamics.FF_U(X, ::Eigen::Matrix<double, 2, 1>::Zero(),
+ ::Eigen::Matrix<double, 2, 1>::Zero()),
+ 0.01)
+ .isApprox(X));
+}
+
+} // namespace testing
+} // namespace arm
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2018/control_loops/superstructure/arm/ekf.cc b/frc971/control_loops/double_jointed_arm/ekf.cc
similarity index 87%
rename from y2018/control_loops/superstructure/arm/ekf.cc
rename to frc971/control_loops/double_jointed_arm/ekf.cc
index 48a71f4..a70e4a6 100644
--- a/y2018/control_loops/superstructure/arm/ekf.cc
+++ b/frc971/control_loops/double_jointed_arm/ekf.cc
@@ -1,19 +1,18 @@
-#include "y2018/control_loops/superstructure/arm/ekf.h"
+#include "frc971/control_loops/double_jointed_arm/ekf.h"
-#include "Eigen/Dense"
#include <iostream>
+#include "Eigen/Dense"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/jacobian.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
DEFINE_double(proximal_voltage_error_uncertainty, 8.0,
"Proximal joint voltage error uncertainty.");
DEFINE_double(distal_voltage_error_uncertainty, 2.0,
"Distal joint voltage error uncertainty.");
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
namespace {
@@ -29,7 +28,7 @@
.asDiagonal());
} // namespace
-EKF::EKF() {
+EKF::EKF(const Dynamics *dynamics) : dynamics_(dynamics) {
X_hat_.setZero();
Q_covariance =
((::Eigen::DiagonalMatrix<double, 6>().diagonal() << ::std::pow(0.1, 2),
@@ -69,9 +68,12 @@
void EKF::Predict(const ::Eigen::Matrix<double, 2, 1> &U, double dt) {
const ::Eigen::Matrix<double, 6, 6> A =
::frc971::control_loops::NumericalJacobianX<6, 2>(
- Dynamics::UnboundedEKFDiscreteDynamics, X_hat_, U, dt);
+ [this](const auto &X_hat_, const auto &U, double dt) {
+ return dynamics_->UnboundedEKFDiscreteDynamics(X_hat_, U, dt);
+ },
+ X_hat_, U, dt);
- X_hat_ = Dynamics::UnboundedEKFDiscreteDynamics(X_hat_, U, dt);
+ X_hat_ = dynamics_->UnboundedEKFDiscreteDynamics(X_hat_, U, dt);
P_ = A * P_ * A.transpose() + Q_covariance;
}
@@ -83,8 +85,8 @@
.asDiagonal());
// H is the jacobian of the h(x) measurement prediction function
const ::Eigen::Matrix<double, 2, 6> H_jacobian =
- (::Eigen::Matrix<double, 2, 6>() << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0,
- 0.0, 0.0, 1.0, 0.0, 0.0, 0.0)
+ (::Eigen::Matrix<double, 2, 6>() << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
+ 0.0, 1.0, 0.0, 0.0, 0.0)
.finished();
// Update step Measurement residual error of proximal and distal joint
@@ -106,6 +108,5 @@
}
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
diff --git a/y2018/control_loops/superstructure/arm/ekf.h b/frc971/control_loops/double_jointed_arm/ekf.h
similarity index 81%
rename from y2018/control_loops/superstructure/arm/ekf.h
rename to frc971/control_loops/double_jointed_arm/ekf.h
index 9ae8b47..d969e82 100644
--- a/y2018/control_loops/superstructure/arm/ekf.h
+++ b/frc971/control_loops/double_jointed_arm/ekf.h
@@ -1,11 +1,11 @@
-#ifndef Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_EKF_H_
-#define Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_EKF_H_
+#ifndef FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_EKF_H_
+#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_EKF_H_
#include "Eigen/Dense"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
// An extended kalman filter for the Arm.
@@ -13,7 +13,7 @@
// [theta0, omega0, theta1, omega1, voltage error0, voltage error1]
class EKF {
public:
- EKF();
+ EKF(const Dynamics *dynamics);
// Resets the internal state back to X. Resets the torque disturbance to 0.
void Reset(const ::Eigen::Matrix<double, 4, 1> &X);
@@ -43,11 +43,12 @@
::Eigen::Matrix<double, 6, 6> P_half_converged_;
::Eigen::Matrix<double, 6, 6> P_converged_;
::Eigen::Matrix<double, 6, 6> P_reset_;
+
+ const Dynamics *dynamics_;
};
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
-#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_EKF_H_
+#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_EKF_H_
diff --git a/y2018/control_loops/superstructure/arm/graph.cc b/frc971/control_loops/double_jointed_arm/graph.cc
similarity index 92%
rename from y2018/control_loops/superstructure/arm/graph.cc
rename to frc971/control_loops/double_jointed_arm/graph.cc
index ad6f982..b5a70ab 100644
--- a/y2018/control_loops/superstructure/arm/graph.cc
+++ b/frc971/control_loops/double_jointed_arm/graph.cc
@@ -1,11 +1,10 @@
-#include "y2018/control_loops/superstructure/arm/graph.h"
+#include "frc971/control_loops/double_jointed_arm/graph.h"
#include <algorithm>
#include <cassert>
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
SearchGraph::SearchGraph(size_t num_vertexes, std::initializer_list<Edge> edges)
@@ -68,6 +67,5 @@
}
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
diff --git a/y2018/control_loops/superstructure/arm/graph.h b/frc971/control_loops/double_jointed_arm/graph.h
similarity index 94%
rename from y2018/control_loops/superstructure/arm/graph.h
rename to frc971/control_loops/double_jointed_arm/graph.h
index 2300d6a..06d396c 100644
--- a/y2018/control_loops/superstructure/arm/graph.h
+++ b/frc971/control_loops/double_jointed_arm/graph.h
@@ -1,5 +1,5 @@
-#ifndef Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_GRAPH_H_
-#define Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_GRAPH_H_
+#ifndef FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_GRAPH_H_
+#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_GRAPH_H_
#include <algorithm>
#include <cassert>
@@ -8,9 +8,8 @@
#include <memory>
#include <vector>
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
// Grr... normal priority queues don't allow modifying the node cost.
@@ -183,8 +182,7 @@
};
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
-#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_GRAPH_H_
+#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_GRAPH_H_
diff --git a/y2018/control_loops/superstructure/arm/graph_test.cc b/frc971/control_loops/double_jointed_arm/graph_test.cc
similarity index 90%
rename from y2018/control_loops/superstructure/arm/graph_test.cc
rename to frc971/control_loops/double_jointed_arm/graph_test.cc
index 8f246a5..7b14ced 100644
--- a/y2018/control_loops/superstructure/arm/graph_test.cc
+++ b/frc971/control_loops/double_jointed_arm/graph_test.cc
@@ -1,10 +1,9 @@
-#include "y2018/control_loops/superstructure/arm/graph.h"
+#include "frc971/control_loops/double_jointed_arm/graph.h"
#include "gtest/gtest.h"
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
namespace testing {
@@ -68,6 +67,5 @@
} // namespace testing
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
diff --git a/frc971/control_loops/double_jointed_arm/test_constants.h b/frc971/control_loops/double_jointed_arm/test_constants.h
new file mode 100644
index 0000000..ea1d3b7
--- /dev/null
+++ b/frc971/control_loops/double_jointed_arm/test_constants.h
@@ -0,0 +1,53 @@
+#ifndef FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TEST_CONSTANTS_H_
+#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TEST_CONSTANTS_H_
+
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace arm {
+namespace testing {
+
+constexpr double kEfficiencyTweak = 0.95;
+constexpr double kStallTorque = 1.41 * kEfficiencyTweak;
+constexpr double kFreeSpeed = (5840.0 / 60.0) * 2.0 * M_PI;
+constexpr double kStallCurrent = 89.0;
+
+constexpr ArmConstants kArmConstants = {
+ .l1 = 46.25 * 0.0254,
+ .l2 = 41.80 * 0.0254,
+ .m1 = 9.34 / 2.2,
+ .m2 = 9.77 / 2.2,
+
+ // Moment of inertia of the joints in kg m^2
+ .j1 = 2957.05 * 0.0002932545454545454,
+ .j2 = 2824.70 * 0.0002932545454545454,
+
+ // Radius of the center of mass of the joints in meters.
+ .r1 = 21.64 * 0.0254,
+ .r2 = 26.70 * 0.0254,
+
+ // Gear ratios for the two joints.
+ .g1 = 140.0,
+ .g2 = 90.0,
+
+ // MiniCIM motor constants.
+ .efficiency_tweak = kEfficiencyTweak,
+ .stall_torque = kStallTorque,
+ .free_speed = kFreeSpeed,
+ .stall_current = kStallCurrent,
+ .resistance = 12.0 / kStallCurrent,
+ .Kv = kFreeSpeed / 12.0,
+ .Kt = kStallTorque / kStallCurrent,
+
+ // Number of motors on the distal joint.
+ .num_distal_motors = 2.0,
+};
+
+} // namespace testing
+} // namespace arm
+} // namespace control_loops
+} // namespace frc971
+
+#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TEST_CONSTANTS_H_
+
diff --git a/y2018/control_loops/superstructure/arm/trajectory.cc b/frc971/control_loops/double_jointed_arm/trajectory.cc
similarity index 92%
rename from y2018/control_loops/superstructure/arm/trajectory.cc
rename to frc971/control_loops/double_jointed_arm/trajectory.cc
index c6e09dd..d389eee 100644
--- a/y2018/control_loops/superstructure/arm/trajectory.cc
+++ b/frc971/control_loops/double_jointed_arm/trajectory.cc
@@ -1,20 +1,19 @@
-#include "y2018/control_loops/superstructure/arm/trajectory.h"
+#include "frc971/control_loops/double_jointed_arm/trajectory.h"
#include "Eigen/Dense"
#include "aos/logging/logging.h"
#include "frc971/control_loops/dlqr.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/jacobian.h"
#include "gflags/gflags.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
DEFINE_double(lqr_proximal_pos, 0.15, "Position LQR gain");
DEFINE_double(lqr_proximal_vel, 4.0, "Velocity LQR gain");
DEFINE_double(lqr_distal_pos, 0.20, "Position LQR gain");
DEFINE_double(lqr_distal_vel, 4.0, "Velocity LQR gain");
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
Path Path::Reversed(const Path &p) {
@@ -106,9 +105,9 @@
::Eigen::Matrix<double, 2, 2> K2;
const ::Eigen::Matrix<double, 2, 1> gravity_volts =
- Dynamics::K3_inverse * Dynamics::GravityTorque(X);
+ dynamics_->K3_inverse_ * dynamics_->GravityTorque(X);
- Dynamics::NormilizedMatriciesForState(X, &K1, &K2);
+ dynamics_->NormilizedMatriciesForState(X, &K1, &K2);
const ::Eigen::Matrix<double, 2, 2> omega_square =
(::Eigen::Matrix<double, 2, 2>() << omega(0, 0), 0.0, 0.0, omega(1, 0))
@@ -123,18 +122,18 @@
::std::sqrt(1.0 / ::std::max(0.001, (alpha_unitizer * alpha).norm()));
const ::Eigen::Matrix<double, 2, 1> vk1 =
- Dynamics::K3_inverse * (K1 * alpha + K2 * omega_square * omega);
+ dynamics_->K3_inverse_ * (K1 * alpha + K2 * omega_square * omega);
const ::Eigen::Matrix<double, 2, 1> vk2 =
- Dynamics::K3_inverse * Dynamics::K4 * omega;
+ dynamics_->K3_inverse_ * dynamics_->K4_ * omega;
// Loop through all the various vmin, plan_vmax combinations.
for (const double c : {-plan_vmax, plan_vmax}) {
// Also loop through saturating theta0 and theta1
for (const ::std::tuple<double, double, double> &abgravity :
{::std::tuple<double, double, double>{vk1(0), vk2(0),
- gravity_volts(0)},
+ gravity_volts(0)},
::std::tuple<double, double, double>{vk1(1), vk2(1),
- gravity_volts(1)}}) {
+ gravity_volts(1)}}) {
const double a = ::std::get<0>(abgravity);
const double b = ::std::get<1>(abgravity);
const double gravity = ::std::get<2>(abgravity);
@@ -178,19 +177,19 @@
::Eigen::Matrix<double, 2, 2> K1;
::Eigen::Matrix<double, 2, 2> K2;
- Dynamics::NormilizedMatriciesForState(X, &K1, &K2);
+ dynamics_->NormilizedMatriciesForState(X, &K1, &K2);
const ::Eigen::Matrix<double, 2, 2> omega_square =
(::Eigen::Matrix<double, 2, 2>() << omega(0, 0), 0.0, 0.0, omega(1, 0))
.finished();
const ::Eigen::Matrix<double, 2, 1> k_constant =
- Dynamics::K3_inverse *
+ dynamics_->K3_inverse_ *
((K1 * alpha + K2 * omega_square * omega) * goal_velocity *
goal_velocity +
- Dynamics::K4 * omega * goal_velocity - Dynamics::GravityTorque(X));
+ dynamics_->K4_ * omega * goal_velocity - dynamics_->GravityTorque(X));
const ::Eigen::Matrix<double, 2, 1> k_scalar =
- Dynamics::K3_inverse * K1 * omega;
+ dynamics_->K3_inverse_ * K1 * omega;
const double constraint_goal_acceleration =
::std::sqrt(
@@ -236,19 +235,19 @@
::Eigen::Matrix<double, 2, 2> K1;
::Eigen::Matrix<double, 2, 2> K2;
- Dynamics::NormilizedMatriciesForState(X, &K1, &K2);
+ dynamics_->NormilizedMatriciesForState(X, &K1, &K2);
const ::Eigen::Matrix<double, 2, 2> omega_square =
(::Eigen::Matrix<double, 2, 2>() << omega(0, 0), 0.0, 0.0, omega(1, 0))
.finished();
const ::Eigen::Matrix<double, 2, 1> k_constant =
- Dynamics::K3_inverse *
+ dynamics_->K3_inverse_ *
((K1 * alpha + K2 * omega_square * omega) * goal_velocity *
goal_velocity +
- Dynamics::K4 * omega * goal_velocity - Dynamics::GravityTorque(X));
+ dynamics_->K4_ * omega * goal_velocity - dynamics_->GravityTorque(X));
const ::Eigen::Matrix<double, 2, 1> k_scalar =
- Dynamics::K3_inverse * K1 * omega;
+ dynamics_->K3_inverse_ * K1 * omega;
const double constraint_goal_acceleration =
::std::sqrt(
@@ -390,12 +389,22 @@
.finished()
.asDiagonal();
+ const auto x_blocked = X.block<4, 1>(0, 0);
+
const ::Eigen::Matrix<double, 4, 4> final_A =
::frc971::control_loops::NumericalJacobianX<4, 2>(
- Dynamics::UnboundedDiscreteDynamics, X.block<4, 1>(0, 0), U, 0.00505);
+ [this](const auto &x_blocked, const auto &U, double dt) {
+ return this->dynamics_->UnboundedDiscreteDynamics(
+ x_blocked, U, dt);
+ },
+ x_blocked, U, 0.00505);
+
const ::Eigen::Matrix<double, 4, 2> final_B =
::frc971::control_loops::NumericalJacobianU<4, 2>(
- Dynamics::UnboundedDiscreteDynamics, X.block<4, 1>(0, 0), U, 0.00505);
+ [this](const auto &x_blocked, const auto &U, double dt) {
+ return this->dynamics_->UnboundedDiscreteDynamics(x_blocked, U, dt);
+ },
+ x_blocked, U, 0.00505);
::Eigen::Matrix<double, 4, 4> S;
::Eigen::Matrix<double, 2, 4> sub_K;
@@ -441,7 +450,7 @@
*saturation_goal_acceleration);
const ::Eigen::Matrix<double, 6, 1> R = trajectory.R(theta_t, omega_t);
const ::Eigen::Matrix<double, 2, 1> U_ff =
- Dynamics::FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t);
+ dynamics_->FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t);
*U = U_ff + K * (R - X);
}
@@ -494,11 +503,11 @@
U_unsaturated_.setZero();
} else {
const ::Eigen::Matrix<double, 6, 1> R =
- trajectory_->R(theta_, ::Eigen::Matrix<double, 2, 1>::Zero());
+ Trajectory::R(theta_, ::Eigen::Matrix<double, 2, 1>::Zero());
- U_ff_ = Dynamics::FF_U(X.block<4, 1>(0, 0),
- ::Eigen::Matrix<double, 2, 1>::Zero(),
- ::Eigen::Matrix<double, 2, 1>::Zero());
+ U_ff_ = dynamics_->FF_U(
+ X.block<4, 1>(0, 0), ::Eigen::Matrix<double, 2, 1>::Zero(),
+ ::Eigen::Matrix<double, 2, 1>::Zero());
const ::Eigen::Matrix<double, 2, 6> K = K_at_state(X, U_ff_);
U_ = U_unsaturated_ = U_ff_ + K * (R - X);
@@ -558,7 +567,7 @@
const ::Eigen::Matrix<double, 6, 1> R = trajectory_->R(theta_t, omega_t);
- U_ff_ = Dynamics::FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t);
+ U_ff_ = dynamics_->FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t);
const ::Eigen::Matrix<double, 2, 6> K = K_at_state(X, U_ff_);
U_ = U_unsaturated_ = U_ff_ + K * (R - X);
@@ -613,6 +622,5 @@
}
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
diff --git a/y2018/control_loops/superstructure/arm/trajectory.h b/frc971/control_loops/double_jointed_arm/trajectory.h
similarity index 93%
rename from y2018/control_loops/superstructure/arm/trajectory.h
rename to frc971/control_loops/double_jointed_arm/trajectory.h
index a3a4246..a194a03 100644
--- a/y2018/control_loops/superstructure/arm/trajectory.h
+++ b/frc971/control_loops/double_jointed_arm/trajectory.h
@@ -1,5 +1,5 @@
-#ifndef Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_TRAJECTORY_H_
-#define Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_TRAJECTORY_H_
+#ifndef FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TRAJECTORY_H_
+#define FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TRAJECTORY_H_
#include <array>
#include <initializer_list>
@@ -7,10 +7,10 @@
#include <vector>
#include "Eigen/Dense"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
// This class represents a path in theta0, theta1 space. It also returns the
@@ -90,8 +90,10 @@
public:
// Constructs a trajectory (but doesn't calculate it) given a path and a step
// size.
- Trajectory(::std::unique_ptr<const Path> path, double gridsize)
- : path_(::std::move(path)),
+ Trajectory(const Dynamics *dynamics, ::std::unique_ptr<const Path> path,
+ double gridsize)
+ : dynamics_(dynamics),
+ path_(::std::move(path)),
num_plan_points_(
static_cast<size_t>(::std::ceil(path_->length() / gridsize) + 1)),
step_size_(path_->length() /
@@ -220,7 +222,8 @@
double GetDAcceleration(double distance) const {
return GetDAcceleration(distance, max_dvelocity_);
}
- double GetDAcceleration(double distance, const ::std::vector<double> &plan) const {
+ double GetDAcceleration(double distance,
+ const ::std::vector<double> &plan) const {
::std::pair<size_t, size_t> indices = IndicesForDistance(distance);
const double v0 = plan[indices.first];
const double v1 = plan[indices.second];
@@ -276,6 +279,7 @@
const Path &path() const { return *path_; }
+
private:
friend class testing::TrajectoryTest_IndicesForDistanceTest_Test;
@@ -298,6 +302,8 @@
return ::std::pair<size_t, size_t>(lower_index, lower_index + 1);
}
+ const Dynamics *dynamics_;
+
// The path to follow.
::std::unique_ptr<const Path> path_;
// The number of points in the plan.
@@ -315,14 +321,16 @@
// This class tracks the current goal along trajectories and paths.
class TrajectoryFollower {
public:
- TrajectoryFollower(const ::Eigen::Matrix<double, 2, 1> &theta)
- : trajectory_(nullptr), theta_(theta) {
+ TrajectoryFollower(const Dynamics *dynamics,
+ const ::Eigen::Matrix<double, 2, 1> &theta)
+ : dynamics_(dynamics), trajectory_(nullptr), theta_(theta) {
omega_.setZero();
last_K_.setZero();
Reset();
}
- TrajectoryFollower(Trajectory *const trajectory) : trajectory_(trajectory) {
+ TrajectoryFollower(const Dynamics *dynamics, Trajectory *const trajectory)
+ : dynamics_(dynamics), trajectory_(trajectory) {
last_K_.setZero();
Reset();
}
@@ -405,6 +413,7 @@
int failed_solutions() const { return failed_solutions_; }
private:
+ const Dynamics *dynamics_;
// The trajectory plan.
const Trajectory *trajectory_ = nullptr;
@@ -431,8 +440,7 @@
};
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
-#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_TRAJECTORY_H_
+#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TRAJECTORY_H_
diff --git a/y2018/control_loops/superstructure/arm/trajectory_test.cc b/frc971/control_loops/double_jointed_arm/trajectory_test.cc
similarity index 86%
rename from y2018/control_loops/superstructure/arm/trajectory_test.cc
rename to frc971/control_loops/double_jointed_arm/trajectory_test.cc
index b91c5a4..e700282 100644
--- a/y2018/control_loops/superstructure/arm/trajectory_test.cc
+++ b/frc971/control_loops/double_jointed_arm/trajectory_test.cc
@@ -1,13 +1,13 @@
-#include "y2018/control_loops/superstructure/arm/trajectory.h"
+#include "frc971/control_loops/double_jointed_arm/trajectory.h"
+#include "frc971/control_loops/double_jointed_arm/test_constants.h"
+#include "frc971/control_loops/double_jointed_arm/demo_path.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/ekf.h"
#include "gtest/gtest.h"
-#include "y2018/control_loops/superstructure/arm/demo_path.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
-#include "y2018/control_loops/superstructure/arm/ekf.h"
-namespace y2018 {
+namespace frc971 {
namespace control_loops {
-namespace superstructure {
namespace arm {
namespace testing {
@@ -75,20 +75,22 @@
(::Eigen::Matrix<double, 2, 1>() << 3.0, 0.0).finished()));
}
-
-// Tests that we can compute the indices of the plan for a given distance correctly.
+// Tests that we can compute the indices of the plan for a given distance
+// correctly.
TEST(TrajectoryTest, IndicesForDistanceTest) {
// Start with a stupid simple plan.
Path p({{{0.0, 0.0, 1.0, 0.0, 0.0, 0.0}},
{{1.0, 0.0, 1.0, 0.0, 0.0, 0.0}},
{{2.0, 0.0, 1.0, 0.0, 0.0, 0.0}},
{{3.0, 0.0, 1.0, 0.0, 0.0, 0.0}}});
- Trajectory t(::std::unique_ptr<Path>(new Path(p)), 0.1);
+ Dynamics dynamics(kArmConstants);
+ Trajectory t(&dynamics, ::std::unique_ptr<Path>(new Path(p)), 0.1);
// 0 - 3.0 every 0.1 should be 31 points.
EXPECT_EQ(t.num_plan_points(), 31);
- // Verify that something centered in a grid cell returns the points on either side.
+ // Verify that something centered in a grid cell returns the points on either
+ // side.
EXPECT_EQ(::std::make_pair(static_cast<size_t>(0), static_cast<size_t>(1)),
t.IndicesForDistance(0.05));
EXPECT_EQ(::std::make_pair(static_cast<size_t>(1), static_cast<size_t>(2)),
@@ -145,17 +147,21 @@
EXPECT_NEAR(path->length(), reversed_path->length(), 1e-6);
for (double d = 0; d < path->length(); d += 0.01) {
- EXPECT_TRUE(path->Theta(d).isApprox(reversed_path->Theta(path->length() - d)));
- EXPECT_TRUE(path->Omega(d).isApprox(-reversed_path->Omega(path->length() - d)));
- EXPECT_TRUE(path->Alpha(d).isApprox(reversed_path->Alpha(path->length() - d)));
+ EXPECT_TRUE(
+ path->Theta(d).isApprox(reversed_path->Theta(path->length() - d)));
+ EXPECT_TRUE(
+ path->Omega(d).isApprox(-reversed_path->Omega(path->length() - d)));
+ EXPECT_TRUE(
+ path->Alpha(d).isApprox(reversed_path->Alpha(path->length() - d)));
}
}
// Tests that we can follow a path. Look at :trajectory_plot if you want to see
// the path.
TEST(TrajectoryTest, RunTrajectory) {
+ Dynamics dynamics(kArmConstants);
::std::unique_ptr<Path> path = MakeDemoPath();
- Trajectory trajectory(::std::move(path), 0.001);
+ Trajectory trajectory(&dynamics, ::std::move(path), 0.001);
constexpr double kAlpha0Max = 40.0;
constexpr double kAlpha1Max = 60.0;
@@ -174,16 +180,17 @@
X << theta_t(0), 0.0, theta_t(1), 0.0;
}
- EKF arm_ekf;
+ EKF arm_ekf(&dynamics);
arm_ekf.Reset(X);
- TrajectoryFollower follower(&trajectory);
+ TrajectoryFollower follower(&dynamics, &trajectory);
constexpr double sim_dt = 0.00505;
while (t < 1.0) {
arm_ekf.Correct((::Eigen::Matrix<double, 2, 1>() << X(0), X(2)).finished(),
sim_dt);
follower.Update(arm_ekf.X_hat(), false, sim_dt, vmax, 12.0);
- X = Dynamics::UnboundedDiscreteDynamics(X, follower.U(), sim_dt);
+
+ X = dynamics.UnboundedDiscreteDynamics(X, follower.U(), sim_dt);
arm_ekf.Predict(follower.U(), sim_dt);
t += sim_dt;
}
@@ -204,6 +211,5 @@
} // namespace testing
} // namespace arm
-} // namespace superstructure
} // namespace control_loops
-} // namespace y2018
+} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/down_estimator_plotter.ts b/frc971/control_loops/drivetrain/down_estimator_plotter.ts
index 178ab0b..126336d 100644
--- a/frc971/control_loops/drivetrain/down_estimator_plotter.ts
+++ b/frc971/control_loops/drivetrain/down_estimator_plotter.ts
@@ -1,8 +1,8 @@
// Provides a basic plot for debugging IMU-related issues on a robot.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {ImuMessageHandler} from 'org_frc971/frc971/wpilib/imu_plot_utils';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import {ImuMessageHandler} from '../../../frc971/wpilib/imu_plot_utils';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/frc971/control_loops/drivetrain/drivetrain_plotter.ts b/frc971/control_loops/drivetrain/drivetrain_plotter.ts
index 4b59dc0..5610e97 100644
--- a/frc971/control_loops/drivetrain/drivetrain_plotter.ts
+++ b/frc971/control_loops/drivetrain/drivetrain_plotter.ts
@@ -1,8 +1,8 @@
// Provides a plot for debugging drivetrain-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {ImuMessageHandler} from 'org_frc971/frc971/wpilib/imu_plot_utils';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import {ImuMessageHandler} from '../../../frc971/wpilib/imu_plot_utils';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/frc971/control_loops/drivetrain/robot_state_plotter.ts b/frc971/control_loops/drivetrain/robot_state_plotter.ts
index 2ce8001..8cffd76 100644
--- a/frc971/control_loops/drivetrain/robot_state_plotter.ts
+++ b/frc971/control_loops/drivetrain/robot_state_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/frc971/control_loops/drivetrain/spline_plotter.ts b/frc971/control_loops/drivetrain/spline_plotter.ts
index c39afd5..67e9fc7 100644
--- a/frc971/control_loops/drivetrain/spline_plotter.ts
+++ b/frc971/control_loops/drivetrain/spline_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging drivetrain-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import * as proxy from '../../../aos/network/www/proxy';
import Connection = proxy.Connection;
diff --git a/frc971/image_streamer/www/proxy.ts b/frc971/image_streamer/www/proxy.ts
index bfe8135..517d203 100644
--- a/frc971/image_streamer/www/proxy.ts
+++ b/frc971/image_streamer/www/proxy.ts
@@ -1,5 +1,5 @@
import {Builder, ByteBuffer} from 'flatbuffers';
-import {Payload, SdpType, WebSocketIce, WebSocketMessage, WebSocketSdp} from 'org_frc971/aos/network/web_proxy_generated';
+import {Payload, SdpType, WebSocketIce, WebSocketMessage, WebSocketSdp} from '../../../aos/network/web_proxy_generated';
// Port 9 is used to indicate an active (outgoing) TCP connection. The server
// would send a corresponding candidate with the actual TCP port it is
diff --git a/frc971/rockpi/build_rootfs.sh b/frc971/rockpi/build_rootfs.sh
index 2e16419..bb8b84a 100755
--- a/frc971/rockpi/build_rootfs.sh
+++ b/frc971/rockpi/build_rootfs.sh
@@ -195,7 +195,7 @@
target "apt-get -y install -t bullseye-backports bpfcc-tools"
-target "apt-get install -y sudo openssh-server python3 bash-completion git v4l-utils cpufrequtils pmount rsync vim-nox chrony libopencv-calib3d4.5 libopencv-contrib4.5 libopencv-core4.5 libopencv-features2d4.5 libopencv-flann4.5 libopencv-highgui4.5 libopencv-imgcodecs4.5 libopencv-imgproc4.5 libopencv-ml4.5 libopencv-objdetect4.5 libopencv-photo4.5 libopencv-shape4.5 libopencv-stitching4.5 libopencv-superres4.5 libopencv-video4.5 libopencv-videoio4.5 libopencv-videostab4.5 libopencv-viz4.5 libnice10 pmount libnice-dev feh libgstreamer1.0-0 libgstreamer-plugins-base1.0-0 libgstreamer-plugins-bad1.0-0 gstreamer1.0-plugins-base gstreamer1.0-plugins-good gstreamer1.0-plugins-bad gstreamer1.0-plugins-ugly gstreamer1.0-nice usbutils locales trace-cmd clinfo jq strace sysstat"
+target "apt-get install -y sudo openssh-server python3 bash-completion git v4l-utils cpufrequtils pmount rsync vim-nox chrony libopencv-calib3d4.5 libopencv-contrib4.5 libopencv-core4.5 libopencv-features2d4.5 libopencv-flann4.5 libopencv-highgui4.5 libopencv-imgcodecs4.5 libopencv-imgproc4.5 libopencv-ml4.5 libopencv-objdetect4.5 libopencv-photo4.5 libopencv-shape4.5 libopencv-stitching4.5 libopencv-superres4.5 libopencv-video4.5 libopencv-videoio4.5 libopencv-videostab4.5 libopencv-viz4.5 libnice10 pmount libnice-dev feh libgstreamer1.0-0 libgstreamer-plugins-base1.0-0 libgstreamer-plugins-bad1.0-0 gstreamer1.0-plugins-base gstreamer1.0-plugins-good gstreamer1.0-plugins-bad gstreamer1.0-plugins-ugly gstreamer1.0-nice usbutils locales trace-cmd clinfo jq strace sysstat lm-sensors"
target "cd /tmp && wget https://software.frc971.org/Build-Dependencies/libmali-midgard-t86x-r14p0-x11_1.9-1_arm64.deb && sudo dpkg -i libmali-midgard-t86x-r14p0-x11_1.9-1_arm64.deb && rm libmali-midgard-t86x-r14p0-x11_1.9-1_arm64.deb"
target "apt-get clean"
@@ -229,6 +229,7 @@
copyfile root.root 644 etc/udev/rules.d/99-usb-mount.rules
copyfile root.root 644 etc/udev/rules.d/99-adis16505.rules
copyfile root.root 644 etc/udev/rules.d/99-mali.rules
+copyfile root.root 644 etc/chrony/chrony.conf
target "apt-get update"
diff --git a/frc971/rockpi/contents/etc/chrony/chrony.conf b/frc971/rockpi/contents/etc/chrony/chrony.conf
new file mode 100644
index 0000000..6e03143
--- /dev/null
+++ b/frc971/rockpi/contents/etc/chrony/chrony.conf
@@ -0,0 +1,59 @@
+# Welcome to the chrony configuration file. See chrony.conf(5) for more
+# information about usable directives.
+
+# Include configuration files found in /etc/chrony/conf.d.
+confdir /etc/chrony/conf.d
+
+# Use Debian vendor zone.
+pool 2.debian.pool.ntp.org iburst
+
+# Use time sources from DHCP.
+sourcedir /run/chrony-dhcp
+
+# Use NTP sources found in /etc/chrony/sources.d.
+sourcedir /etc/chrony/sources.d
+
+# This directive specify the location of the file containing ID/key pairs for
+# NTP authentication.
+keyfile /etc/chrony/chrony.keys
+
+# This directive specify the file into which chronyd will store the rate
+# information.
+driftfile /var/lib/chrony/chrony.drift
+
+# Save NTS keys and cookies.
+ntsdumpdir /var/lib/chrony
+
+# Uncomment the following line to turn logging on.
+#log tracking measurements statistics
+
+# Log files location.
+logdir /var/log/chrony
+
+# Stop bad estimates upsetting machine clock.
+maxupdateskew 100.0
+
+# This directive enables kernel synchronisation (every 11 minutes) of the
+# real-time clock. Note that it can’t be used along with the 'rtcfile' directive.
+rtcsync
+
+# Always step the time if it's more than 4ms off.
+makestep 0.004 -1
+
+# The next 2 settings are used to control how much slewing of the clock chrony
+# is allowed to do. The total will be the sum of both and we have a hard limit
+# at 500ppm coming from AOS.
+
+# The maximum slewing allowed to correct an offset with the reference clock.
+# Note that this value doesn't include corrections due to frequency errors
+# (drift).
+maxslewrate 200
+
+# Maximum frequency error (drift) of the clock. Chrony will try to compensate
+# for drift and this setting limits how large that correction can be.
+maxdrift 100
+
+# Get TAI-UTC offset and leap seconds from the system tz database.
+# This directive must be commented out when using time sources serving
+# leap-smeared time.
+leapsectz right/UTC
diff --git a/frc971/wpilib/imu_plot_utils.ts b/frc971/wpilib/imu_plot_utils.ts
index c4b516b..a56fd9b 100644
--- a/frc971/wpilib/imu_plot_utils.ts
+++ b/frc971/wpilib/imu_plot_utils.ts
@@ -1,9 +1,9 @@
// This script provides a basic utility for de-batching the IMUValues
// message. See imu_plotter.ts for usage.
-import {IMUValuesBatch} from 'org_frc971/frc971/wpilib/imu_batch_generated';
-import {MessageHandler, TimestampedMessage} from 'org_frc971/aos/network/www/aos_plotter';
-import {Point} from 'org_frc971/aos/network/www/plotter';
-import {Table} from 'org_frc971/aos/network/www/reflection';
+import {IMUValuesBatch} from './imu_batch_generated';
+import {MessageHandler, TimestampedMessage} from '../../aos/network/www/aos_plotter';
+import {Point} from '../../aos/network/www/plotter';
+import {Table} from '../../aos/network/www/reflection';
import {ByteBuffer} from 'flatbuffers';
import {Schema} from 'flatbuffers_reflection/reflection_generated';
diff --git a/frc971/wpilib/imu_plotter.ts b/frc971/wpilib/imu_plotter.ts
index 6768e1c..91edd7c 100644
--- a/frc971/wpilib/imu_plotter.ts
+++ b/frc971/wpilib/imu_plotter.ts
@@ -1,7 +1,7 @@
// Provides a basic plot for debugging IMU-related issues on a robot.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {ImuMessageHandler} from 'org_frc971/frc971/wpilib/imu_plot_utils';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {AosPlotter} from '../../aos/network/www/aos_plotter';
+import {ImuMessageHandler} from '../../frc971/wpilib/imu_plot_utils';
+import * as proxy from '../../aos/network/www/proxy';
import Connection = proxy.Connection;
diff --git a/pnpm-lock.yaml b/pnpm-lock.yaml
new file mode 100644
index 0000000..65a160f
--- /dev/null
+++ b/pnpm-lock.yaml
@@ -0,0 +1,4373 @@
+lockfileVersion: 5.4
+
+importers:
+
+ .:
+ specifiers:
+ '@angular/animations': 15.0.1
+ '@angular/cli': 15.0.1
+ '@angular/common': 15.0.1
+ '@angular/compiler': 15.0.1
+ '@angular/compiler-cli': 15.0.1
+ '@angular/core': 15.0.1
+ '@angular/forms': 15.0.1
+ '@angular/platform-browser': 15.0.1
+ '@babel/cli': ^7.6.0
+ '@babel/core': ^7.6.0
+ '@rollup/plugin-node-resolve': 13.1.3
+ '@types/flatbuffers': 1.10.0
+ '@types/jasmine': 3.10.3
+ '@types/node': 17.0.21
+ cypress: 12.3.0
+ html-insert-assets: 0.14.3
+ jasmine: 3.10.0
+ karma: 6.4.1
+ karma-chrome-launcher: 3.1.0
+ karma-firefox-launcher: 2.1.2
+ karma-jasmine: 4.0.1
+ karma-requirejs: 1.1.0
+ karma-sourcemap-loader: 0.3.8
+ prettier: 2.6.1
+ protractor: 7.0.0
+ requirejs: 2.3.6
+ rollup: 2.66.1
+ rxjs: 7.5.7
+ terser: 5.10.0
+ typescript: 4.8.4
+ zone.js: ^0.11.4
+ devDependencies:
+ '@angular/animations': 15.0.1_@angular+core@15.0.1
+ '@angular/cli': 15.0.1
+ '@angular/common': 15.0.1_gc4fl5hkkh62bvf2jldebe7kfi
+ '@angular/compiler': 15.0.1_@angular+core@15.0.1
+ '@angular/compiler-cli': 15.0.1_cjgqlygpi5ntpb3clzn7pzsmpy
+ '@angular/core': 15.0.1_rxjs@7.5.7+zone.js@0.11.8
+ '@angular/forms': 15.0.1_lshev2zdnaa2h7gkxro3dgbuau
+ '@angular/platform-browser': 15.0.1_elnjnvrny24npcy6jcashrycoy
+ '@babel/cli': 7.20.7_@babel+core@7.20.12
+ '@babel/core': 7.20.12
+ '@rollup/plugin-node-resolve': 13.1.3_rollup@2.66.1
+ '@types/flatbuffers': 1.10.0
+ '@types/jasmine': 3.10.3
+ '@types/node': 17.0.21
+ cypress: 12.3.0
+ html-insert-assets: 0.14.3
+ jasmine: 3.10.0
+ karma: 6.4.1
+ karma-chrome-launcher: 3.1.0
+ karma-firefox-launcher: 2.1.2
+ karma-jasmine: 4.0.1_karma@6.4.1
+ karma-requirejs: 1.1.0_rexopxsgq4andhwzqrad3qy2ka
+ karma-sourcemap-loader: 0.3.8
+ prettier: 2.6.1
+ protractor: 7.0.0
+ requirejs: 2.3.6
+ rollup: 2.66.1
+ rxjs: 7.5.7
+ terser: 5.10.0
+ typescript: 4.8.4
+ zone.js: 0.11.8
+
+packages:
+
+ /@ampproject/remapping/2.2.0:
+ resolution: {integrity: sha512-qRmjj8nj9qmLTQXXmaR1cck3UXSRMPrbsLJAasZpF+t3riI71BXed5ebIOYwQntykeZuhjsdweEc9BxH5Jc26w==}
+ engines: {node: '>=6.0.0'}
+ dependencies:
+ '@jridgewell/gen-mapping': 0.1.1
+ '@jridgewell/trace-mapping': 0.3.17
+ dev: true
+
+ /@angular-devkit/architect/0.1500.1:
+ resolution: {integrity: sha512-HoGMdUB9z1brPq3f0m3la6N0ODBarH5LjZN+5KyIMdXgJJN5y+gs2H6yCPQfJT56fqtp/cckxOYcLAFTf45Tcg==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0, npm: ^6.11.0 || ^7.5.6 || >=8.0.0, yarn: '>= 1.13.0'}
+ dependencies:
+ '@angular-devkit/core': 15.0.1
+ rxjs: 6.6.7
+ transitivePeerDependencies:
+ - chokidar
+ dev: true
+
+ /@angular-devkit/core/15.0.1:
+ resolution: {integrity: sha512-Q8sF561Wf53ufdrKWvsqebbD5EjJpdHaPjg5nAHYwPtwD1ciG7oL55cQFs0LYqy9Ux6k34NimodhH3QgXYYPFQ==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0, npm: ^6.11.0 || ^7.5.6 || >=8.0.0, yarn: '>= 1.13.0'}
+ peerDependencies:
+ chokidar: ^3.5.2
+ peerDependenciesMeta:
+ chokidar:
+ optional: true
+ dependencies:
+ ajv: 8.11.0
+ ajv-formats: 2.1.1
+ jsonc-parser: 3.2.0
+ rxjs: 6.6.7
+ source-map: 0.7.4
+ dev: true
+
+ /@angular-devkit/schematics/15.0.1:
+ resolution: {integrity: sha512-DS9t+xl1lOphYkdz17FwRO0LUs5IYBpyqr3O8SqrXESOhVUXlbcEhVtVeQiYxfeQZVRPWVR64Tf6E6ELXcGLYw==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0, npm: ^6.11.0 || ^7.5.6 || >=8.0.0, yarn: '>= 1.13.0'}
+ dependencies:
+ '@angular-devkit/core': 15.0.1
+ jsonc-parser: 3.2.0
+ magic-string: 0.26.7
+ ora: 5.4.1
+ rxjs: 6.6.7
+ transitivePeerDependencies:
+ - chokidar
+ dev: true
+
+ /@angular/animations/15.0.1_@angular+core@15.0.1:
+ resolution: {integrity: sha512-GfxqpRcoRfQNS1pVA+PadcgCGJSFag07jFJIQUHX3HZkI/4PyXGn/7ptgebN3tBjy+ASk4PBOQP/ntGbrr55zw==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ '@angular/core': 15.0.1
+ dependencies:
+ '@angular/core': 15.0.1_rxjs@7.5.7+zone.js@0.11.8
+ tslib: 2.4.1
+ dev: true
+
+ /@angular/cli/15.0.1:
+ resolution: {integrity: sha512-ntwJxtzGuHl07eb56x8WM6tQ3YhBKCP61o8WoHBrOBEFNm9rEV9C2webMIWYVFAa0iG1pmDq6U5Qc7WFPM9rtg==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0, npm: ^6.11.0 || ^7.5.6 || >=8.0.0, yarn: '>= 1.13.0'}
+ hasBin: true
+ dependencies:
+ '@angular-devkit/architect': 0.1500.1
+ '@angular-devkit/core': 15.0.1
+ '@angular-devkit/schematics': 15.0.1
+ '@schematics/angular': 15.0.1
+ '@yarnpkg/lockfile': 1.1.0
+ ansi-colors: 4.1.3
+ ini: 3.0.1
+ inquirer: 8.2.4
+ jsonc-parser: 3.2.0
+ npm-package-arg: 9.1.2
+ npm-pick-manifest: 8.0.1
+ open: 8.4.0
+ ora: 5.4.1
+ pacote: 15.0.6
+ resolve: 1.22.1
+ semver: 7.3.8
+ symbol-observable: 4.0.0
+ yargs: 17.6.2
+ transitivePeerDependencies:
+ - bluebird
+ - chokidar
+ - supports-color
+ dev: true
+
+ /@angular/common/15.0.1_gc4fl5hkkh62bvf2jldebe7kfi:
+ resolution: {integrity: sha512-XRD1Dj2aINyp5yYueCuwLU1y84z+ZFXeO84oNfwIu0unHszuo02iIzrV+yCm/ATwt6qUkIbe6xhZNjUorZecyA==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ '@angular/core': 15.0.1
+ rxjs: ^6.5.3 || ^7.4.0
+ dependencies:
+ '@angular/core': 15.0.1_rxjs@7.5.7+zone.js@0.11.8
+ rxjs: 7.5.7
+ tslib: 2.4.1
+ dev: true
+
+ /@angular/compiler-cli/15.0.1_cjgqlygpi5ntpb3clzn7pzsmpy:
+ resolution: {integrity: sha512-M2VsKBw8dQMC5p3PmpM+EBZAZ9Qk/rGX+aIHYBGzsgGFqYMEcz6Nxrj4v6I3Hta7tW7QEVXf883rXiWxHlwtbw==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ hasBin: true
+ peerDependencies:
+ '@angular/compiler': 15.0.1
+ typescript: '>=4.8.2 <4.9'
+ dependencies:
+ '@angular/compiler': 15.0.1_@angular+core@15.0.1
+ '@babel/core': 7.20.12
+ chokidar: 3.5.3
+ convert-source-map: 1.9.0
+ dependency-graph: 0.11.0
+ magic-string: 0.26.7
+ reflect-metadata: 0.1.13
+ semver: 7.3.8
+ sourcemap-codec: 1.4.8
+ tslib: 2.4.1
+ typescript: 4.8.4
+ yargs: 17.6.2
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /@angular/compiler/15.0.1_@angular+core@15.0.1:
+ resolution: {integrity: sha512-4talkxip79XPfoj69qgY8VXV1KIBKOyZCRWHhNVqMdECyw/fceVWN4r8kDL0qOTBh1CKmhoQFXQilr9g7nFatA==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ '@angular/core': 15.0.1
+ peerDependenciesMeta:
+ '@angular/core':
+ optional: true
+ dependencies:
+ '@angular/core': 15.0.1_rxjs@7.5.7+zone.js@0.11.8
+ tslib: 2.4.1
+ dev: true
+
+ /@angular/core/15.0.1_rxjs@7.5.7+zone.js@0.11.8:
+ resolution: {integrity: sha512-idaKf9hhguyGn/yj5KMHIUEvW4PpeYcwlRUSoEskQC1799BsXwJyV0AwZ67GH1ltnAj34gbhMhDedcCLdhOffA==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ rxjs: ^6.5.3 || ^7.4.0
+ zone.js: ~0.11.4 || ~0.12.0
+ dependencies:
+ rxjs: 7.5.7
+ tslib: 2.4.1
+ zone.js: 0.11.8
+ dev: true
+
+ /@angular/forms/15.0.1:
+ resolution: {integrity: sha512-gNj/fY7B7swczWI3jpJK4904W0WHCrYviZB8m97P4MkcxdMfQezp4VoRsj+vIkKGtUPUWje3uIjzqodhJlxIJA==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ '@angular/common': 15.0.1
+ '@angular/core': 15.0.1
+ '@angular/platform-browser': 15.0.1
+ rxjs: ^6.5.3 || ^7.4.0
+ dependencies:
+ tslib: 2.4.1
+ dev: false
+
+ /@angular/forms/15.0.1_lshev2zdnaa2h7gkxro3dgbuau:
+ resolution: {integrity: sha512-gNj/fY7B7swczWI3jpJK4904W0WHCrYviZB8m97P4MkcxdMfQezp4VoRsj+vIkKGtUPUWje3uIjzqodhJlxIJA==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ '@angular/common': 15.0.1
+ '@angular/core': 15.0.1
+ '@angular/platform-browser': 15.0.1
+ rxjs: ^6.5.3 || ^7.4.0
+ dependencies:
+ '@angular/common': 15.0.1_gc4fl5hkkh62bvf2jldebe7kfi
+ '@angular/core': 15.0.1_rxjs@7.5.7+zone.js@0.11.8
+ '@angular/platform-browser': 15.0.1_elnjnvrny24npcy6jcashrycoy
+ rxjs: 7.5.7
+ tslib: 2.4.1
+ dev: true
+
+ /@angular/platform-browser/15.0.1_elnjnvrny24npcy6jcashrycoy:
+ resolution: {integrity: sha512-fH0EfRgbQC0ql8V1ZWVfF75H9lSjT2T6uGfR8cBdRAO/RWwWgx/TfFsjdWAZtjuKRZnKY3wRQ/yVYeQarC3n0Q==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0}
+ peerDependencies:
+ '@angular/animations': 15.0.1
+ '@angular/common': 15.0.1
+ '@angular/core': 15.0.1
+ peerDependenciesMeta:
+ '@angular/animations':
+ optional: true
+ dependencies:
+ '@angular/animations': 15.0.1_@angular+core@15.0.1
+ '@angular/common': 15.0.1_gc4fl5hkkh62bvf2jldebe7kfi
+ '@angular/core': 15.0.1_rxjs@7.5.7+zone.js@0.11.8
+ tslib: 2.4.1
+ dev: true
+
+ /@babel/cli/7.20.7_@babel+core@7.20.12:
+ resolution: {integrity: sha512-WylgcELHB66WwQqItxNILsMlaTd8/SO6SgTTjMp4uCI7P4QyH1r3nqgFmO3BfM4AtfniHgFMH3EpYFj/zynBkQ==}
+ engines: {node: '>=6.9.0'}
+ hasBin: true
+ peerDependencies:
+ '@babel/core': ^7.0.0-0
+ dependencies:
+ '@babel/core': 7.20.12
+ '@jridgewell/trace-mapping': 0.3.17
+ commander: 4.1.1
+ convert-source-map: 1.9.0
+ fs-readdir-recursive: 1.1.0
+ glob: 7.2.3
+ make-dir: 2.1.0
+ slash: 2.0.0
+ optionalDependencies:
+ '@nicolo-ribaudo/chokidar-2': 2.1.8-no-fsevents.3
+ chokidar: 3.5.3
+ dev: true
+
+ /@babel/code-frame/7.18.6:
+ resolution: {integrity: sha512-TDCmlK5eOvH+eH7cdAFlNXeVJqWIQ7gW9tY1GJIpUtFb6CmjVyq2VM3u71bOyR8CRihcCgMUYoDNyLXao3+70Q==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/highlight': 7.18.6
+ dev: true
+
+ /@babel/compat-data/7.20.10:
+ resolution: {integrity: sha512-sEnuDPpOJR/fcafHMjpcpGN5M2jbUGUHwmuWKM/YdPzeEDJg8bgmbcWQFUfE32MQjti1koACvoPVsDe8Uq+idg==}
+ engines: {node: '>=6.9.0'}
+ dev: true
+
+ /@babel/core/7.20.12:
+ resolution: {integrity: sha512-XsMfHovsUYHFMdrIHkZphTN/2Hzzi78R08NuHfDBehym2VsPDL6Zn/JAD/JQdnRvbSsbQc4mVaU1m6JgtTEElg==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@ampproject/remapping': 2.2.0
+ '@babel/code-frame': 7.18.6
+ '@babel/generator': 7.20.7
+ '@babel/helper-compilation-targets': 7.20.7_@babel+core@7.20.12
+ '@babel/helper-module-transforms': 7.20.11
+ '@babel/helpers': 7.20.7
+ '@babel/parser': 7.20.7
+ '@babel/template': 7.20.7
+ '@babel/traverse': 7.20.12
+ '@babel/types': 7.20.7
+ convert-source-map: 1.9.0
+ debug: 4.3.4
+ gensync: 1.0.0-beta.2
+ json5: 2.2.3
+ semver: 6.3.0
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /@babel/generator/7.20.7:
+ resolution: {integrity: sha512-7wqMOJq8doJMZmP4ApXTzLxSr7+oO2jroJURrVEp6XShrQUObV8Tq/D0NCcoYg2uHqUrjzO0zwBjoYzelxK+sw==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/types': 7.20.7
+ '@jridgewell/gen-mapping': 0.3.2
+ jsesc: 2.5.2
+ dev: true
+
+ /@babel/helper-compilation-targets/7.20.7_@babel+core@7.20.12:
+ resolution: {integrity: sha512-4tGORmfQcrc+bvrjb5y3dG9Mx1IOZjsHqQVUz7XCNHO+iTmqxWnVg3KRygjGmpRLJGdQSKuvFinbIb0CnZwHAQ==}
+ engines: {node: '>=6.9.0'}
+ peerDependencies:
+ '@babel/core': ^7.0.0
+ dependencies:
+ '@babel/compat-data': 7.20.10
+ '@babel/core': 7.20.12
+ '@babel/helper-validator-option': 7.18.6
+ browserslist: 4.21.4
+ lru-cache: 5.1.1
+ semver: 6.3.0
+ dev: true
+
+ /@babel/helper-environment-visitor/7.18.9:
+ resolution: {integrity: sha512-3r/aACDJ3fhQ/EVgFy0hpj8oHyHpQc+LPtJoY9SzTThAsStm4Ptegq92vqKoE3vD706ZVFWITnMnxucw+S9Ipg==}
+ engines: {node: '>=6.9.0'}
+ dev: true
+
+ /@babel/helper-function-name/7.19.0:
+ resolution: {integrity: sha512-WAwHBINyrpqywkUH0nTnNgI5ina5TFn85HKS0pbPDfxFfhyR/aNQEn4hGi1P1JyT//I0t4OgXUlofzWILRvS5w==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/template': 7.20.7
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/helper-hoist-variables/7.18.6:
+ resolution: {integrity: sha512-UlJQPkFqFULIcyW5sbzgbkxn2FKRgwWiRexcuaR8RNJRy8+LLveqPjwZV/bwrLZCN0eUHD/x8D0heK1ozuoo6Q==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/helper-module-imports/7.18.6:
+ resolution: {integrity: sha512-0NFvs3VkuSYbFi1x2Vd6tKrywq+z/cLeYC/RJNFrIX/30Bf5aiGYbtvGXolEktzJH8o5E5KJ3tT+nkxuuZFVlA==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/helper-module-transforms/7.20.11:
+ resolution: {integrity: sha512-uRy78kN4psmji1s2QtbtcCSaj/LILFDp0f/ymhpQH5QY3nljUZCaNWz9X1dEj/8MBdBEFECs7yRhKn8i7NjZgg==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/helper-environment-visitor': 7.18.9
+ '@babel/helper-module-imports': 7.18.6
+ '@babel/helper-simple-access': 7.20.2
+ '@babel/helper-split-export-declaration': 7.18.6
+ '@babel/helper-validator-identifier': 7.19.1
+ '@babel/template': 7.20.7
+ '@babel/traverse': 7.20.12
+ '@babel/types': 7.20.7
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /@babel/helper-simple-access/7.20.2:
+ resolution: {integrity: sha512-+0woI/WPq59IrqDYbVGfshjT5Dmk/nnbdpcF8SnMhhXObpTq2KNBdLFRFrkVdbDOyUmHBCxzm5FHV1rACIkIbA==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/helper-split-export-declaration/7.18.6:
+ resolution: {integrity: sha512-bde1etTx6ZyTmobl9LLMMQsaizFVZrquTEHOqKeQESMKo4PlObf+8+JA25ZsIpZhT/WEd39+vOdLXAFG/nELpA==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/helper-string-parser/7.19.4:
+ resolution: {integrity: sha512-nHtDoQcuqFmwYNYPz3Rah5ph2p8PFeFCsZk9A/48dPc/rGocJ5J3hAAZ7pb76VWX3fZKu+uEr/FhH5jLx7umrw==}
+ engines: {node: '>=6.9.0'}
+ dev: true
+
+ /@babel/helper-validator-identifier/7.19.1:
+ resolution: {integrity: sha512-awrNfaMtnHUr653GgGEs++LlAvW6w+DcPrOliSMXWCKo597CwL5Acf/wWdNkf/tfEQE3mjkeD1YOVZOUV/od1w==}
+ engines: {node: '>=6.9.0'}
+ dev: true
+
+ /@babel/helper-validator-option/7.18.6:
+ resolution: {integrity: sha512-XO7gESt5ouv/LRJdrVjkShckw6STTaB7l9BrpBaAHDeF5YZT+01PCwmR0SJHnkW6i8OwW/EVWRShfi4j2x+KQw==}
+ engines: {node: '>=6.9.0'}
+ dev: true
+
+ /@babel/helpers/7.20.7:
+ resolution: {integrity: sha512-PBPjs5BppzsGaxHQCDKnZ6Gd9s6xl8bBCluz3vEInLGRJmnZan4F6BYCeqtyXqkk4W5IlPmjK4JlOuZkpJ3xZA==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/template': 7.20.7
+ '@babel/traverse': 7.20.12
+ '@babel/types': 7.20.7
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /@babel/highlight/7.18.6:
+ resolution: {integrity: sha512-u7stbOuYjaPezCuLj29hNW1v64M2Md2qupEKP1fHc7WdOA3DgLh37suiSrZYY7haUB7iBeQZ9P1uiRF359do3g==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/helper-validator-identifier': 7.19.1
+ chalk: 2.4.2
+ js-tokens: 4.0.0
+ dev: true
+
+ /@babel/parser/7.20.7:
+ resolution: {integrity: sha512-T3Z9oHybU+0vZlY9CiDSJQTD5ZapcW18ZctFMi0MOAl/4BjFF4ul7NVSARLdbGO5vDqy9eQiGTV0LtKfvCYvcg==}
+ engines: {node: '>=6.0.0'}
+ hasBin: true
+ dependencies:
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/template/7.20.7:
+ resolution: {integrity: sha512-8SegXApWe6VoNw0r9JHpSteLKTpTiLZ4rMlGIm9JQ18KiCtyQiAMEazujAHrUS5flrcqYZa75ukev3P6QmUwUw==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/code-frame': 7.18.6
+ '@babel/parser': 7.20.7
+ '@babel/types': 7.20.7
+ dev: true
+
+ /@babel/traverse/7.20.12:
+ resolution: {integrity: sha512-MsIbFN0u+raeja38qboyF8TIT7K0BFzz/Yd/77ta4MsUsmP2RAnidIlwq7d5HFQrH/OZJecGV6B71C4zAgpoSQ==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/code-frame': 7.18.6
+ '@babel/generator': 7.20.7
+ '@babel/helper-environment-visitor': 7.18.9
+ '@babel/helper-function-name': 7.19.0
+ '@babel/helper-hoist-variables': 7.18.6
+ '@babel/helper-split-export-declaration': 7.18.6
+ '@babel/parser': 7.20.7
+ '@babel/types': 7.20.7
+ debug: 4.3.4
+ globals: 11.12.0
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /@babel/types/7.20.7:
+ resolution: {integrity: sha512-69OnhBxSSgK0OzTJai4kyPDiKTIe3j+ctaHdIGVbRahTLAT7L3R9oeXHC2aVSuGYt3cVnoAMDmOCgJ2yaiLMvg==}
+ engines: {node: '>=6.9.0'}
+ dependencies:
+ '@babel/helper-string-parser': 7.19.4
+ '@babel/helper-validator-identifier': 7.19.1
+ to-fast-properties: 2.0.0
+ dev: true
+
+ /@colors/colors/1.5.0:
+ resolution: {integrity: sha512-ooWCrlZP11i8GImSjTHYHLkvFDP48nS4+204nGb1RiX/WXYHmJA2III9/e2DWVabCESdW7hBAEzHRqUn9OUVvQ==}
+ engines: {node: '>=0.1.90'}
+ dev: true
+
+ /@cypress/request/2.88.11:
+ resolution: {integrity: sha512-M83/wfQ1EkspjkE2lNWNV5ui2Cv7UCv1swW1DqljahbzLVWltcsexQh8jYtuS/vzFXP+HySntGM83ZXA9fn17w==}
+ engines: {node: '>= 6'}
+ dependencies:
+ aws-sign2: 0.7.0
+ aws4: 1.12.0
+ caseless: 0.12.0
+ combined-stream: 1.0.8
+ extend: 3.0.2
+ forever-agent: 0.6.1
+ form-data: 2.3.3
+ http-signature: 1.3.6
+ is-typedarray: 1.0.0
+ isstream: 0.1.2
+ json-stringify-safe: 5.0.1
+ mime-types: 2.1.35
+ performance-now: 2.1.0
+ qs: 6.10.4
+ safe-buffer: 5.2.1
+ tough-cookie: 2.5.0
+ tunnel-agent: 0.6.0
+ uuid: 8.3.2
+ dev: true
+
+ /@cypress/xvfb/1.2.4_supports-color@8.1.1:
+ resolution: {integrity: sha512-skbBzPggOVYCbnGgV+0dmBdW/s77ZkAOXIC1knS8NagwDjBrNC1LuXtQJeiN6l+m7lzmHtaoUw/ctJKdqkG57Q==}
+ dependencies:
+ debug: 3.2.7_supports-color@8.1.1
+ lodash.once: 4.1.1
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /@gar/promisify/1.1.3:
+ resolution: {integrity: sha512-k2Ty1JcVojjJFwrg/ThKi2ujJ7XNLYaFGNB/bWT9wGR+oSMJHMa5w+CUq6p/pVrKeNNgA7pCqEcjSnHVoqJQFw==}
+ dev: true
+
+ /@jridgewell/gen-mapping/0.1.1:
+ resolution: {integrity: sha512-sQXCasFk+U8lWYEe66WxRDOE9PjVz4vSM51fTu3Hw+ClTpUSQb718772vH3pyS5pShp6lvQM7SxgIDXXXmOX7w==}
+ engines: {node: '>=6.0.0'}
+ dependencies:
+ '@jridgewell/set-array': 1.1.2
+ '@jridgewell/sourcemap-codec': 1.4.14
+ dev: true
+
+ /@jridgewell/gen-mapping/0.3.2:
+ resolution: {integrity: sha512-mh65xKQAzI6iBcFzwv28KVWSmCkdRBWoOh+bYQGW3+6OZvbbN3TqMGo5hqYxQniRcH9F2VZIoJCm4pa3BPDK/A==}
+ engines: {node: '>=6.0.0'}
+ dependencies:
+ '@jridgewell/set-array': 1.1.2
+ '@jridgewell/sourcemap-codec': 1.4.14
+ '@jridgewell/trace-mapping': 0.3.17
+ dev: true
+
+ /@jridgewell/resolve-uri/3.1.0:
+ resolution: {integrity: sha512-F2msla3tad+Mfht5cJq7LSXcdudKTWCVYUgw6pLFOOHSTtZlj6SWNYAp+AhuqLmWdBO2X5hPrLcu8cVP8fy28w==}
+ engines: {node: '>=6.0.0'}
+ dev: true
+
+ /@jridgewell/set-array/1.1.2:
+ resolution: {integrity: sha512-xnkseuNADM0gt2bs+BvhO0p78Mk762YnZdsuzFV018NoG1Sj1SCQvpSqa7XUaTam5vAGasABV9qXASMKnFMwMw==}
+ engines: {node: '>=6.0.0'}
+ dev: true
+
+ /@jridgewell/sourcemap-codec/1.4.14:
+ resolution: {integrity: sha512-XPSJHWmi394fuUuzDnGz1wiKqWfo1yXecHQMRf2l6hztTO+nPru658AyDngaBe7isIxEkRsPR3FZh+s7iVa4Uw==}
+ dev: true
+
+ /@jridgewell/trace-mapping/0.3.17:
+ resolution: {integrity: sha512-MCNzAp77qzKca9+W/+I0+sEpaUnZoeasnghNeVc41VZCEKaCH73Vq3BZZ/SzWIgrqE4H4ceI+p+b6C0mHf9T4g==}
+ dependencies:
+ '@jridgewell/resolve-uri': 3.1.0
+ '@jridgewell/sourcemap-codec': 1.4.14
+ dev: true
+
+ /@nicolo-ribaudo/chokidar-2/2.1.8-no-fsevents.3:
+ resolution: {integrity: sha512-s88O1aVtXftvp5bCPB7WnmXc5IwOZZ7YPuwNPt+GtOOXpPvad1LfbmjYv+qII7zP6RU2QGnqve27dnLycEnyEQ==}
+ requiresBuild: true
+ dev: true
+ optional: true
+
+ /@npmcli/fs/2.1.2:
+ resolution: {integrity: sha512-yOJKRvohFOaLqipNtwYB9WugyZKhC/DZC4VYPmpaCzDBrA8YpK3qHZ8/HGscMnE4GqbkLNuVcCnxkeQEdGt6LQ==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ '@gar/promisify': 1.1.3
+ semver: 7.3.8
+ dev: true
+
+ /@npmcli/fs/3.1.0:
+ resolution: {integrity: sha512-7kZUAaLscfgbwBQRbvdMYaZOWyMEcPTH/tJjnyAWJ/dvvs9Ef+CERx/qJb9GExJpl1qipaDGn7KqHnFGGixd0w==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ semver: 7.3.8
+ dev: true
+
+ /@npmcli/git/4.0.3:
+ resolution: {integrity: sha512-8cXNkDIbnXPVbhXMmQ7/bklCAjtmPaXfI9aEM4iH+xSuEHINLMHhlfESvVwdqmHJRJkR48vNJTSUvoF6GRPSFA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ '@npmcli/promise-spawn': 6.0.2
+ lru-cache: 7.14.1
+ mkdirp: 1.0.4
+ npm-pick-manifest: 8.0.1
+ proc-log: 3.0.0
+ promise-inflight: 1.0.1
+ promise-retry: 2.0.1
+ semver: 7.3.8
+ which: 3.0.0
+ transitivePeerDependencies:
+ - bluebird
+ dev: true
+
+ /@npmcli/installed-package-contents/2.0.1:
+ resolution: {integrity: sha512-GIykAFdOVK31Q1/zAtT5MbxqQL2vyl9mvFJv+OGu01zxbhL3p0xc8gJjdNGX1mWmUT43aEKVO2L6V/2j4TOsAA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ hasBin: true
+ dependencies:
+ npm-bundled: 3.0.0
+ npm-normalize-package-bin: 3.0.0
+ dev: true
+
+ /@npmcli/move-file/2.0.1:
+ resolution: {integrity: sha512-mJd2Z5TjYWq/ttPLLGqArdtnC74J6bOzg4rMDnN+p1xTacZ2yPRCk2y0oSWQtygLR9YVQXgOcONrwtnk3JupxQ==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ deprecated: This functionality has been moved to @npmcli/fs
+ dependencies:
+ mkdirp: 1.0.4
+ rimraf: 3.0.2
+ dev: true
+
+ /@npmcli/node-gyp/3.0.0:
+ resolution: {integrity: sha512-gp8pRXC2oOxu0DUE1/M3bYtb1b3/DbJ5aM113+XJBgfXdussRAsX0YOrOhdd8WvnAR6auDBvJomGAkLKA5ydxA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dev: true
+
+ /@npmcli/promise-spawn/6.0.2:
+ resolution: {integrity: sha512-gGq0NJkIGSwdbUt4yhdF8ZrmkGKVz9vAdVzpOfnom+V8PLSmSOVhZwbNvZZS1EYcJN5hzzKBxmmVVAInM6HQLg==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ which: 3.0.0
+ dev: true
+
+ /@npmcli/run-script/6.0.0:
+ resolution: {integrity: sha512-ql+AbRur1TeOdl1FY+RAwGW9fcr4ZwiVKabdvm93mujGREVuVLbdkXRJDrkTXSdCjaxYydr1wlA2v67jxWG5BQ==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ '@npmcli/node-gyp': 3.0.0
+ '@npmcli/promise-spawn': 6.0.2
+ node-gyp: 9.3.1
+ read-package-json-fast: 3.0.2
+ which: 3.0.0
+ transitivePeerDependencies:
+ - bluebird
+ - supports-color
+ dev: true
+
+ /@rollup/plugin-node-resolve/13.1.3_rollup@2.66.1:
+ resolution: {integrity: sha512-BdxNk+LtmElRo5d06MGY4zoepyrXX1tkzX2hrnPEZ53k78GuOMWLqmJDGIIOPwVRIFZrLQOo+Yr6KtCuLIA0AQ==}
+ engines: {node: '>= 10.0.0'}
+ peerDependencies:
+ rollup: ^2.42.0
+ dependencies:
+ '@rollup/pluginutils': 3.1.0_rollup@2.66.1
+ '@types/resolve': 1.17.1
+ builtin-modules: 3.3.0
+ deepmerge: 4.2.2
+ is-module: 1.0.0
+ resolve: 1.22.1
+ rollup: 2.66.1
+ dev: true
+
+ /@rollup/pluginutils/3.1.0_rollup@2.66.1:
+ resolution: {integrity: sha512-GksZ6pr6TpIjHm8h9lSQ8pi8BE9VeubNT0OMJ3B5uZJ8pz73NPiqOtCog/x2/QzM1ENChPKxMDhiQuRHsqc+lg==}
+ engines: {node: '>= 8.0.0'}
+ peerDependencies:
+ rollup: ^1.20.0||^2.0.0
+ dependencies:
+ '@types/estree': 0.0.39
+ estree-walker: 1.0.1
+ picomatch: 2.3.1
+ rollup: 2.66.1
+ dev: true
+
+ /@schematics/angular/15.0.1:
+ resolution: {integrity: sha512-UGiQ4IwdLWdQwlWVgbAM5B6G4VdzVOn0yS1PkOtTt0hvAkszriu7uyaH2Qh8aFSTvNAIg/l7/6grI/UGj8iDaw==}
+ engines: {node: ^14.20.0 || ^16.13.0 || >=18.10.0, npm: ^6.11.0 || ^7.5.6 || >=8.0.0, yarn: '>= 1.13.0'}
+ dependencies:
+ '@angular-devkit/core': 15.0.1
+ '@angular-devkit/schematics': 15.0.1
+ jsonc-parser: 3.2.0
+ transitivePeerDependencies:
+ - chokidar
+ dev: true
+
+ /@socket.io/component-emitter/3.1.0:
+ resolution: {integrity: sha512-+9jVqKhRSpsc591z5vX+X5Yyw+he/HCB4iQ/RYxw35CEPaY1gnsNE43nf9n9AaYjAQrTiI/mOwKUKdUs9vf7Xg==}
+ dev: true
+
+ /@tootallnate/once/2.0.0:
+ resolution: {integrity: sha512-XCuKFP5PS55gnMVu3dty8KPatLqUoy/ZYzDzAGCQ8JNFCkLXzmI7vNHCR+XpbZaMWQK/vQubr7PkYq8g470J/A==}
+ engines: {node: '>= 10'}
+ dev: true
+
+ /@types/cookie/0.4.1:
+ resolution: {integrity: sha512-XW/Aa8APYr6jSVVA1y/DEIZX0/GMKLEVekNG727R8cs56ahETkRAy/3DR7+fJyh7oUgGwNQaRfXCun0+KbWY7Q==}
+ dev: true
+
+ /@types/cors/2.8.13:
+ resolution: {integrity: sha512-RG8AStHlUiV5ysZQKq97copd2UmVYw3/pRMLefISZ3S1hK104Cwm7iLQ3fTKx+lsUH2CE8FlLaYeEA2LSeqYUA==}
+ dependencies:
+ '@types/node': 17.0.21
+ dev: true
+
+ /@types/estree/0.0.39:
+ resolution: {integrity: sha512-EYNwp3bU+98cpU4lAWYYL7Zz+2gryWH1qbdDTidVd6hkiR6weksdbMadyXKXNPEkQFhXM+hVO9ZygomHXp+AIw==}
+ dev: true
+
+ /@types/flatbuffers/1.10.0:
+ resolution: {integrity: sha512-7btbphLrKvo5yl/5CC2OCxUSMx1wV1wvGT1qDXkSt7yi00/YW7E8k6qzXqJHsp+WU0eoG7r6MTQQXI9lIvd0qA==}
+ dev: true
+
+ /@types/jasmine/3.10.3:
+ resolution: {integrity: sha512-SWyMrjgdAUHNQmutvDcKablrJhkDLy4wunTme8oYLjKp41GnHGxMRXr2MQMvy/qy8H3LdzwQk9gH4hZ6T++H8g==}
+ dev: true
+
+ /@types/node/14.18.36:
+ resolution: {integrity: sha512-FXKWbsJ6a1hIrRxv+FoukuHnGTgEzKYGi7kilfMae96AL9UNkPFNWJEEYWzdRI9ooIkbr4AKldyuSTLql06vLQ==}
+ dev: true
+
+ /@types/node/17.0.21:
+ resolution: {integrity: sha512-DBZCJbhII3r90XbQxI8Y9IjjiiOGlZ0Hr32omXIZvwwZ7p4DMMXGrKXVyPfuoBOri9XNtL0UK69jYIBIsRX3QQ==}
+ dev: true
+
+ /@types/q/0.0.32:
+ resolution: {integrity: sha512-qYi3YV9inU/REEfxwVcGZzbS3KG/Xs90lv0Pr+lDtuVjBPGd1A+eciXzVSaRvLify132BfcvhvEjeVahrUl0Ug==}
+ dev: true
+
+ /@types/resolve/1.17.1:
+ resolution: {integrity: sha512-yy7HuzQhj0dhGpD8RLXSZWEkLsV9ibvxvi6EiJ3bkqLAO1RGo0WbkWQiwpRlSFymTJRz0d3k5LM3kkx8ArDbLw==}
+ dependencies:
+ '@types/node': 17.0.21
+ dev: true
+
+ /@types/selenium-webdriver/3.0.20:
+ resolution: {integrity: sha512-6d8Q5fqS9DWOXEhMDiF6/2FjyHdmP/jSTAUyeQR7QwrFeNmYyzmvGxD5aLIHL445HjWgibs0eAig+KPnbaesXA==}
+ dev: true
+
+ /@types/sinonjs__fake-timers/8.1.1:
+ resolution: {integrity: sha512-0kSuKjAS0TrGLJ0M/+8MaFkGsQhZpB6pxOmvS3K8FYI72K//YmdfoW9X2qPsAKh1mkwxGD5zib9s1FIFed6E8g==}
+ dev: true
+
+ /@types/sizzle/2.3.3:
+ resolution: {integrity: sha512-JYM8x9EGF163bEyhdJBpR2QX1R5naCJHC8ucJylJ3w9/CVBaskdQ8WqBf8MmQrd1kRvp/a4TS8HJ+bxzR7ZJYQ==}
+ dev: true
+
+ /@types/yauzl/2.10.0:
+ resolution: {integrity: sha512-Cn6WYCm0tXv8p6k+A8PvbDG763EDpBoTzHdA+Q/MF6H3sapGjCm9NzoaJncJS9tUKSuCoDs9XHxYYsQDgxR6kw==}
+ requiresBuild: true
+ dependencies:
+ '@types/node': 17.0.21
+ dev: true
+ optional: true
+
+ /@yarnpkg/lockfile/1.1.0:
+ resolution: {integrity: sha512-GpSwvyXOcOOlV70vbnzjj4fW5xW/FdUF6nQEt1ENy7m4ZCczi1+/buVUPAqmGfqznsORNFzUMjctTIp8a9tuCQ==}
+ dev: true
+
+ /abbrev/1.1.1:
+ resolution: {integrity: sha512-nne9/IiQ/hzIhY6pdDnbBtz7DjPTKrY00P/zvPSm5pOFkl6xuGrGnXn/VtTNNfNtAfZ9/1RtehkszU9qcTii0Q==}
+ dev: true
+
+ /accepts/1.3.8:
+ resolution: {integrity: sha512-PYAthTa2m2VKxuvSD3DPC/Gy+U+sOA1LAuT8mkmRuvw+NACSaeXEQ+NHcVF7rONl6qcaxV3Uuemwawk+7+SJLw==}
+ engines: {node: '>= 0.6'}
+ dependencies:
+ mime-types: 2.1.35
+ negotiator: 0.6.3
+ dev: true
+
+ /acorn/8.8.1:
+ resolution: {integrity: sha512-7zFpHzhnqYKrkYdUjF1HI1bzd0VygEGX8lFk4k5zVMqHEoES+P+7TKI+EvLO9WVMJ8eekdO0aDEK044xTXwPPA==}
+ engines: {node: '>=0.4.0'}
+ hasBin: true
+ dev: true
+
+ /adm-zip/0.4.16:
+ resolution: {integrity: sha512-TFi4HBKSGfIKsK5YCkKaaFG2m4PEDyViZmEwof3MTIgzimHLto6muaHVpbrljdIvIrFZzEq/p4nafOeLcYegrg==}
+ engines: {node: '>=0.3.0'}
+ dev: true
+
+ /agent-base/4.3.0:
+ resolution: {integrity: sha512-salcGninV0nPrwpGNn4VTXBb1SOuXQBiqbrNXoeizJsHrsL6ERFM2Ne3JUSBWRE6aeNJI2ROP/WEEIDUiDe3cg==}
+ engines: {node: '>= 4.0.0'}
+ dependencies:
+ es6-promisify: 5.0.0
+ dev: true
+
+ /agent-base/6.0.2:
+ resolution: {integrity: sha512-RZNwNclF7+MS/8bDg70amg32dyeZGZxiDuQmZxKLAlQjr3jGyLx+4Kkk58UO7D2QdgFIQCovuSuZESne6RG6XQ==}
+ engines: {node: '>= 6.0.0'}
+ dependencies:
+ debug: 4.3.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /agentkeepalive/4.2.1:
+ resolution: {integrity: sha512-Zn4cw2NEqd+9fiSVWMscnjyQ1a8Yfoc5oBajLeo5w+YBHgDUcEBY2hS4YpTz6iN5f/2zQiktcuM6tS8x1p9dpA==}
+ engines: {node: '>= 8.0.0'}
+ dependencies:
+ debug: 4.3.4
+ depd: 1.1.2
+ humanize-ms: 1.2.1
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /aggregate-error/3.1.0:
+ resolution: {integrity: sha512-4I7Td01quW/RpocfNayFdFVk1qSuoh0E7JrbRJ16nH01HhKFQ88INq9Sd+nd72zqRySlr9BmDA8xlEJ6vJMrYA==}
+ engines: {node: '>=8'}
+ dependencies:
+ clean-stack: 2.2.0
+ indent-string: 4.0.0
+ dev: true
+
+ /ajv-formats/2.1.1:
+ resolution: {integrity: sha512-Wx0Kx52hxE7C18hkMEggYlEifqWZtYaRgouJor+WMdPnQyEK13vgEWyVNup7SoeeoLMsr4kf5h6dOW11I15MUA==}
+ peerDependenciesMeta:
+ ajv:
+ optional: true
+ dependencies:
+ ajv: 8.11.0
+ dev: true
+
+ /ajv/6.12.6:
+ resolution: {integrity: sha512-j3fVLgvTo527anyYyJOGTYJbG+vnnQYvE0m5mmkc1TK+nxAppkCLMIL0aZ4dblVCNoGShhm+kzE4ZUykBoMg4g==}
+ dependencies:
+ fast-deep-equal: 3.1.3
+ fast-json-stable-stringify: 2.1.0
+ json-schema-traverse: 0.4.1
+ uri-js: 4.4.1
+ dev: true
+
+ /ajv/8.11.0:
+ resolution: {integrity: sha512-wGgprdCvMalC0BztXvitD2hC04YffAvtsUn93JbGXYLAtCUO4xd17mCCZQxUOItiBwZvJScWo8NIvQMQ71rdpg==}
+ dependencies:
+ fast-deep-equal: 3.1.3
+ json-schema-traverse: 1.0.0
+ require-from-string: 2.0.2
+ uri-js: 4.4.1
+ dev: true
+
+ /ansi-colors/4.1.3:
+ resolution: {integrity: sha512-/6w/C21Pm1A7aZitlI5Ni/2J6FFQN8i1Cvz3kHABAAbw93v/NlvKdVOqz7CCWz/3iv/JplRSEEZ83XION15ovw==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /ansi-escapes/4.3.2:
+ resolution: {integrity: sha512-gKXj5ALrKWQLsYG9jlTRmR/xKluxHV+Z9QEwNIgCfM1/uwPMCuzVVnh5mwTd+OuBZcwSIMbqssNWRm1lE51QaQ==}
+ engines: {node: '>=8'}
+ dependencies:
+ type-fest: 0.21.3
+ dev: true
+
+ /ansi-regex/2.1.1:
+ resolution: {integrity: sha512-TIGnTpdo+E3+pCyAluZvtED5p5wCqLdezCyhPZzKPcxvFplEt4i+W7OONCKgeZFT3+y5NZZfOOS/Bdcanm1MYA==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /ansi-regex/5.0.1:
+ resolution: {integrity: sha512-quJQXlTSUGL2LH9SUXo8VwsY4soanhgo6LNSm84E1LBcE8s3O0wpdiRzyR9z/ZZJMlMWv37qOOb9pdJlMUEKFQ==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /ansi-styles/2.2.1:
+ resolution: {integrity: sha512-kmCevFghRiWM7HB5zTPULl4r9bVFSWjz62MhqizDGUrq2NWuNMQyuv4tHHoKJHs69M/MF64lEcHdYIocrdWQYA==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /ansi-styles/3.2.1:
+ resolution: {integrity: sha512-VT0ZI6kZRdTh8YyJw3SMbYm/u+NqfsAxEpWO0Pf9sq8/e94WxxOpPKx9FR1FlyCtOVDNOQ+8ntlqFxiRc+r5qA==}
+ engines: {node: '>=4'}
+ dependencies:
+ color-convert: 1.9.3
+ dev: true
+
+ /ansi-styles/4.3.0:
+ resolution: {integrity: sha512-zbB9rCJAT1rbjiVDb2hqKFHNYLxgtk8NURxZ3IZwD3F6NtxbXZQCnnSi1Lkx+IDohdPlFp222wVALIheZJQSEg==}
+ engines: {node: '>=8'}
+ dependencies:
+ color-convert: 2.0.1
+ dev: true
+
+ /anymatch/3.1.3:
+ resolution: {integrity: sha512-KMReFUr0B4t+D+OBkjR3KYqvocp2XaSzO55UcB6mgQMd3KbcE+mWTyvVV7D/zsdEbNnV6acZUutkiHQXvTr1Rw==}
+ engines: {node: '>= 8'}
+ dependencies:
+ normalize-path: 3.0.0
+ picomatch: 2.3.1
+ dev: true
+
+ /aproba/2.0.0:
+ resolution: {integrity: sha512-lYe4Gx7QT+MKGbDsA+Z+he/Wtef0BiwDOlK/XkBrdfsh9J/jPPXbX0tE9x9cl27Tmu5gg3QUbUrQYa/y+KOHPQ==}
+ dev: true
+
+ /arch/2.2.0:
+ resolution: {integrity: sha512-Of/R0wqp83cgHozfIYLbBMnej79U/SVGOOyuB3VVFv1NRM/PSFMK12x9KVtiYzJqmnU5WR2qp0Z5rHb7sWGnFQ==}
+ dev: true
+
+ /are-we-there-yet/3.0.1:
+ resolution: {integrity: sha512-QZW4EDmGwlYur0Yyf/b2uGucHQMa8aFUP7eu9ddR73vvhFyt4V0Vl3QHPcTNJ8l6qYOBdxgXdnBXQrHilfRQBg==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ delegates: 1.0.0
+ readable-stream: 3.6.0
+ dev: true
+
+ /array-union/1.0.2:
+ resolution: {integrity: sha512-Dxr6QJj/RdU/hCaBjOfxW+q6lyuVE6JFWIrAUpuOOhoJJoQ99cUn3igRaHVB5P9WrgFVN0FfArM3x0cueOU8ng==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ array-uniq: 1.0.3
+ dev: true
+
+ /array-uniq/1.0.3:
+ resolution: {integrity: sha512-MNha4BWQ6JbwhFhj03YK552f7cb3AzoE8SzeljgChvL1dl3IcvggXVz1DilzySZkCja+CXuZbdW7yATchWn8/Q==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /arrify/1.0.1:
+ resolution: {integrity: sha512-3CYzex9M9FGQjCGMGyi6/31c8GJbgb0qGyrx5HWxPd0aCwh4cB2YjMb2Xf9UuoogrMrlO9cTqnB5rI5GHZTcUA==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /asn1/0.2.6:
+ resolution: {integrity: sha512-ix/FxPn0MDjeyJ7i/yoHGFt/EX6LyNbxSEhPPXODPL+KB0VPk86UYfL0lMdy+KCnv+fmvIzySwaK5COwqVbWTQ==}
+ dependencies:
+ safer-buffer: 2.1.2
+ dev: true
+
+ /assert-plus/1.0.0:
+ resolution: {integrity: sha512-NfJ4UzBCcQGLDlQq7nHxH+tv3kyZ0hHQqF5BO6J7tNJeP5do1llPr8dZ8zHonfhAu0PHAdMkSo+8o0wxg9lZWw==}
+ engines: {node: '>=0.8'}
+ dev: true
+
+ /astral-regex/2.0.0:
+ resolution: {integrity: sha512-Z7tMw1ytTXt5jqMcOP+OQteU1VuNK9Y02uuJtKQ1Sv69jXQKKg5cibLwGJow8yzZP+eAc18EmLGPal0bp36rvQ==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /async/3.2.4:
+ resolution: {integrity: sha512-iAB+JbDEGXhyIUavoDl9WP/Jj106Kz9DEn1DPgYw5ruDn0e3Wgi3sKFm55sASdGBNOQB8F59d9qQ7deqrHA8wQ==}
+ dev: true
+
+ /asynckit/0.4.0:
+ resolution: {integrity: sha512-Oei9OH4tRh0YqU3GxhX79dM/mwVgvbZJaSNaRk+bshkj0S5cfHcgYakreBjrHwatXKbz+IoIdYLxrKim2MjW0Q==}
+ dev: true
+
+ /at-least-node/1.0.0:
+ resolution: {integrity: sha512-+q/t7Ekv1EDY2l6Gda6LLiX14rU9TV20Wa3ofeQmwPFZbOMo9DXrLbOjFaaclkXKWidIaopwAObQDqwWtGUjqg==}
+ engines: {node: '>= 4.0.0'}
+ dev: true
+
+ /aws-sign2/0.7.0:
+ resolution: {integrity: sha512-08kcGqnYf/YmjoRhfxyu+CLxBjUtHLXLXX/vUfx9l2LYzG3c1m61nrpyFUZI6zeS+Li/wWMMidD9KgrqtGq3mA==}
+ dev: true
+
+ /aws4/1.12.0:
+ resolution: {integrity: sha512-NmWvPnx0F1SfrQbYwOi7OeaNGokp9XhzNioJ/CSBs8Qa4vxug81mhJEAVZwxXuBmYB5KDRfMq/F3RR0BIU7sWg==}
+ dev: true
+
+ /balanced-match/1.0.2:
+ resolution: {integrity: sha512-3oSeUO0TMV67hN1AmbXsK4yaqU7tjiHlbxRDZOpH0KW9+CeX4bRAaX0Anxt0tx2MrpRpWwQaPwIlISEJhYU5Pw==}
+ dev: true
+
+ /base64-js/1.5.1:
+ resolution: {integrity: sha512-AKpaYlHn8t4SVbOHCy+b5+KKgvR4vrsD8vbvrbiQJps7fKDTkjkDry6ji0rUJjC0kzbNePLwzxq8iypo41qeWA==}
+ dev: true
+
+ /base64id/2.0.0:
+ resolution: {integrity: sha512-lGe34o6EHj9y3Kts9R4ZYs/Gr+6N7MCaMlIFA3F1R2O5/m7K06AxfSeO5530PEERE6/WyEg3lsuyw4GHlPZHog==}
+ engines: {node: ^4.5.0 || >= 5.9}
+ dev: true
+
+ /bcrypt-pbkdf/1.0.2:
+ resolution: {integrity: sha512-qeFIXtP4MSoi6NLqO12WfqARWWuCKi2Rn/9hJLEmtB5yTNr9DqFWkJRCf2qShWzPeAMRnOgCrq0sg/KLv5ES9w==}
+ dependencies:
+ tweetnacl: 0.14.5
+ dev: true
+
+ /binary-extensions/2.2.0:
+ resolution: {integrity: sha512-jDctJ/IVQbZoJykoeHbhXpOlNBqGNcwXJKJog42E5HDPUwQTSdjCHdihjj0DlnheQ7blbT6dHOafNAiS8ooQKA==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /bl/4.1.0:
+ resolution: {integrity: sha512-1W07cM9gS6DcLperZfFSj+bWLtaPGSOHWhPiGzXmvVJbRLdG82sH/Kn8EtW1VqWVA54AKf2h5k5BbnIbwF3h6w==}
+ dependencies:
+ buffer: 5.7.1
+ inherits: 2.0.4
+ readable-stream: 3.6.0
+ dev: true
+
+ /blob-util/2.0.2:
+ resolution: {integrity: sha512-T7JQa+zsXXEa6/8ZhHcQEW1UFfVM49Ts65uBkFL6fz2QmrElqmbajIDJvuA0tEhRe5eIjpV9ZF+0RfZR9voJFQ==}
+ dev: true
+
+ /blocking-proxy/1.0.1:
+ resolution: {integrity: sha512-KE8NFMZr3mN2E0HcvCgRtX7DjhiIQrwle+nSVJVC/yqFb9+xznHl2ZcoBp2L9qzkI4t4cBFJ1efXF8Dwi132RA==}
+ engines: {node: '>=6.9.x'}
+ hasBin: true
+ dependencies:
+ minimist: 1.2.7
+ dev: true
+
+ /bluebird/3.7.2:
+ resolution: {integrity: sha512-XpNj6GDQzdfW+r2Wnn7xiSAd7TM3jzkxGXBGTtWKuSXv1xUV+azxAm8jdWZN06QTQk+2N2XB9jRDkvbmQmcRtg==}
+ dev: true
+
+ /body-parser/1.20.1:
+ resolution: {integrity: sha512-jWi7abTbYwajOytWCQc37VulmWiRae5RyTpaCyDcS5/lMdtwSz5lOpDE67srw/HYe35f1z3fDQw+3txg7gNtWw==}
+ engines: {node: '>= 0.8', npm: 1.2.8000 || >= 1.4.16}
+ dependencies:
+ bytes: 3.1.2
+ content-type: 1.0.4
+ debug: 2.6.9
+ depd: 2.0.0
+ destroy: 1.2.0
+ http-errors: 2.0.0
+ iconv-lite: 0.4.24
+ on-finished: 2.4.1
+ qs: 6.11.0
+ raw-body: 2.5.1
+ type-is: 1.6.18
+ unpipe: 1.0.0
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /brace-expansion/1.1.11:
+ resolution: {integrity: sha512-iCuPHDFgrHX7H2vEI/5xpz07zSHB00TpugqhmYtVmMO6518mCuRMoOYFldEBl0g187ufozdaHgWKcYFb61qGiA==}
+ dependencies:
+ balanced-match: 1.0.2
+ concat-map: 0.0.1
+ dev: true
+
+ /brace-expansion/2.0.1:
+ resolution: {integrity: sha512-XnAIvQ8eM+kC6aULx6wuQiwVsnzsi9d3WxzV3FpWTGA19F621kwdbsAcFKXgKUHZWsy+mY6iL1sHTxWEFCytDA==}
+ dependencies:
+ balanced-match: 1.0.2
+ dev: true
+
+ /braces/3.0.2:
+ resolution: {integrity: sha512-b8um+L1RzM3WDSzvhm6gIz1yfTbBt6YTlcEKAvsmqCZZFw46z626lVj9j1yEPW33H5H+lBQpZMP1k8l+78Ha0A==}
+ engines: {node: '>=8'}
+ dependencies:
+ fill-range: 7.0.1
+ dev: true
+
+ /browserslist/4.21.4:
+ resolution: {integrity: sha512-CBHJJdDmgjl3daYjN5Cp5kbTf1mUhZoS+beLklHIvkOWscs83YAhLlF3Wsh/lciQYAcbBJgTOD44VtG31ZM4Hw==}
+ engines: {node: ^6 || ^7 || ^8 || ^9 || ^10 || ^11 || ^12 || >=13.7}
+ hasBin: true
+ dependencies:
+ caniuse-lite: 1.0.30001445
+ electron-to-chromium: 1.4.284
+ node-releases: 2.0.8
+ update-browserslist-db: 1.0.10_browserslist@4.21.4
+ dev: true
+
+ /browserstack/1.6.1:
+ resolution: {integrity: sha512-GxtFjpIaKdbAyzHfFDKixKO8IBT7wR3NjbzrGc78nNs/Ciys9wU3/nBtsqsWv5nDSrdI5tz0peKuzCPuNXNUiw==}
+ dependencies:
+ https-proxy-agent: 2.2.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /buffer-crc32/0.2.13:
+ resolution: {integrity: sha512-VO9Ht/+p3SN7SKWqcrgEzjGbRSJYTx+Q1pTQC0wrWqHx0vpJraQ6GtHx8tvcg1rlK1byhU5gccxgOgj7B0TDkQ==}
+ dev: true
+
+ /buffer-from/1.1.2:
+ resolution: {integrity: sha512-E+XQCRwSbaaiChtv6k6Dwgc+bx+Bs6vuKJHHl5kox/BaKbhiXzqQOwK4cO22yElGp2OCmjwVhT3HmxgyPGnJfQ==}
+ dev: true
+
+ /buffer/5.7.1:
+ resolution: {integrity: sha512-EHcyIPBQ4BSGlvjB16k5KgAJ27CIsHY/2JBmCRReo48y9rQ3MaUzWX3KVlBa4U7MyX02HdVj0K7C3WaB3ju7FQ==}
+ dependencies:
+ base64-js: 1.5.1
+ ieee754: 1.2.1
+ dev: true
+
+ /builtin-modules/3.3.0:
+ resolution: {integrity: sha512-zhaCDicdLuWN5UbN5IMnFqNMhNfo919sH85y2/ea+5Yg9TsTkeZxpL+JLbp6cgYFS4sRLp3YV4S6yDuqVWHYOw==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /builtins/5.0.1:
+ resolution: {integrity: sha512-qwVpFEHNfhYJIzNRBvd2C1kyo6jz3ZSMPyyuR47OPdiKWlbYnZNyDWuyR175qDnAJLiCo5fBBqPb3RiXgWlkOQ==}
+ dependencies:
+ semver: 7.3.8
+ dev: true
+
+ /bytes/3.1.2:
+ resolution: {integrity: sha512-/Nf7TyzTx6S3yRJObOAV7956r8cr2+Oj8AC5dt8wSP3BQAoeX58NoHyCU8P8zGkNXStjTSi6fzO6F0pBdcYbEg==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /cacache/16.1.3:
+ resolution: {integrity: sha512-/+Emcj9DAXxX4cwlLmRI9c166RuL3w30zp4R7Joiv2cQTtTtA+jeuCAjH3ZlGnYS3tKENSrKhAzVVP9GVyzeYQ==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ '@npmcli/fs': 2.1.2
+ '@npmcli/move-file': 2.0.1
+ chownr: 2.0.0
+ fs-minipass: 2.1.0
+ glob: 8.1.0
+ infer-owner: 1.0.4
+ lru-cache: 7.14.1
+ minipass: 3.3.6
+ minipass-collect: 1.0.2
+ minipass-flush: 1.0.5
+ minipass-pipeline: 1.2.4
+ mkdirp: 1.0.4
+ p-map: 4.0.0
+ promise-inflight: 1.0.1
+ rimraf: 3.0.2
+ ssri: 9.0.1
+ tar: 6.1.13
+ unique-filename: 2.0.1
+ transitivePeerDependencies:
+ - bluebird
+ dev: true
+
+ /cacache/17.0.4:
+ resolution: {integrity: sha512-Z/nL3gU+zTUjz5pCA5vVjYM8pmaw2kxM7JEiE0fv3w77Wj+sFbi70CrBruUWH0uNcEdvLDixFpgA2JM4F4DBjA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ '@npmcli/fs': 3.1.0
+ fs-minipass: 3.0.0
+ glob: 8.1.0
+ lru-cache: 7.14.1
+ minipass: 4.0.0
+ minipass-collect: 1.0.2
+ minipass-flush: 1.0.5
+ minipass-pipeline: 1.2.4
+ p-map: 4.0.0
+ promise-inflight: 1.0.1
+ ssri: 10.0.1
+ tar: 6.1.13
+ unique-filename: 3.0.0
+ transitivePeerDependencies:
+ - bluebird
+ dev: true
+
+ /cachedir/2.3.0:
+ resolution: {integrity: sha512-A+Fezp4zxnit6FanDmv9EqXNAi3vt9DWp51/71UEhXukb7QUuvtv9344h91dyAxuTLoSYJFU299qzR3tzwPAhw==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /call-bind/1.0.2:
+ resolution: {integrity: sha512-7O+FbCihrB5WGbFYesctwmTKae6rOiIzmz1icreWJ+0aA7LJfuqhEso2T9ncpcFtzMQtzXf2QGGueWJGTYsqrA==}
+ dependencies:
+ function-bind: 1.1.1
+ get-intrinsic: 1.1.3
+ dev: true
+
+ /camelcase/5.3.1:
+ resolution: {integrity: sha512-L28STB170nwWS63UjtlEOE3dldQApaJXZkOI1uMFfzf3rRuPegHaHesyee+YxQ+W6SvRDQV6UrdOdRiR153wJg==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /caniuse-lite/1.0.30001445:
+ resolution: {integrity: sha512-8sdQIdMztYmzfTMO6KfLny878Ln9c2M0fc7EH60IjlP4Dc4PiCy7K2Vl3ITmWgOyPgVQKa5x+UP/KqFsxj4mBg==}
+ dev: true
+
+ /caseless/0.12.0:
+ resolution: {integrity: sha512-4tYFyifaFfGacoiObjJegolkwSU4xQNGbVgUiNYVUxbQ2x2lUsFvY4hVgVzGiIe6WLOPqycWXA40l+PWsxthUw==}
+ dev: true
+
+ /chalk/1.1.3:
+ resolution: {integrity: sha512-U3lRVLMSlsCfjqYPbLyVv11M9CPW4I728d6TCKMAOJueEeB9/8o+eSsMnxPJD+Q+K909sdESg7C+tIkoH6on1A==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ ansi-styles: 2.2.1
+ escape-string-regexp: 1.0.5
+ has-ansi: 2.0.0
+ strip-ansi: 3.0.1
+ supports-color: 2.0.0
+ dev: true
+
+ /chalk/2.4.2:
+ resolution: {integrity: sha512-Mti+f9lpJNcwF4tWV8/OrTTtF1gZi+f8FqlyAdouralcFWFQWF2+NgCHShjkCb+IFBLq9buZwE1xckQU4peSuQ==}
+ engines: {node: '>=4'}
+ dependencies:
+ ansi-styles: 3.2.1
+ escape-string-regexp: 1.0.5
+ supports-color: 5.5.0
+ dev: true
+
+ /chalk/4.1.2:
+ resolution: {integrity: sha512-oKnbhFyRIXpUuez8iBMmyEa4nbj4IOQyuhc/wy9kY7/WVPcwIO9VA668Pu8RkO7+0G76SLROeyw9CpQ061i4mA==}
+ engines: {node: '>=10'}
+ dependencies:
+ ansi-styles: 4.3.0
+ supports-color: 7.2.0
+ dev: true
+
+ /chardet/0.7.0:
+ resolution: {integrity: sha512-mT8iDcrh03qDGRRmoA2hmBJnxpllMR+0/0qlzjqZES6NdiWDcZkCNAk4rPFZ9Q85r27unkiNNg8ZOiwZXBHwcA==}
+ dev: true
+
+ /check-more-types/2.24.0:
+ resolution: {integrity: sha512-Pj779qHxV2tuapviy1bSZNEL1maXr13bPYpsvSDB68HlYcYuhlDrmGd63i0JHMCLKzc7rUSNIrpdJlhVlNwrxA==}
+ engines: {node: '>= 0.8.0'}
+ dev: true
+
+ /chokidar/3.5.3:
+ resolution: {integrity: sha512-Dr3sfKRP6oTcjf2JmUmFJfeVMvXBdegxB0iVQ5eb2V10uFJUCAS8OByZdVAyVb8xXNz3GjjTgj9kLWsZTqE6kw==}
+ engines: {node: '>= 8.10.0'}
+ dependencies:
+ anymatch: 3.1.3
+ braces: 3.0.2
+ glob-parent: 5.1.2
+ is-binary-path: 2.1.0
+ is-glob: 4.0.3
+ normalize-path: 3.0.0
+ readdirp: 3.6.0
+ optionalDependencies:
+ fsevents: 2.3.2
+ dev: true
+
+ /chownr/2.0.0:
+ resolution: {integrity: sha512-bIomtDF5KGpdogkLd9VspvFzk9KfpyyGlS8YFVZl7TGPBHL5snIOnxeshwVgPteQ9b4Eydl+pVbIyE1DcvCWgQ==}
+ engines: {node: '>=10'}
+ dev: true
+
+ /ci-info/3.7.1:
+ resolution: {integrity: sha512-4jYS4MOAaCIStSRwiuxc4B8MYhIe676yO1sYGzARnjXkWpmzZMMYxY6zu8WYWDhSuth5zhrQ1rhNSibyyvv4/w==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /clean-stack/2.2.0:
+ resolution: {integrity: sha512-4diC9HaTE+KRAMWhDhrGOECgWZxoevMc5TlkObMqNSsVU62PYzXZ/SMTjzyGAFF1YusgxGcSWTEXBhp0CPwQ1A==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /cli-cursor/3.1.0:
+ resolution: {integrity: sha512-I/zHAwsKf9FqGoXM4WWRACob9+SNukZTd94DWF57E4toouRulbCxcUh6RKUEOQlYTHJnzkPMySvPNaaSLNfLZw==}
+ engines: {node: '>=8'}
+ dependencies:
+ restore-cursor: 3.1.0
+ dev: true
+
+ /cli-spinners/2.7.0:
+ resolution: {integrity: sha512-qu3pN8Y3qHNgE2AFweciB1IfMnmZ/fsNTEE+NOFjmGB2F/7rLhnhzppvpCnN4FovtP26k8lHyy9ptEbNwWFLzw==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /cli-table3/0.6.3:
+ resolution: {integrity: sha512-w5Jac5SykAeZJKntOxJCrm63Eg5/4dhMWIcuTbo9rpE+brgaSZo0RuNJZeOyMgsUdhDeojvgyQLmjI+K50ZGyg==}
+ engines: {node: 10.* || >= 12.*}
+ dependencies:
+ string-width: 4.2.3
+ optionalDependencies:
+ '@colors/colors': 1.5.0
+ dev: true
+
+ /cli-truncate/2.1.0:
+ resolution: {integrity: sha512-n8fOixwDD6b/ObinzTrp1ZKFzbgvKZvuz/TvejnLn1aQfC6r52XEx85FmuC+3HI+JM7coBRXUvNqEU2PHVrHpg==}
+ engines: {node: '>=8'}
+ dependencies:
+ slice-ansi: 3.0.0
+ string-width: 4.2.3
+ dev: true
+
+ /cli-width/3.0.0:
+ resolution: {integrity: sha512-FxqpkPPwu1HjuN93Omfm4h8uIanXofW0RxVEW3k5RKx+mJJYSthzNhp32Kzxxy3YAEZ/Dc/EWN1vZRY0+kOhbw==}
+ engines: {node: '>= 10'}
+ dev: true
+
+ /cliui/6.0.0:
+ resolution: {integrity: sha512-t6wbgtoCXvAzst7QgXxJYqPt0usEfbgQdftEPbLL/cvv6HPE5VgvqCuAIDR0NgU52ds6rFwqrgakNLrHEjCbrQ==}
+ dependencies:
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ wrap-ansi: 6.2.0
+ dev: true
+
+ /cliui/7.0.4:
+ resolution: {integrity: sha512-OcRE68cOsVMXp1Yvonl/fzkQOyjLSu/8bhPDfQt0e0/Eb283TKP20Fs2MqoPsr9SwA595rRCA+QMzYc9nBP+JQ==}
+ dependencies:
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ wrap-ansi: 7.0.0
+ dev: true
+
+ /cliui/8.0.1:
+ resolution: {integrity: sha512-BSeNnyus75C4//NQ9gQt1/csTXyo/8Sb+afLAkzAptFuMsod9HFokGNudZpi/oQV73hnVK+sR+5PVRMd+Dr7YQ==}
+ engines: {node: '>=12'}
+ dependencies:
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ wrap-ansi: 7.0.0
+ dev: true
+
+ /clone/1.0.4:
+ resolution: {integrity: sha512-JQHZ2QMW6l3aH/j6xCqQThY/9OH4D/9ls34cgkUBiEeocRTU04tHfKPBsUK1PqZCUQM7GiA0IIXJSuXHI64Kbg==}
+ engines: {node: '>=0.8'}
+ dev: true
+
+ /color-convert/1.9.3:
+ resolution: {integrity: sha512-QfAUtd+vFdAtFQcC8CCyYt1fYWxSqAiK2cSD6zDB8N3cpsEBAvRxp9zOGg6G/SHHJYAT88/az/IuDGALsNVbGg==}
+ dependencies:
+ color-name: 1.1.3
+ dev: true
+
+ /color-convert/2.0.1:
+ resolution: {integrity: sha512-RRECPsj7iu/xb5oKYcsFHSppFNnsj/52OVTRKb4zP5onXwVF3zVmmToNcOfGC+CRDpfK/U584fMg38ZHCaElKQ==}
+ engines: {node: '>=7.0.0'}
+ dependencies:
+ color-name: 1.1.4
+ dev: true
+
+ /color-name/1.1.3:
+ resolution: {integrity: sha512-72fSenhMw2HZMTVHeCA9KCmpEIbzWiQsjN+BHcBbS9vr1mtt+vJjPdksIBNUmKAW8TFUDPJK5SUU3QhE9NEXDw==}
+ dev: true
+
+ /color-name/1.1.4:
+ resolution: {integrity: sha512-dOy+3AuW3a2wNbZHIuMZpTcgjGuLU/uBL/ubcZF9OXbDo8ff4O8yVp5Bf0efS8uEoYo5q4Fx7dY9OgQGXgAsQA==}
+ dev: true
+
+ /color-support/1.1.3:
+ resolution: {integrity: sha512-qiBjkpbMLO/HL68y+lh4q0/O1MZFj2RX6X/KmMa3+gJD3z+WwI1ZzDHysvqHGS3mP6mznPckpXmw1nI9cJjyRg==}
+ hasBin: true
+ dev: true
+
+ /colorette/2.0.19:
+ resolution: {integrity: sha512-3tlv/dIP7FWvj3BsbHrGLJ6l/oKh1O3TcgBqMn+yyCagOxc23fyzDS6HypQbgxWbkpDnf52p1LuR4eWDQ/K9WQ==}
+ dev: true
+
+ /combined-stream/1.0.8:
+ resolution: {integrity: sha512-FQN4MRfuJeHf7cBbBMJFXhKSDq+2kAArBlmRBvcvFE5BB1HZKXtSFASDhdlz9zOYwxh8lDdnvmMOe/+5cdoEdg==}
+ engines: {node: '>= 0.8'}
+ dependencies:
+ delayed-stream: 1.0.0
+ dev: true
+
+ /commander/2.20.3:
+ resolution: {integrity: sha512-GpVkmM8vF2vQUkj2LvZmD35JxeJOLCwJ9cUkugyk2nuhbv3+mJvpLYYt+0+USMxE+oj+ey/lJEnhZw75x/OMcQ==}
+ dev: true
+
+ /commander/4.1.1:
+ resolution: {integrity: sha512-NOKm8xhkzAjzFx8B2v5OAHT+u5pRQc2UCa2Vq9jYL/31o2wi9mxBA7LIFs3sV5VSC49z6pEhfbMULvShKj26WA==}
+ engines: {node: '>= 6'}
+ dev: true
+
+ /commander/5.1.0:
+ resolution: {integrity: sha512-P0CysNDQ7rtVw4QIQtm+MRxV66vKFSvlsQvGYXZWR3qFU0jlMKHZZZgw8e+8DSah4UDKMqnknRDQz+xuQXQ/Zg==}
+ engines: {node: '>= 6'}
+ dev: true
+
+ /common-tags/1.8.2:
+ resolution: {integrity: sha512-gk/Z852D2Wtb//0I+kRFNKKE9dIIVirjoqPoA1wJU+XePVXZfGeBpk45+A1rKO4Q43prqWBNY/MiIeRLbPWUaA==}
+ engines: {node: '>=4.0.0'}
+ dev: true
+
+ /concat-map/0.0.1:
+ resolution: {integrity: sha512-/Srv4dswyQNBfohGpz9o6Yb3Gz3SrUDqBH5rTuhGR7ahtlbYKnVxw2bCFMRljaA7EXHaXZ8wsHdodFvbkhKmqg==}
+ dev: true
+
+ /connect/3.7.0:
+ resolution: {integrity: sha512-ZqRXc+tZukToSNmh5C2iWMSoV3X1YUcPbqEM4DkEG5tNQXrQUZCNVGGv3IuicnkMtPfGf3Xtp8WCXs295iQ1pQ==}
+ engines: {node: '>= 0.10.0'}
+ dependencies:
+ debug: 2.6.9
+ finalhandler: 1.1.2
+ parseurl: 1.3.3
+ utils-merge: 1.0.1
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /console-control-strings/1.1.0:
+ resolution: {integrity: sha512-ty/fTekppD2fIwRvnZAVdeOiGd1c7YXEixbgJTNzqcxJWKQnjJ/V1bNEEE6hygpM3WjwHFUVK6HTjWSzV4a8sQ==}
+ dev: true
+
+ /content-type/1.0.4:
+ resolution: {integrity: sha512-hIP3EEPs8tB9AT1L+NUqtwOAps4mk2Zob89MWXMHjHWg9milF/j4osnnQLXBCBFBk/tvIG/tUc9mOUJiPBhPXA==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /convert-source-map/1.9.0:
+ resolution: {integrity: sha512-ASFBup0Mz1uyiIjANan1jzLQami9z1PoYSZCiiYW2FczPbenXc45FZdBZLzOT+r6+iciuEModtmCti+hjaAk0A==}
+ dev: true
+
+ /cookie/0.4.2:
+ resolution: {integrity: sha512-aSWTXFzaKWkvHO1Ny/s+ePFpvKsPnjc551iI41v3ny/ow6tBG5Vd+FuqGNhh1LxOmVzOlGUriIlOaokOvhaStA==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /core-util-is/1.0.2:
+ resolution: {integrity: sha512-3lqz5YjWTYnW6dlDa5TLaTCcShfar1e40rmcJVwCBJC6mWlFuj0eCHIElmG1g5kyuJ/GD+8Wn4FFCcz4gJPfaQ==}
+ dev: true
+
+ /core-util-is/1.0.3:
+ resolution: {integrity: sha512-ZQBvi1DcpJ4GDqanjucZ2Hj3wEO5pZDS89BWbkcrvdxksJorwUDDZamX9ldFkp9aw2lmBDLgkObEA4DWNJ9FYQ==}
+ dev: true
+
+ /cors/2.8.5:
+ resolution: {integrity: sha512-KIHbLJqu73RGr/hnbrO9uBeixNGuvSQjul/jdFvS/KFSIH1hWVd1ng7zOHx+YrEfInLG7q4n6GHQ9cDtxv/P6g==}
+ engines: {node: '>= 0.10'}
+ dependencies:
+ object-assign: 4.1.1
+ vary: 1.1.2
+ dev: true
+
+ /cross-spawn/7.0.3:
+ resolution: {integrity: sha512-iRDPJKUPVEND7dHPO8rkbOnPpyDygcDFtWjpeWNCgy8WP2rXcxXL8TskReQl6OrB2G7+UJrags1q15Fudc7G6w==}
+ engines: {node: '>= 8'}
+ dependencies:
+ path-key: 3.1.1
+ shebang-command: 2.0.0
+ which: 2.0.2
+ dev: true
+
+ /custom-event/1.0.1:
+ resolution: {integrity: sha512-GAj5FOq0Hd+RsCGVJxZuKaIDXDf3h6GQoNEjFgbLLI/trgtavwUbSnZ5pVfg27DVCaWjIohryS0JFwIJyT2cMg==}
+ dev: true
+
+ /cypress/12.3.0:
+ resolution: {integrity: sha512-ZQNebibi6NBt51TRxRMYKeFvIiQZ01t50HSy7z/JMgRVqBUey3cdjog5MYEbzG6Ktti5ckDt1tfcC47lmFwXkw==}
+ engines: {node: ^14.0.0 || ^16.0.0 || >=18.0.0}
+ hasBin: true
+ requiresBuild: true
+ dependencies:
+ '@cypress/request': 2.88.11
+ '@cypress/xvfb': 1.2.4_supports-color@8.1.1
+ '@types/node': 14.18.36
+ '@types/sinonjs__fake-timers': 8.1.1
+ '@types/sizzle': 2.3.3
+ arch: 2.2.0
+ blob-util: 2.0.2
+ bluebird: 3.7.2
+ buffer: 5.7.1
+ cachedir: 2.3.0
+ chalk: 4.1.2
+ check-more-types: 2.24.0
+ cli-cursor: 3.1.0
+ cli-table3: 0.6.3
+ commander: 5.1.0
+ common-tags: 1.8.2
+ dayjs: 1.11.7
+ debug: 4.3.4_supports-color@8.1.1
+ enquirer: 2.3.6
+ eventemitter2: 6.4.7
+ execa: 4.1.0
+ executable: 4.1.1
+ extract-zip: 2.0.1_supports-color@8.1.1
+ figures: 3.2.0
+ fs-extra: 9.1.0
+ getos: 3.2.1
+ is-ci: 3.0.1
+ is-installed-globally: 0.4.0
+ lazy-ass: 1.6.0
+ listr2: 3.14.0_enquirer@2.3.6
+ lodash: 4.17.21
+ log-symbols: 4.1.0
+ minimist: 1.2.7
+ ospath: 1.2.2
+ pretty-bytes: 5.6.0
+ proxy-from-env: 1.0.0
+ request-progress: 3.0.0
+ semver: 7.3.8
+ supports-color: 8.1.1
+ tmp: 0.2.1
+ untildify: 4.0.0
+ yauzl: 2.10.0
+ dev: true
+
+ /dashdash/1.14.1:
+ resolution: {integrity: sha512-jRFi8UDGo6j+odZiEpjazZaWqEal3w/basFjQHQEwVtZJGDpxbH1MeYluwCS8Xq5wmLJooDlMgvVarmWfGM44g==}
+ engines: {node: '>=0.10'}
+ dependencies:
+ assert-plus: 1.0.0
+ dev: true
+
+ /date-format/4.0.14:
+ resolution: {integrity: sha512-39BOQLs9ZjKh0/patS9nrT8wc3ioX3/eA/zgbKNopnF2wCqJEoxywwwElATYvRsXdnOxA/OQeQoFZ3rFjVajhg==}
+ engines: {node: '>=4.0'}
+ dev: true
+
+ /dayjs/1.11.7:
+ resolution: {integrity: sha512-+Yw9U6YO5TQohxLcIkrXBeY73WP3ejHWVvx8XCk3gxvQDCTEmS48ZrSZCKciI7Bhl/uCMyxYtE9UqRILmFphkQ==}
+ dev: true
+
+ /debug/2.6.9:
+ resolution: {integrity: sha512-bC7ElrdJaJnPbAP+1EotYvqZsb3ecl5wi6Bfi6BJTUcNowp6cvspg0jXznRTKDjm/E7AdgFBVeAPVMNcKGsHMA==}
+ peerDependencies:
+ supports-color: '*'
+ peerDependenciesMeta:
+ supports-color:
+ optional: true
+ dependencies:
+ ms: 2.0.0
+ dev: true
+
+ /debug/3.2.7:
+ resolution: {integrity: sha512-CFjzYYAi4ThfiQvizrFQevTTXHtnCqWfe7x1AhgEscTz6ZbLbfoLRLPugTQyBth6f8ZERVUSyWHFD/7Wu4t1XQ==}
+ peerDependencies:
+ supports-color: '*'
+ peerDependenciesMeta:
+ supports-color:
+ optional: true
+ dependencies:
+ ms: 2.1.3
+ dev: true
+
+ /debug/3.2.7_supports-color@8.1.1:
+ resolution: {integrity: sha512-CFjzYYAi4ThfiQvizrFQevTTXHtnCqWfe7x1AhgEscTz6ZbLbfoLRLPugTQyBth6f8ZERVUSyWHFD/7Wu4t1XQ==}
+ peerDependencies:
+ supports-color: '*'
+ peerDependenciesMeta:
+ supports-color:
+ optional: true
+ dependencies:
+ ms: 2.1.3
+ supports-color: 8.1.1
+ dev: true
+
+ /debug/4.3.4:
+ resolution: {integrity: sha512-PRWFHuSU3eDtQJPvnNY7Jcket1j0t5OuOsFzPPzsekD52Zl8qUfFIPEiswXqIvHWGVHOgX+7G/vCNNhehwxfkQ==}
+ engines: {node: '>=6.0'}
+ peerDependencies:
+ supports-color: '*'
+ peerDependenciesMeta:
+ supports-color:
+ optional: true
+ dependencies:
+ ms: 2.1.2
+ dev: true
+
+ /debug/4.3.4_supports-color@8.1.1:
+ resolution: {integrity: sha512-PRWFHuSU3eDtQJPvnNY7Jcket1j0t5OuOsFzPPzsekD52Zl8qUfFIPEiswXqIvHWGVHOgX+7G/vCNNhehwxfkQ==}
+ engines: {node: '>=6.0'}
+ peerDependencies:
+ supports-color: '*'
+ peerDependenciesMeta:
+ supports-color:
+ optional: true
+ dependencies:
+ ms: 2.1.2
+ supports-color: 8.1.1
+ dev: true
+
+ /decamelize/1.2.0:
+ resolution: {integrity: sha512-z2S+W9X73hAUUki+N+9Za2lBlun89zigOyGrsax+KUQ6wKW4ZoWpEYBkGhQjwAjjDCkWxhY0VKEhk8wzY7F5cA==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /deepmerge/4.2.2:
+ resolution: {integrity: sha512-FJ3UgI4gIl+PHZm53knsuSFpE+nESMr7M4v9QcgB7S63Kj/6WqMiFQJpBBYz1Pt+66bZpP3Q7Lye0Oo9MPKEdg==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /defaults/1.0.4:
+ resolution: {integrity: sha512-eFuaLoy/Rxalv2kr+lqMlUnrDWV+3j4pljOIJgLIhI058IQfWJ7vXhyEIHu+HtC738klGALYxOKDO0bQP3tg8A==}
+ dependencies:
+ clone: 1.0.4
+ dev: true
+
+ /define-lazy-prop/2.0.0:
+ resolution: {integrity: sha512-Ds09qNh8yw3khSjiJjiUInaGX9xlqZDY7JVryGxdxV7NPeuqQfplOpQ66yJFZut3jLa5zOwkXw1g9EI2uKh4Og==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /del/2.2.2:
+ resolution: {integrity: sha512-Z4fzpbIRjOu7lO5jCETSWoqUDVe0IPOlfugBsF6suen2LKDlVb4QZpKEM9P+buNJ4KI1eN7I083w/pbKUpsrWQ==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ globby: 5.0.0
+ is-path-cwd: 1.0.0
+ is-path-in-cwd: 1.0.1
+ object-assign: 4.1.1
+ pify: 2.3.0
+ pinkie-promise: 2.0.1
+ rimraf: 2.7.1
+ dev: true
+
+ /delayed-stream/1.0.0:
+ resolution: {integrity: sha512-ZySD7Nf91aLB0RxL4KGrKHBXl7Eds1DAmEdcoVawXnLD7SDhpNgtuII2aAkg7a7QS41jxPSZ17p4VdGnMHk3MQ==}
+ engines: {node: '>=0.4.0'}
+ dev: true
+
+ /delegates/1.0.0:
+ resolution: {integrity: sha512-bd2L678uiWATM6m5Z1VzNCErI3jiGzt6HGY8OVICs40JQq/HALfbyNJmp0UDakEY4pMMaN0Ly5om/B1VI/+xfQ==}
+ dev: true
+
+ /depd/1.1.2:
+ resolution: {integrity: sha512-7emPTl6Dpo6JRXOXjLRxck+FlLRX5847cLKEn00PLAgc3g2hTZZgr+e4c2v6QpSmLeFP3n5yUo7ft6avBK/5jQ==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /depd/2.0.0:
+ resolution: {integrity: sha512-g7nH6P6dyDioJogAAGprGpCtVImJhpPk/roCzdb3fIh61/s/nPsfR6onyMwkCAR/OlC3yBC0lESvUoQEAssIrw==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /dependency-graph/0.11.0:
+ resolution: {integrity: sha512-JeMq7fEshyepOWDfcfHK06N3MhyPhz++vtqWhMT5O9A3K42rdsEDpfdVqjaqaAhsw6a+ZqeDvQVtD0hFHQWrzg==}
+ engines: {node: '>= 0.6.0'}
+ dev: true
+
+ /destroy/1.2.0:
+ resolution: {integrity: sha512-2sJGJTaXIIaR1w4iJSNoN0hnMY7Gpc/n8D4qSCJw8QqFWXf7cuAgnEHxBpweaVcPevC2l3KpjYCx3NypQQgaJg==}
+ engines: {node: '>= 0.8', npm: 1.2.8000 || >= 1.4.16}
+ dev: true
+
+ /di/0.0.1:
+ resolution: {integrity: sha512-uJaamHkagcZtHPqCIHZxnFrXlunQXgBOsZSUOWwFw31QJCAbyTBoHMW75YOTur5ZNx8pIeAKgf6GWIgaqqiLhA==}
+ dev: true
+
+ /dom-serialize/2.2.1:
+ resolution: {integrity: sha512-Yra4DbvoW7/Z6LBN560ZwXMjoNOSAN2wRsKFGc4iBeso+mpIA6qj1vfdf9HpMaKAqG6wXTy+1SYEzmNpKXOSsQ==}
+ dependencies:
+ custom-event: 1.0.1
+ ent: 2.2.0
+ extend: 3.0.2
+ void-elements: 2.0.1
+ dev: true
+
+ /ecc-jsbn/0.1.2:
+ resolution: {integrity: sha512-eh9O+hwRHNbG4BLTjEl3nw044CkGm5X6LoaCf7LPp7UU8Qrt47JYNi6nPX8xjW97TKGKm1ouctg0QSpZe9qrnw==}
+ dependencies:
+ jsbn: 0.1.1
+ safer-buffer: 2.1.2
+ dev: true
+
+ /ee-first/1.1.1:
+ resolution: {integrity: sha512-WMwm9LhRUo+WUaRN+vRuETqG89IgZphVSNkdFgeb6sS/E4OrDIN7t48CAewSHXc6C8lefD8KKfr5vY61brQlow==}
+ dev: true
+
+ /electron-to-chromium/1.4.284:
+ resolution: {integrity: sha512-M8WEXFuKXMYMVr45fo8mq0wUrrJHheiKZf6BArTKk9ZBYCKJEOU5H8cdWgDT+qCVZf7Na4lVUaZsA+h6uA9+PA==}
+ dev: true
+
+ /emoji-regex/8.0.0:
+ resolution: {integrity: sha512-MSjYzcWNOA0ewAHpz0MxpYFvwg6yjy1NG3xteoqz644VCo/RPgnr1/GGt+ic3iJTzQ8Eu3TdM14SawnVUmGE6A==}
+ dev: true
+
+ /encodeurl/1.0.2:
+ resolution: {integrity: sha512-TPJXq8JqFaVYm2CWmPvnP2Iyo4ZSM7/QKcSmuMLDObfpH5fi7RUGmd/rTDf+rut/saiDiQEeVTNgAmJEdAOx0w==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /encoding/0.1.13:
+ resolution: {integrity: sha512-ETBauow1T35Y/WZMkio9jiM0Z5xjHHmJ4XmjZOq1l/dXz3lr2sRn87nJy20RupqSh1F2m3HHPSp8ShIPQJrJ3A==}
+ requiresBuild: true
+ dependencies:
+ iconv-lite: 0.6.3
+ dev: true
+ optional: true
+
+ /end-of-stream/1.4.4:
+ resolution: {integrity: sha512-+uw1inIHVPQoaVuHzRyXd21icM+cnt4CzD5rW+NC1wjOUSTOs+Te7FOv7AhN7vS9x/oIyhLP5PR1H+phQAHu5Q==}
+ dependencies:
+ once: 1.4.0
+ dev: true
+
+ /engine.io-parser/5.0.6:
+ resolution: {integrity: sha512-tjuoZDMAdEhVnSFleYPCtdL2GXwVTGtNjoeJd9IhIG3C1xs9uwxqRNEu5WpnDZCaozwVlK/nuQhpodhXSIMaxw==}
+ engines: {node: '>=10.0.0'}
+ dev: true
+
+ /engine.io/6.2.1:
+ resolution: {integrity: sha512-ECceEFcAaNRybd3lsGQKas3ZlMVjN3cyWwMP25D2i0zWfyiytVbTpRPa34qrr+FHddtpBVOmq4H/DCv1O0lZRA==}
+ engines: {node: '>=10.0.0'}
+ dependencies:
+ '@types/cookie': 0.4.1
+ '@types/cors': 2.8.13
+ '@types/node': 17.0.21
+ accepts: 1.3.8
+ base64id: 2.0.0
+ cookie: 0.4.2
+ cors: 2.8.5
+ debug: 4.3.4
+ engine.io-parser: 5.0.6
+ ws: 8.2.3
+ transitivePeerDependencies:
+ - bufferutil
+ - supports-color
+ - utf-8-validate
+ dev: true
+
+ /enquirer/2.3.6:
+ resolution: {integrity: sha512-yjNnPr315/FjS4zIsUxYguYUPP2e1NK4d7E7ZOLiyYCcbFBiTMyID+2wvm2w6+pZ/odMA7cRkjhsPbltwBOrLg==}
+ engines: {node: '>=8.6'}
+ dependencies:
+ ansi-colors: 4.1.3
+ dev: true
+
+ /ent/2.2.0:
+ resolution: {integrity: sha512-GHrMyVZQWvTIdDtpiEXdHZnFQKzeO09apj8Cbl4pKWy4i0Oprcq17usfDt5aO63swf0JOeMWjWQE/LzgSRuWpA==}
+ dev: true
+
+ /env-paths/2.2.1:
+ resolution: {integrity: sha512-+h1lkLKhZMTYjog1VEpJNG7NZJWcuc2DDk/qsqSTRRCOXiLjeQ1d1/udrUGhqMxUgAlwKNZ0cf2uqan5GLuS2A==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /err-code/2.0.3:
+ resolution: {integrity: sha512-2bmlRpNKBxT/CRmPOlyISQpNj+qSeYvcym/uT0Jx2bMOlKLtSy1ZmLuVxSEKKyor/N5yhvp/ZiG1oE3DEYMSFA==}
+ dev: true
+
+ /es6-promise/4.2.8:
+ resolution: {integrity: sha512-HJDGx5daxeIvxdBxvG2cb9g4tEvwIk3i8+nhX0yGrYmZUzbkdg8QbDevheDB8gd0//uPj4c1EQua8Q+MViT0/w==}
+ dev: true
+
+ /es6-promisify/5.0.0:
+ resolution: {integrity: sha512-C+d6UdsYDk0lMebHNR4S2NybQMMngAOnOwYBQjTOiv0MkoJMP0Myw2mgpDLBcpfCmRLxyFqYhS/CfOENq4SJhQ==}
+ dependencies:
+ es6-promise: 4.2.8
+ dev: true
+
+ /escalade/3.1.1:
+ resolution: {integrity: sha512-k0er2gUkLf8O0zKJiAhmkTnJlTvINGv7ygDNPbeIsX/TJjGJZHuh9B2UxbsaEkmlEo9MfhrSzmhIlhRlI2GXnw==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /escape-html/1.0.3:
+ resolution: {integrity: sha512-NiSupZ4OeuGwr68lGIeym/ksIZMJodUGOSCZ/FSnTxcrekbvqrgdUxlJOMpijaKZVjAJrWrGs/6Jy8OMuyj9ow==}
+ dev: true
+
+ /escape-string-regexp/1.0.5:
+ resolution: {integrity: sha512-vbRorB5FUQWvla16U8R/qgaFIya2qGzwDrNmCZuYKrbdSUMG6I1ZCGQRefkRVhuOkIGVne7BQ35DSfo1qvJqFg==}
+ engines: {node: '>=0.8.0'}
+ dev: true
+
+ /estree-walker/1.0.1:
+ resolution: {integrity: sha512-1fMXF3YP4pZZVozF8j/ZLfvnR8NSIljt56UhbZ5PeeDmmGHpgpdwQt7ITlGvYaQukCvuBRMLEiKiYC+oeIg4cg==}
+ dev: true
+
+ /eventemitter2/6.4.7:
+ resolution: {integrity: sha512-tYUSVOGeQPKt/eC1ABfhHy5Xd96N3oIijJvN3O9+TsC28T5V9yX9oEfEK5faP0EFSNVOG97qtAS68GBrQB2hDg==}
+ dev: true
+
+ /eventemitter3/4.0.7:
+ resolution: {integrity: sha512-8guHBZCwKnFhYdHr2ysuRWErTwhoN2X8XELRlrRwpmfeY2jjuUN4taQMsULKUVo1K4DvZl+0pgfyoysHxvmvEw==}
+ dev: true
+
+ /execa/4.1.0:
+ resolution: {integrity: sha512-j5W0//W7f8UxAn8hXVnwG8tLwdiUy4FJLcSupCg6maBYZDpyBvTApK7KyuI4bKj8KOh1r2YH+6ucuYtJv1bTZA==}
+ engines: {node: '>=10'}
+ dependencies:
+ cross-spawn: 7.0.3
+ get-stream: 5.2.0
+ human-signals: 1.1.1
+ is-stream: 2.0.1
+ merge-stream: 2.0.0
+ npm-run-path: 4.0.1
+ onetime: 5.1.2
+ signal-exit: 3.0.7
+ strip-final-newline: 2.0.0
+ dev: true
+
+ /executable/4.1.1:
+ resolution: {integrity: sha512-8iA79xD3uAch729dUG8xaaBBFGaEa0wdD2VkYLFHwlqosEj/jT66AzcreRDSgV7ehnNLBW2WR5jIXwGKjVdTLg==}
+ engines: {node: '>=4'}
+ dependencies:
+ pify: 2.3.0
+ dev: true
+
+ /exit/0.1.2:
+ resolution: {integrity: sha512-Zk/eNKV2zbjpKzrsQ+n1G6poVbErQxJ0LBOJXaKZ1EViLzH+hrLu9cdXI4zw9dBQJslwBEpbQ2P1oS7nDxs6jQ==}
+ engines: {node: '>= 0.8.0'}
+ dev: true
+
+ /extend/3.0.2:
+ resolution: {integrity: sha512-fjquC59cD7CyW6urNXK0FBufkZcoiGG80wTuPujX590cB5Ttln20E2UB4S/WARVqhXffZl2LNgS+gQdPIIim/g==}
+ dev: true
+
+ /external-editor/3.1.0:
+ resolution: {integrity: sha512-hMQ4CX1p1izmuLYyZqLMO/qGNw10wSv9QDCPfzXfyFrOaCSSoRfqE1Kf1s5an66J5JZC62NewG+mK49jOCtQew==}
+ engines: {node: '>=4'}
+ dependencies:
+ chardet: 0.7.0
+ iconv-lite: 0.4.24
+ tmp: 0.0.33
+ dev: true
+
+ /extract-zip/2.0.1_supports-color@8.1.1:
+ resolution: {integrity: sha512-GDhU9ntwuKyGXdZBUgTIe+vXnWj0fppUEtMDL0+idd5Sta8TGpHssn/eusA9mrPr9qNDym6SxAYZjNvCn/9RBg==}
+ engines: {node: '>= 10.17.0'}
+ hasBin: true
+ dependencies:
+ debug: 4.3.4_supports-color@8.1.1
+ get-stream: 5.2.0
+ yauzl: 2.10.0
+ optionalDependencies:
+ '@types/yauzl': 2.10.0
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /extsprintf/1.3.0:
+ resolution: {integrity: sha512-11Ndz7Nv+mvAC1j0ktTa7fAb0vLyGGX+rMHNBYQviQDGU0Hw7lhctJANqbPhu9nV9/izT/IntTgZ7Im/9LJs9g==}
+ engines: {'0': node >=0.6.0}
+ dev: true
+
+ /fast-deep-equal/3.1.3:
+ resolution: {integrity: sha512-f3qQ9oQy9j2AhBe/H9VC91wLmKBCCU/gDOnKNAYG5hswO7BLKj09Hc5HYNz9cGI++xlpDCIgDaitVs03ATR84Q==}
+ dev: true
+
+ /fast-json-stable-stringify/2.1.0:
+ resolution: {integrity: sha512-lhd/wF+Lk98HZoTCtlVraHtfh5XYijIjalXck7saUtuanSDyLMxnHhSXEDJqHxD7msR8D0uCmqlkwjCV8xvwHw==}
+ dev: true
+
+ /fd-slicer/1.1.0:
+ resolution: {integrity: sha512-cE1qsB/VwyQozZ+q1dGxR8LBYNZeofhEdUNGSMbQD3Gw2lAzX9Zb3uIU6Ebc/Fmyjo9AWWfnn0AUCHqtevs/8g==}
+ dependencies:
+ pend: 1.2.0
+ dev: true
+
+ /figures/3.2.0:
+ resolution: {integrity: sha512-yaduQFRKLXYOGgEn6AZau90j3ggSOyiqXU0F9JZfeXYhNa+Jk4X+s45A2zg5jns87GAFa34BBm2kXw4XpNcbdg==}
+ engines: {node: '>=8'}
+ dependencies:
+ escape-string-regexp: 1.0.5
+ dev: true
+
+ /fill-range/7.0.1:
+ resolution: {integrity: sha512-qOo9F+dMUmC2Lcb4BbVvnKJxTPjCm+RRpe4gDuGrzkL7mEVl/djYSu2OdQ2Pa302N4oqkSg9ir6jaLWJ2USVpQ==}
+ engines: {node: '>=8'}
+ dependencies:
+ to-regex-range: 5.0.1
+ dev: true
+
+ /finalhandler/1.1.2:
+ resolution: {integrity: sha512-aAWcW57uxVNrQZqFXjITpW3sIUQmHGG3qSb9mUah9MgMC4NeWhNOlNjXEYq3HjRAvL6arUviZGGJsBg6z0zsWA==}
+ engines: {node: '>= 0.8'}
+ dependencies:
+ debug: 2.6.9
+ encodeurl: 1.0.2
+ escape-html: 1.0.3
+ on-finished: 2.3.0
+ parseurl: 1.3.3
+ statuses: 1.5.0
+ unpipe: 1.0.0
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /find-up/4.1.0:
+ resolution: {integrity: sha512-PpOwAdQ/YlXQ2vj8a3h8IipDuYRi3wceVQQGYWxNINccq40Anw7BlsEXCMbt1Zt+OLA6Fq9suIpIWD0OsnISlw==}
+ engines: {node: '>=8'}
+ dependencies:
+ locate-path: 5.0.0
+ path-exists: 4.0.0
+ dev: true
+
+ /flatted/3.2.7:
+ resolution: {integrity: sha512-5nqDSxl8nn5BSNxyR3n4I6eDmbolI6WT+QqR547RwxQapgjQBmtktdP+HTBb/a/zLsbzERTONyUB5pefh5TtjQ==}
+ dev: true
+
+ /follow-redirects/1.15.2:
+ resolution: {integrity: sha512-VQLG33o04KaQ8uYi2tVNbdrWp1QWxNNea+nmIB4EVM28v0hmP17z7aG1+wAkNzVq4KeXTq3221ye5qTJP91JwA==}
+ engines: {node: '>=4.0'}
+ peerDependencies:
+ debug: '*'
+ peerDependenciesMeta:
+ debug:
+ optional: true
+ dev: true
+
+ /forever-agent/0.6.1:
+ resolution: {integrity: sha512-j0KLYPhm6zeac4lz3oJ3o65qvgQCcPubiyotZrXqEaG4hNagNYO8qdlUrX5vwqv9ohqeT/Z3j6+yW067yWWdUw==}
+ dev: true
+
+ /form-data/2.3.3:
+ resolution: {integrity: sha512-1lLKB2Mu3aGP1Q/2eCOx0fNbRMe7XdwktwOruhfqqd0rIJWwN4Dh+E3hrPSlDCXnSR7UtZ1N38rVXm+6+MEhJQ==}
+ engines: {node: '>= 0.12'}
+ dependencies:
+ asynckit: 0.4.0
+ combined-stream: 1.0.8
+ mime-types: 2.1.35
+ dev: true
+
+ /fs-extra/8.1.0:
+ resolution: {integrity: sha512-yhlQgA6mnOJUKOsRUFsgJdQCvkKhcz8tlZG5HBQfReYZy46OwLcY+Zia0mtdHsOo9y/hP+CxMN0TU9QxoOtG4g==}
+ engines: {node: '>=6 <7 || >=8'}
+ dependencies:
+ graceful-fs: 4.2.10
+ jsonfile: 4.0.0
+ universalify: 0.1.2
+ dev: true
+
+ /fs-extra/9.1.0:
+ resolution: {integrity: sha512-hcg3ZmepS30/7BSFqRvoo3DOMQu7IjqxO5nCDt+zM9XWjb33Wg7ziNT+Qvqbuc3+gWpzO02JubVyk2G4Zvo1OQ==}
+ engines: {node: '>=10'}
+ dependencies:
+ at-least-node: 1.0.0
+ graceful-fs: 4.2.10
+ jsonfile: 6.1.0
+ universalify: 2.0.0
+ dev: true
+
+ /fs-minipass/2.1.0:
+ resolution: {integrity: sha512-V/JgOLFCS+R6Vcq0slCuaeWEdNC3ouDlJMNIsacH2VtALiu9mV4LPrHc5cDl8k5aw6J8jwgWWpiTo5RYhmIzvg==}
+ engines: {node: '>= 8'}
+ dependencies:
+ minipass: 3.3.6
+ dev: true
+
+ /fs-minipass/3.0.0:
+ resolution: {integrity: sha512-EUojgQaSPy6sxcqcZgQv6TVF6jiKvurji3AxhAivs/Ep4O1UpS8TusaxpybfFHZ2skRhLqzk6WR8nqNYIMMDeA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ minipass: 4.0.0
+ dev: true
+
+ /fs-readdir-recursive/1.1.0:
+ resolution: {integrity: sha512-GNanXlVr2pf02+sPN40XN8HG+ePaNcvM0q5mZBd668Obwb0yD5GiUbZOFgwn8kGMY6I3mdyDJzieUy3PTYyTRA==}
+ dev: true
+
+ /fs.realpath/1.0.0:
+ resolution: {integrity: sha512-OO0pH2lK6a0hZnAdau5ItzHPI6pUlvI7jMVnxUQRtw4owF2wk8lOSabtGDCTP4Ggrg2MbGnWO9X8K1t4+fGMDw==}
+ dev: true
+
+ /fsevents/2.3.2:
+ resolution: {integrity: sha512-xiqMQR4xAeHTuB9uWm+fFRcIOgKBMiOBP+eXiyT7jsgVCq1bkVygt00oASowB7EdtpOHaaPgKt812P9ab+DDKA==}
+ engines: {node: ^8.16.0 || ^10.6.0 || >=11.0.0}
+ os: [darwin]
+ requiresBuild: true
+ dev: true
+ optional: true
+
+ /function-bind/1.1.1:
+ resolution: {integrity: sha512-yIovAzMX49sF8Yl58fSCWJ5svSLuaibPxXQJFLmBObTuCr0Mf1KiPopGM9NiFjiYBCbfaa2Fh6breQ6ANVTI0A==}
+ dev: true
+
+ /gauge/4.0.4:
+ resolution: {integrity: sha512-f9m+BEN5jkg6a0fZjleidjN51VE1X+mPFQ2DJ0uv1V39oCLCbsGe6yjbBnp7eK7z/+GAon99a3nHuqbuuthyPg==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ aproba: 2.0.0
+ color-support: 1.1.3
+ console-control-strings: 1.1.0
+ has-unicode: 2.0.1
+ signal-exit: 3.0.7
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ wide-align: 1.1.5
+ dev: true
+
+ /gensync/1.0.0-beta.2:
+ resolution: {integrity: sha512-3hN7NaskYvMDLQY55gnW3NQ+mesEAepTqlg+VEbj7zzqEMBVNhzcGYYeqFo/TlYz6eQiFcp1HcsCZO+nGgS8zg==}
+ engines: {node: '>=6.9.0'}
+ dev: true
+
+ /get-caller-file/2.0.5:
+ resolution: {integrity: sha512-DyFP3BM/3YHTQOCUL/w0OZHR0lpKeGrxotcHWcqNEdnltqFwXVfhEBQ94eIo34AfQpo0rGki4cyIiftY06h2Fg==}
+ engines: {node: 6.* || 8.* || >= 10.*}
+ dev: true
+
+ /get-intrinsic/1.1.3:
+ resolution: {integrity: sha512-QJVz1Tj7MS099PevUG5jvnt9tSkXN8K14dxQlikJuPt4uD9hHAHjLyLBiLR5zELelBdD9QNRAXZzsJx0WaDL9A==}
+ dependencies:
+ function-bind: 1.1.1
+ has: 1.0.3
+ has-symbols: 1.0.3
+ dev: true
+
+ /get-stream/5.2.0:
+ resolution: {integrity: sha512-nBF+F1rAZVCu/p7rjzgA+Yb4lfYXrpl7a6VmJrU8wF9I1CKvP/QwPNZHnOlwbTkY6dvtFIzFMSyQXbLoTQPRpA==}
+ engines: {node: '>=8'}
+ dependencies:
+ pump: 3.0.0
+ dev: true
+
+ /getos/3.2.1:
+ resolution: {integrity: sha512-U56CfOK17OKgTVqozZjUKNdkfEv6jk5WISBJ8SHoagjE6L69zOwl3Z+O8myjY9MEW3i2HPWQBt/LTbCgcC973Q==}
+ dependencies:
+ async: 3.2.4
+ dev: true
+
+ /getpass/0.1.7:
+ resolution: {integrity: sha512-0fzj9JxOLfJ+XGLhR8ze3unN0KZCgZwiSSDz168VERjK8Wl8kVSdcu2kspd4s4wtAa1y/qrVRiAA0WclVsu0ng==}
+ dependencies:
+ assert-plus: 1.0.0
+ dev: true
+
+ /glob-parent/5.1.2:
+ resolution: {integrity: sha512-AOIgSQCepiJYwP3ARnGx+5VnTu2HBYdzbGP45eLw1vr3zB3vZLeyed1sC9hnbcOc9/SrMyM5RPQrkGz4aS9Zow==}
+ engines: {node: '>= 6'}
+ dependencies:
+ is-glob: 4.0.3
+ dev: true
+
+ /glob/7.2.3:
+ resolution: {integrity: sha512-nFR0zLpU2YCaRxwoCJvL6UvCH2JFyFVIvwTLsIf21AuHlMskA1hhTdk+LlYJtOlYt9v6dvszD2BGRqBL+iQK9Q==}
+ dependencies:
+ fs.realpath: 1.0.0
+ inflight: 1.0.6
+ inherits: 2.0.4
+ minimatch: 3.1.2
+ once: 1.4.0
+ path-is-absolute: 1.0.1
+ dev: true
+
+ /glob/8.1.0:
+ resolution: {integrity: sha512-r8hpEjiQEYlF2QU0df3dS+nxxSIreXQS1qRhMJM0Q5NDdR386C7jb7Hwwod8Fgiuex+k0GFjgft18yvxm5XoCQ==}
+ engines: {node: '>=12'}
+ dependencies:
+ fs.realpath: 1.0.0
+ inflight: 1.0.6
+ inherits: 2.0.4
+ minimatch: 5.1.4
+ once: 1.4.0
+ dev: true
+
+ /global-dirs/3.0.1:
+ resolution: {integrity: sha512-NBcGGFbBA9s1VzD41QXDG+3++t9Mn5t1FpLdhESY6oKY4gYTFpX4wO3sqGUa0Srjtbfj3szX0RnemmrVRUdULA==}
+ engines: {node: '>=10'}
+ dependencies:
+ ini: 2.0.0
+ dev: true
+
+ /globals/11.12.0:
+ resolution: {integrity: sha512-WOBp/EEGUiIsJSp7wcv/y6MO+lV9UoncWqxuFfm8eBwzWNgyfBd6Gz+IeKQ9jCmyhoH99g15M3T+QaVHFjizVA==}
+ engines: {node: '>=4'}
+ dev: true
+
+ /globby/5.0.0:
+ resolution: {integrity: sha512-HJRTIH2EeH44ka+LWig+EqT2ONSYpVlNfx6pyd592/VF1TbfljJ7elwie7oSwcViLGqOdWocSdu2txwBF9bjmQ==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ array-union: 1.0.2
+ arrify: 1.0.1
+ glob: 7.2.3
+ object-assign: 4.1.1
+ pify: 2.3.0
+ pinkie-promise: 2.0.1
+ dev: true
+
+ /graceful-fs/4.2.10:
+ resolution: {integrity: sha512-9ByhssR2fPVsNZj478qUUbKfmL0+t5BDVyjShtyZZLiK7ZDAArFFfopyOTj0M05wE2tJPisA4iTnnXl2YoPvOA==}
+ dev: true
+
+ /har-schema/2.0.0:
+ resolution: {integrity: sha512-Oqluz6zhGX8cyRaTQlFMPw80bSJVG2x/cFb8ZPhUILGgHka9SsokCCOQgpveePerqidZOrT14ipqfJb7ILcW5Q==}
+ engines: {node: '>=4'}
+ dev: true
+
+ /har-validator/5.1.5:
+ resolution: {integrity: sha512-nmT2T0lljbxdQZfspsno9hgrG3Uir6Ks5afism62poxqBM6sDnMEuPmzTq8XN0OEwqKLLdh1jQI3qyE66Nzb3w==}
+ engines: {node: '>=6'}
+ deprecated: this library is no longer supported
+ dependencies:
+ ajv: 6.12.6
+ har-schema: 2.0.0
+ dev: true
+
+ /has-ansi/2.0.0:
+ resolution: {integrity: sha512-C8vBJ8DwUCx19vhm7urhTuUsr4/IyP6l4VzNQDv+ryHQObW3TTTp9yB68WpYgRe2bbaGuZ/se74IqFeVnMnLZg==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ ansi-regex: 2.1.1
+ dev: true
+
+ /has-flag/3.0.0:
+ resolution: {integrity: sha512-sKJf1+ceQBr4SMkvQnBDNDtf4TXpVhVGateu0t918bl30FnbE2m4vNLX+VWe/dpjlb+HugGYzW7uQXH98HPEYw==}
+ engines: {node: '>=4'}
+ dev: true
+
+ /has-flag/4.0.0:
+ resolution: {integrity: sha512-EykJT/Q1KjTWctppgIAgfSO0tKVuZUjhgMr17kqTumMl6Afv3EISleU7qZUzoXDFTAHTDC4NOoG/ZxU3EvlMPQ==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /has-symbols/1.0.3:
+ resolution: {integrity: sha512-l3LCuF6MgDNwTDKkdYGEihYjt5pRPbEg46rtlmnSPlUbgmB8LOIrKJbYYFBSbnPaJexMKtiPO8hmeRjRz2Td+A==}
+ engines: {node: '>= 0.4'}
+ dev: true
+
+ /has-unicode/2.0.1:
+ resolution: {integrity: sha512-8Rf9Y83NBReMnx0gFzA8JImQACstCYWUplepDa9xprwwtmgEZUF0h/i5xSA625zB/I37EtrswSST6OXxwaaIJQ==}
+ dev: true
+
+ /has/1.0.3:
+ resolution: {integrity: sha512-f2dvO0VU6Oej7RkWJGrehjbzMAjFp5/VKPp5tTpWIV4JHHZK1/BxbFRtf/siA2SWTe09caDmVtYYzWEIbBS4zw==}
+ engines: {node: '>= 0.4.0'}
+ dependencies:
+ function-bind: 1.1.1
+ dev: true
+
+ /hosted-git-info/5.2.1:
+ resolution: {integrity: sha512-xIcQYMnhcx2Nr4JTjsFmwwnr9vldugPy9uVm0o87bjqqWMv9GaqsTeT+i99wTl0mk1uLxJtHxLb8kymqTENQsw==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ lru-cache: 7.14.1
+ dev: true
+
+ /hosted-git-info/6.1.1:
+ resolution: {integrity: sha512-r0EI+HBMcXadMrugk0GCQ+6BQV39PiWAZVfq7oIckeGiN7sjRGyQxPdft3nQekFTCQbYxLBH+/axZMeH8UX6+w==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ lru-cache: 7.14.1
+ dev: true
+
+ /html-insert-assets/0.14.3:
+ resolution: {integrity: sha512-4st+C8j3KFwzo8nZE8g7lgzuF+8l6+0WxhXKszV0+siYtbP4WZCHO4U2DVnW/9PJ4PSQYUuz/u92pXByDzZdJg==}
+ hasBin: true
+ dependencies:
+ mkdirp: 1.0.4
+ parse5: 6.0.1
+ dev: true
+
+ /http-cache-semantics/4.1.0:
+ resolution: {integrity: sha512-carPklcUh7ROWRK7Cv27RPtdhYhUsela/ue5/jKzjegVvXDqM2ILE9Q2BGn9JZJh1g87cp56su/FgQSzcWS8cQ==}
+ dev: true
+
+ /http-errors/2.0.0:
+ resolution: {integrity: sha512-FtwrG/euBzaEjYeRqOgly7G0qviiXoJWnvEH2Z1plBdXgbyjv34pHTSb9zoeHMyDy33+DWy5Wt9Wo+TURtOYSQ==}
+ engines: {node: '>= 0.8'}
+ dependencies:
+ depd: 2.0.0
+ inherits: 2.0.4
+ setprototypeof: 1.2.0
+ statuses: 2.0.1
+ toidentifier: 1.0.1
+ dev: true
+
+ /http-proxy-agent/5.0.0:
+ resolution: {integrity: sha512-n2hY8YdoRE1i7r6M0w9DIw5GgZN0G25P8zLCRQ8rjXtTU3vsNFBI/vWK/UIeE6g5MUUz6avwAPXmL6Fy9D/90w==}
+ engines: {node: '>= 6'}
+ dependencies:
+ '@tootallnate/once': 2.0.0
+ agent-base: 6.0.2
+ debug: 4.3.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /http-proxy/1.18.1:
+ resolution: {integrity: sha512-7mz/721AbnJwIVbnaSv1Cz3Am0ZLT/UBwkC92VlxhXv/k/BBQfM2fXElQNC27BVGr0uwUpplYPQM9LnaBMR5NQ==}
+ engines: {node: '>=8.0.0'}
+ dependencies:
+ eventemitter3: 4.0.7
+ follow-redirects: 1.15.2
+ requires-port: 1.0.0
+ transitivePeerDependencies:
+ - debug
+ dev: true
+
+ /http-signature/1.2.0:
+ resolution: {integrity: sha512-CAbnr6Rz4CYQkLYUtSNXxQPUH2gK8f3iWexVlsnMeD+GjlsQ0Xsy1cOX+mN3dtxYomRy21CiOzU8Uhw6OwncEQ==}
+ engines: {node: '>=0.8', npm: '>=1.3.7'}
+ dependencies:
+ assert-plus: 1.0.0
+ jsprim: 1.4.2
+ sshpk: 1.17.0
+ dev: true
+
+ /http-signature/1.3.6:
+ resolution: {integrity: sha512-3adrsD6zqo4GsTqtO7FyrejHNv+NgiIfAfv68+jVlFmSr9OGy7zrxONceFRLKvnnZA5jbxQBX1u9PpB6Wi32Gw==}
+ engines: {node: '>=0.10'}
+ dependencies:
+ assert-plus: 1.0.0
+ jsprim: 2.0.2
+ sshpk: 1.17.0
+ dev: true
+
+ /https-proxy-agent/2.2.4:
+ resolution: {integrity: sha512-OmvfoQ53WLjtA9HeYP9RNrWMJzzAz1JGaSFr1nijg0PVR1JaD/xbJq1mdEIIlxGpXp9eSe/O2LgU9DJmTPd0Eg==}
+ engines: {node: '>= 4.5.0'}
+ dependencies:
+ agent-base: 4.3.0
+ debug: 3.2.7
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /https-proxy-agent/5.0.1:
+ resolution: {integrity: sha512-dFcAjpTQFgoLMzC2VwU+C/CbS7uRL0lWmxDITmqm7C+7F0Odmj6s9l6alZc6AELXhrnggM2CeWSXHGOdX2YtwA==}
+ engines: {node: '>= 6'}
+ dependencies:
+ agent-base: 6.0.2
+ debug: 4.3.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /human-signals/1.1.1:
+ resolution: {integrity: sha512-SEQu7vl8KjNL2eoGBLF3+wAjpsNfA9XMlXAYj/3EdaNfAlxKthD1xjEQfGOUhllCGGJVNY34bRr6lPINhNjyZw==}
+ engines: {node: '>=8.12.0'}
+ dev: true
+
+ /humanize-ms/1.2.1:
+ resolution: {integrity: sha512-Fl70vYtsAFb/C06PTS9dZBo7ihau+Tu/DNCk/OyHhea07S+aeMWpFFkUaXRa8fI+ScZbEI8dfSxwY7gxZ9SAVQ==}
+ dependencies:
+ ms: 2.1.3
+ dev: true
+
+ /iconv-lite/0.4.24:
+ resolution: {integrity: sha512-v3MXnZAcvnywkTUEZomIActle7RXXeedOR31wwl7VlyoXO4Qi9arvSenNQWne1TcRwhCL1HwLI21bEqdpj8/rA==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ safer-buffer: 2.1.2
+ dev: true
+
+ /iconv-lite/0.6.3:
+ resolution: {integrity: sha512-4fCk79wshMdzMp2rH06qWrJE4iolqLhCUH+OiuIgU++RB0+94NlDL81atO7GX55uUKueo0txHNtvEyI6D7WdMw==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ safer-buffer: 2.1.2
+ dev: true
+ optional: true
+
+ /ieee754/1.2.1:
+ resolution: {integrity: sha512-dcyqhDvX1C46lXZcVqCpK+FtMRQVdIMN6/Df5js2zouUsqG7I6sFxitIC+7KYK29KdXOLHdu9zL4sFnoVQnqaA==}
+ dev: true
+
+ /ignore-walk/6.0.0:
+ resolution: {integrity: sha512-bTf9UWe/UP1yxG3QUrj/KOvEhTAUWPcv+WvbFZ28LcqznXabp7Xu6o9y1JEC18+oqODuS7VhTpekV5XvFwsxJg==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ minimatch: 5.1.4
+ dev: true
+
+ /immediate/3.0.6:
+ resolution: {integrity: sha512-XXOFtyqDjNDAQxVfYxuF7g9Il/IbWmmlQg2MYKOH8ExIT1qg6xc4zyS3HaEEATgs1btfzxq15ciUiY7gjSXRGQ==}
+ dev: true
+
+ /imurmurhash/0.1.4:
+ resolution: {integrity: sha512-JmXMZ6wuvDmLiHEml9ykzqO6lwFbof0GG4IkcGaENdCRDDmMVnny7s5HsIgHCbaq0w2MyPhDqkhTUgS2LU2PHA==}
+ engines: {node: '>=0.8.19'}
+ dev: true
+
+ /indent-string/4.0.0:
+ resolution: {integrity: sha512-EdDDZu4A2OyIK7Lr/2zG+w5jmbuk1DVBnEwREQvBzspBJkCEbRa8GxU1lghYcaGJCnRWibjDXlq779X1/y5xwg==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /infer-owner/1.0.4:
+ resolution: {integrity: sha512-IClj+Xz94+d7irH5qRyfJonOdfTzuDaifE6ZPWfx0N0+/ATZCbuTPq2prFl526urkQd90WyUKIh1DfBQ2hMz9A==}
+ dev: true
+
+ /inflight/1.0.6:
+ resolution: {integrity: sha512-k92I/b08q4wvFscXCLvqfsHCrjrF7yiXsQuIVvVE7N82W3+aqpzuUdBbfhWcy/FZR3/4IgflMgKLOsvPDrGCJA==}
+ dependencies:
+ once: 1.4.0
+ wrappy: 1.0.2
+ dev: true
+
+ /inherits/2.0.4:
+ resolution: {integrity: sha512-k/vGaX4/Yla3WzyMCvTQOXYeIHvqOKtnqBduzTHpzpQZzAskKMhZ2K+EnBiSM9zGSoIFeMpXKxa4dYeZIQqewQ==}
+ dev: true
+
+ /ini/1.3.8:
+ resolution: {integrity: sha512-JV/yugV2uzW5iMRSiZAyDtQd+nxtUnjeLt0acNdw98kKLrvuRVyB80tsREOE7yvGVgalhZ6RNXCmEHkUKBKxew==}
+ dev: true
+
+ /ini/2.0.0:
+ resolution: {integrity: sha512-7PnF4oN3CvZF23ADhA5wRaYEQpJ8qygSkbtTXWBeXWXmEVRXK+1ITciHWwHhsjv1TmW0MgacIv6hEi5pX5NQdA==}
+ engines: {node: '>=10'}
+ dev: true
+
+ /ini/3.0.1:
+ resolution: {integrity: sha512-it4HyVAUTKBc6m8e1iXWvXSTdndF7HbdN713+kvLrymxTaU4AUBWrJ4vEooP+V7fexnVD3LKcBshjGGPefSMUQ==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dev: true
+
+ /inquirer/8.2.4:
+ resolution: {integrity: sha512-nn4F01dxU8VeKfq192IjLsxu0/OmMZ4Lg3xKAns148rCaXP6ntAoEkVYZThWjwON8AlzdZZi6oqnhNbxUG9hVg==}
+ engines: {node: '>=12.0.0'}
+ dependencies:
+ ansi-escapes: 4.3.2
+ chalk: 4.1.2
+ cli-cursor: 3.1.0
+ cli-width: 3.0.0
+ external-editor: 3.1.0
+ figures: 3.2.0
+ lodash: 4.17.21
+ mute-stream: 0.0.8
+ ora: 5.4.1
+ run-async: 2.4.1
+ rxjs: 7.5.7
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ through: 2.3.8
+ wrap-ansi: 7.0.0
+ dev: true
+
+ /ip/2.0.0:
+ resolution: {integrity: sha512-WKa+XuLG1A1R0UWhl2+1XQSi+fZWMsYKffMZTTYsiZaUD8k2yDAj5atimTUD2TZkyCkNEeYE5NhFZmupOGtjYQ==}
+ dev: true
+
+ /is-binary-path/2.1.0:
+ resolution: {integrity: sha512-ZMERYes6pDydyuGidse7OsHxtbI7WVeUEozgR/g7rd0xUimYNlvZRE/K2MgZTjWy725IfelLeVcEM97mmtRGXw==}
+ engines: {node: '>=8'}
+ dependencies:
+ binary-extensions: 2.2.0
+ dev: true
+
+ /is-ci/3.0.1:
+ resolution: {integrity: sha512-ZYvCgrefwqoQ6yTyYUbQu64HsITZ3NfKX1lzaEYdkTDcfKzzCI/wthRRYKkdjHKFVgNiXKAKm65Zo1pk2as/QQ==}
+ hasBin: true
+ dependencies:
+ ci-info: 3.7.1
+ dev: true
+
+ /is-core-module/2.11.0:
+ resolution: {integrity: sha512-RRjxlvLDkD1YJwDbroBHMb+cukurkDWNyHx7D3oNB5x9rb5ogcksMC5wHCadcXoo67gVr/+3GFySh3134zi6rw==}
+ dependencies:
+ has: 1.0.3
+ dev: true
+
+ /is-docker/2.2.1:
+ resolution: {integrity: sha512-F+i2BKsFrH66iaUFc0woD8sLy8getkwTwtOBjvs56Cx4CgJDeKQeqfz8wAYiSb8JOprWhHH5p77PbmYCvvUuXQ==}
+ engines: {node: '>=8'}
+ hasBin: true
+ dev: true
+
+ /is-extglob/2.1.1:
+ resolution: {integrity: sha512-SbKbANkN603Vi4jEZv49LeVJMn4yGwsbzZworEoyEiutsN3nJYdbO36zfhGJ6QEDpOZIFkDtnq5JRxmvl3jsoQ==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /is-fullwidth-code-point/3.0.0:
+ resolution: {integrity: sha512-zymm5+u+sCsSWyD9qNaejV3DFvhCKclKdizYaJUuHA83RLjb7nSuGnddCHGv0hk+KY7BMAlsWeK4Ueg6EV6XQg==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /is-glob/4.0.3:
+ resolution: {integrity: sha512-xelSayHH36ZgE7ZWhli7pW34hNbNl8Ojv5KVmkJD4hBdD3th8Tfk9vYasLM+mXWOZhFkgZfxhLSnrwRr4elSSg==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ is-extglob: 2.1.1
+ dev: true
+
+ /is-installed-globally/0.4.0:
+ resolution: {integrity: sha512-iwGqO3J21aaSkC7jWnHP/difazwS7SFeIqxv6wEtLU8Y5KlzFTjyqcSIT0d8s4+dDhKytsk9PJZ2BkS5eZwQRQ==}
+ engines: {node: '>=10'}
+ dependencies:
+ global-dirs: 3.0.1
+ is-path-inside: 3.0.3
+ dev: true
+
+ /is-interactive/1.0.0:
+ resolution: {integrity: sha512-2HvIEKRoqS62guEC+qBjpvRubdX910WCMuJTZ+I9yvqKU2/12eSL549HMwtabb4oupdj2sMP50k+XJfB/8JE6w==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /is-lambda/1.0.1:
+ resolution: {integrity: sha512-z7CMFGNrENq5iFB9Bqo64Xk6Y9sg+epq1myIcdHaGnbMTYOxvzsEtdYqQUylB7LxfkvgrrjP32T6Ywciio9UIQ==}
+ dev: true
+
+ /is-module/1.0.0:
+ resolution: {integrity: sha512-51ypPSPCoTEIN9dy5Oy+h4pShgJmPCygKfyRCISBI+JoWT/2oJvK8QPxmwv7b/p239jXrm9M1mlQbyKJ5A152g==}
+ dev: true
+
+ /is-number/7.0.0:
+ resolution: {integrity: sha512-41Cifkg6e8TylSpdtTpeLVMqvSBEVzTttHvERD741+pnZ8ANv0004MRL43QKPDlK9cGvNp6NZWZUBlbGXYxxng==}
+ engines: {node: '>=0.12.0'}
+ dev: true
+
+ /is-path-cwd/1.0.0:
+ resolution: {integrity: sha512-cnS56eR9SPAscL77ik76ATVqoPARTqPIVkMDVxRaWH06zT+6+CzIroYRJ0VVvm0Z1zfAvxvz9i/D3Ppjaqt5Nw==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /is-path-in-cwd/1.0.1:
+ resolution: {integrity: sha512-FjV1RTW48E7CWM7eE/J2NJvAEEVektecDBVBE5Hh3nM1Jd0kvhHtX68Pr3xsDf857xt3Y4AkwVULK1Vku62aaQ==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ is-path-inside: 1.0.1
+ dev: true
+
+ /is-path-inside/1.0.1:
+ resolution: {integrity: sha512-qhsCR/Esx4U4hg/9I19OVUAJkGWtjRYHMRgUMZE2TDdj+Ag+kttZanLupfddNyglzz50cUlmWzUaI37GDfNx/g==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ path-is-inside: 1.0.2
+ dev: true
+
+ /is-path-inside/3.0.3:
+ resolution: {integrity: sha512-Fd4gABb+ycGAmKou8eMftCupSir5lRxqf4aD/vd0cD2qc4HL07OjCeuHMr8Ro4CoMaeCKDB0/ECBOVWjTwUvPQ==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /is-stream/2.0.1:
+ resolution: {integrity: sha512-hFoiJiTl63nn+kstHGBtewWSKnQLpyb155KHheA1l39uvtO9nWIop1p3udqPcUd/xbF1VLMO4n7OI6p7RbngDg==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /is-typedarray/1.0.0:
+ resolution: {integrity: sha512-cyA56iCMHAh5CdzjJIa4aohJyeO1YbwLi3Jc35MmRU6poroFjIGZzUzupGiRPOjgHg9TLu43xbpwXk523fMxKA==}
+ dev: true
+
+ /is-unicode-supported/0.1.0:
+ resolution: {integrity: sha512-knxG2q4UC3u8stRGyAVJCOdxFmv5DZiRcdlIaAQXAbSfJya+OhopNotLQrstBhququ4ZpuKbDc/8S6mgXgPFPw==}
+ engines: {node: '>=10'}
+ dev: true
+
+ /is-wsl/2.2.0:
+ resolution: {integrity: sha512-fKzAra0rGJUUBwGBgNkHZuToZcn+TtXHpeCgmkMJMMYx1sQDYaCSyjJBSCa2nH1DGm7s3n1oBnohoVTBaN7Lww==}
+ engines: {node: '>=8'}
+ dependencies:
+ is-docker: 2.2.1
+ dev: true
+
+ /isarray/1.0.0:
+ resolution: {integrity: sha512-VLghIWNM6ELQzo7zwmcg0NmTVyWKYjvIeM83yjp0wRDTmUnrM678fQbcKBo6n2CJEF0szoG//ytg+TKla89ALQ==}
+ dev: true
+
+ /isbinaryfile/4.0.10:
+ resolution: {integrity: sha512-iHrqe5shvBUcFbmZq9zOQHBoeOhZJu6RQGrDpBgenUm/Am+F3JM2MgQj+rK3Z601fzrL5gLZWtAPH2OBaSVcyw==}
+ engines: {node: '>= 8.0.0'}
+ dev: true
+
+ /isexe/2.0.0:
+ resolution: {integrity: sha512-RHxMLp9lnKHGHRng9QFhRCMbYAcVpn69smSGcq3f36xjgVVWThj4qqLbTLlq7Ssj8B+fIQ1EuCEGI2lKsyQeIw==}
+ dev: true
+
+ /isstream/0.1.2:
+ resolution: {integrity: sha512-Yljz7ffyPbrLpLngrMtZ7NduUgVvi6wG9RJ9IUcyCd59YQ911PBJphODUcbOVbqYfxe1wuYf/LJ8PauMRwsM/g==}
+ dev: true
+
+ /jasmine-core/2.8.0:
+ resolution: {integrity: sha512-SNkOkS+/jMZvLhuSx1fjhcNWUC/KG6oVyFUGkSBEr9n1axSNduWU8GlI7suaHXr4yxjet6KjrUZxUTE5WzzWwQ==}
+ dev: true
+
+ /jasmine-core/3.10.1:
+ resolution: {integrity: sha512-ooZWSDVAdh79Rrj4/nnfklL3NQVra0BcuhcuWoAwwi+znLDoUeH87AFfeX8s+YeYi6xlv5nveRyaA1v7CintfA==}
+ dev: true
+
+ /jasmine-core/3.99.1:
+ resolution: {integrity: sha512-Hu1dmuoGcZ7AfyynN3LsfruwMbxMALMka+YtZeGoLuDEySVmVAPaonkNoBRIw/ectu8b9tVQCJNgp4a4knp+tg==}
+ dev: true
+
+ /jasmine/2.8.0:
+ resolution: {integrity: sha512-KbdGQTf5jbZgltoHs31XGiChAPumMSY64OZMWLNYnEnMfG5uwGBhffePwuskexjT+/Jea/gU3qAU8344hNohSw==}
+ hasBin: true
+ dependencies:
+ exit: 0.1.2
+ glob: 7.2.3
+ jasmine-core: 2.8.0
+ dev: true
+
+ /jasmine/3.10.0:
+ resolution: {integrity: sha512-2Y42VsC+3CQCTzTwJezOvji4qLORmKIE0kwowWC+934Krn6ZXNQYljiwK5st9V3PVx96BSiDYXSB60VVah3IlQ==}
+ hasBin: true
+ dependencies:
+ glob: 7.2.3
+ jasmine-core: 3.10.1
+ dev: true
+
+ /jasminewd2/2.2.0:
+ resolution: {integrity: sha512-Rn0nZe4rfDhzA63Al3ZGh0E+JTmM6ESZYXJGKuqKGZObsAB9fwXPD03GjtIEvJBDOhN94T5MzbwZSqzFHSQPzg==}
+ engines: {node: '>= 6.9.x'}
+ dev: true
+
+ /js-tokens/4.0.0:
+ resolution: {integrity: sha512-RdJUflcE3cUzKiMqQgsCu06FPu9UdIJO0beYbPhHN4k6apgJtifcoCtT9bcxOpYBtpD2kCM6Sbzg4CausW/PKQ==}
+ dev: true
+
+ /jsbn/0.1.1:
+ resolution: {integrity: sha512-UVU9dibq2JcFWxQPA6KCqj5O42VOmAY3zQUfEKxU0KpTGXwNoCjkX1e13eHNvw/xPynt6pU0rZ1htjWTNTSXsg==}
+ dev: true
+
+ /jsesc/2.5.2:
+ resolution: {integrity: sha512-OYu7XEzjkCQ3C5Ps3QIZsQfNpqoJyZZA99wd9aWd05NCtC5pWOkShK2mkL6HXQR6/Cy2lbNdPlZBpuQHXE63gA==}
+ engines: {node: '>=4'}
+ hasBin: true
+ dev: true
+
+ /json-parse-even-better-errors/3.0.0:
+ resolution: {integrity: sha512-iZbGHafX/59r39gPwVPRBGw0QQKnA7tte5pSMrhWOW7swGsVvVTjmfyAV9pNqk8YGT7tRCdxRu8uzcgZwoDooA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dev: true
+
+ /json-schema-traverse/0.4.1:
+ resolution: {integrity: sha512-xbbCH5dCYU5T8LcEhhuh7HJ88HXuW3qsI3Y0zOZFKfZEHcpWiHU/Jxzk629Brsab/mMiHQti9wMP+845RPe3Vg==}
+ dev: true
+
+ /json-schema-traverse/1.0.0:
+ resolution: {integrity: sha512-NM8/P9n3XjXhIZn1lLhkFaACTOURQXjWhV4BA/RnOv8xvgqtqpAX9IO4mRQxSx1Rlo4tqzeqb0sOlruaOy3dug==}
+ dev: true
+
+ /json-schema/0.4.0:
+ resolution: {integrity: sha512-es94M3nTIfsEPisRafak+HDLfHXnKBhV3vU5eqPcS3flIWqcxJWgXHXiey3YrpaNsanY5ei1VoYEbOzijuq9BA==}
+ dev: true
+
+ /json-stringify-safe/5.0.1:
+ resolution: {integrity: sha512-ZClg6AaYvamvYEE82d3Iyd3vSSIjQ+odgjaTzRuO3s7toCdFKczob2i0zCh7JE8kWn17yvAWhUVxvqGwUalsRA==}
+ dev: true
+
+ /json5/2.2.3:
+ resolution: {integrity: sha512-XmOWe7eyHYH14cLdVPoyg+GOH3rYX++KpzrylJwSW98t3Nk+U8XOl8FWKOgwtzdb8lXGf6zYwDUzeHMWfxasyg==}
+ engines: {node: '>=6'}
+ hasBin: true
+ dev: true
+
+ /jsonc-parser/3.2.0:
+ resolution: {integrity: sha512-gfFQZrcTc8CnKXp6Y4/CBT3fTc0OVuDofpre4aEeEpSBPV5X5v4+Vmx+8snU7RLPrNHPKSgLxGo9YuQzz20o+w==}
+ dev: true
+
+ /jsonfile/4.0.0:
+ resolution: {integrity: sha512-m6F1R3z8jjlf2imQHS2Qez5sjKWQzbuuhuJ/FKYFRZvPE3PuHcSMVZzfsLhGVOkfd20obL5SWEBew5ShlquNxg==}
+ optionalDependencies:
+ graceful-fs: 4.2.10
+ dev: true
+
+ /jsonfile/6.1.0:
+ resolution: {integrity: sha512-5dgndWOriYSm5cnYaJNhalLNDKOqFwyDB/rr1E9ZsGciGvKPs8R2xYGCacuf3z6K1YKDz182fd+fY3cn3pMqXQ==}
+ dependencies:
+ universalify: 2.0.0
+ optionalDependencies:
+ graceful-fs: 4.2.10
+ dev: true
+
+ /jsonparse/1.3.1:
+ resolution: {integrity: sha512-POQXvpdL69+CluYsillJ7SUhKvytYjW9vG/GKpnf+xP8UWgYEM/RaMzHHofbALDiKbbP1W8UEYmgGl39WkPZsg==}
+ engines: {'0': node >= 0.2.0}
+ dev: true
+
+ /jsprim/1.4.2:
+ resolution: {integrity: sha512-P2bSOMAc/ciLz6DzgjVlGJP9+BrJWu5UDGK70C2iweC5QBIeFf0ZXRvGjEj2uYgrY2MkAAhsSWHDWlFtEroZWw==}
+ engines: {node: '>=0.6.0'}
+ dependencies:
+ assert-plus: 1.0.0
+ extsprintf: 1.3.0
+ json-schema: 0.4.0
+ verror: 1.10.0
+ dev: true
+
+ /jsprim/2.0.2:
+ resolution: {integrity: sha512-gqXddjPqQ6G40VdnI6T6yObEC+pDNvyP95wdQhkWkg7crHH3km5qP1FsOXEkzEQwnz6gz5qGTn1c2Y52wP3OyQ==}
+ engines: {'0': node >=0.6.0}
+ dependencies:
+ assert-plus: 1.0.0
+ extsprintf: 1.3.0
+ json-schema: 0.4.0
+ verror: 1.10.0
+ dev: true
+
+ /jszip/3.10.1:
+ resolution: {integrity: sha512-xXDvecyTpGLrqFrvkrUSoxxfJI5AH7U8zxxtVclpsUtMCq4JQ290LY8AW5c7Ggnr/Y/oK+bQMbqK2qmtk3pN4g==}
+ dependencies:
+ lie: 3.3.0
+ pako: 1.0.11
+ readable-stream: 2.3.7
+ setimmediate: 1.0.5
+ dev: true
+
+ /karma-chrome-launcher/3.1.0:
+ resolution: {integrity: sha512-3dPs/n7vgz1rxxtynpzZTvb9y/GIaW8xjAwcIGttLbycqoFtI7yo1NGnQi6oFTherRE+GIhCAHZC4vEqWGhNvg==}
+ dependencies:
+ which: 1.3.1
+ dev: true
+
+ /karma-firefox-launcher/2.1.2:
+ resolution: {integrity: sha512-VV9xDQU1QIboTrjtGVD4NCfzIH7n01ZXqy/qpBhnOeGVOkG5JYPEm8kuSd7psHE6WouZaQ9Ool92g8LFweSNMA==}
+ dependencies:
+ is-wsl: 2.2.0
+ which: 2.0.2
+ dev: true
+
+ /karma-jasmine/4.0.1_karma@6.4.1:
+ resolution: {integrity: sha512-h8XDAhTiZjJKzfkoO1laMH+zfNlra+dEQHUAjpn5JV1zCPtOIVWGQjLBrqhnzQa/hrU2XrZwSyBa6XjEBzfXzw==}
+ engines: {node: '>= 10'}
+ peerDependencies:
+ karma: '*'
+ dependencies:
+ jasmine-core: 3.99.1
+ karma: 6.4.1
+ dev: true
+
+ /karma-requirejs/1.1.0_rexopxsgq4andhwzqrad3qy2ka:
+ resolution: {integrity: sha512-MHTOYKdwwJBkvYid0TaYvBzOnFH3TDtzo6ie5E4o9SaUSXXsfMRLa/whUz6efVIgTxj1xnKYasNn/XwEgJeB/Q==}
+ peerDependencies:
+ karma: '>=0.9'
+ requirejs: ^2.1.0
+ dependencies:
+ karma: 6.4.1
+ requirejs: 2.3.6
+ dev: true
+
+ /karma-sourcemap-loader/0.3.8:
+ resolution: {integrity: sha512-zorxyAakYZuBcHRJE+vbrK2o2JXLFWK8VVjiT/6P+ltLBUGUvqTEkUiQ119MGdOrK7mrmxXHZF1/pfT6GgIZ6g==}
+ dependencies:
+ graceful-fs: 4.2.10
+ dev: true
+
+ /karma/6.4.1:
+ resolution: {integrity: sha512-Cj57NKOskK7wtFWSlMvZf459iX+kpYIPXmkNUzP2WAFcA7nhr/ALn5R7sw3w+1udFDcpMx/tuB8d5amgm3ijaA==}
+ engines: {node: '>= 10'}
+ hasBin: true
+ dependencies:
+ '@colors/colors': 1.5.0
+ body-parser: 1.20.1
+ braces: 3.0.2
+ chokidar: 3.5.3
+ connect: 3.7.0
+ di: 0.0.1
+ dom-serialize: 2.2.1
+ glob: 7.2.3
+ graceful-fs: 4.2.10
+ http-proxy: 1.18.1
+ isbinaryfile: 4.0.10
+ lodash: 4.17.21
+ log4js: 6.7.1
+ mime: 2.6.0
+ minimatch: 3.1.2
+ mkdirp: 0.5.6
+ qjobs: 1.2.0
+ range-parser: 1.2.1
+ rimraf: 3.0.2
+ socket.io: 4.5.4
+ source-map: 0.6.1
+ tmp: 0.2.1
+ ua-parser-js: 0.7.32
+ yargs: 16.2.0
+ transitivePeerDependencies:
+ - bufferutil
+ - debug
+ - supports-color
+ - utf-8-validate
+ dev: true
+
+ /lazy-ass/1.6.0:
+ resolution: {integrity: sha512-cc8oEVoctTvsFZ/Oje/kGnHbpWHYBe8IAJe4C0QNc3t8uM/0Y8+erSz/7Y1ALuXTEZTMvxXwO6YbX1ey3ujiZw==}
+ engines: {node: '> 0.8'}
+ dev: true
+
+ /lie/3.3.0:
+ resolution: {integrity: sha512-UaiMJzeWRlEujzAuw5LokY1L5ecNQYZKfmyZ9L7wDHb/p5etKaxXhohBcrw0EYby+G/NA52vRSN4N39dxHAIwQ==}
+ dependencies:
+ immediate: 3.0.6
+ dev: true
+
+ /listr2/3.14.0_enquirer@2.3.6:
+ resolution: {integrity: sha512-TyWI8G99GX9GjE54cJ+RrNMcIFBfwMPxc3XTFiAYGN4s10hWROGtOg7+O6u6LE3mNkyld7RSLE6nrKBvTfcs3g==}
+ engines: {node: '>=10.0.0'}
+ peerDependencies:
+ enquirer: '>= 2.3.0 < 3'
+ peerDependenciesMeta:
+ enquirer:
+ optional: true
+ dependencies:
+ cli-truncate: 2.1.0
+ colorette: 2.0.19
+ enquirer: 2.3.6
+ log-update: 4.0.0
+ p-map: 4.0.0
+ rfdc: 1.3.0
+ rxjs: 7.5.7
+ through: 2.3.8
+ wrap-ansi: 7.0.0
+ dev: true
+
+ /locate-path/5.0.0:
+ resolution: {integrity: sha512-t7hw9pI+WvuwNJXwk5zVHpyhIqzg2qTlklJOf0mVxGSbe3Fp2VieZcduNYjaLDoy6p9uGpQEGWG87WpMKlNq8g==}
+ engines: {node: '>=8'}
+ dependencies:
+ p-locate: 4.1.0
+ dev: true
+
+ /lodash.once/4.1.1:
+ resolution: {integrity: sha512-Sb487aTOCr9drQVL8pIxOzVhafOjZN9UU54hiN8PU3uAiSV7lx1yYNpbNmex2PK6dSJoNTSJUUswT651yww3Mg==}
+ dev: true
+
+ /lodash/4.17.21:
+ resolution: {integrity: sha512-v2kDEe57lecTulaDIuNTPy3Ry4gLGJ6Z1O3vE1krgXZNrsQ+LFTGHVxVjcXPs17LhbZVGedAJv8XZ1tvj5FvSg==}
+ dev: true
+
+ /log-symbols/4.1.0:
+ resolution: {integrity: sha512-8XPvpAA8uyhfteu8pIvQxpJZ7SYYdpUivZpGy6sFsBuKRY/7rQGavedeB8aK+Zkyq6upMFVL/9AW6vOYzfRyLg==}
+ engines: {node: '>=10'}
+ dependencies:
+ chalk: 4.1.2
+ is-unicode-supported: 0.1.0
+ dev: true
+
+ /log-update/4.0.0:
+ resolution: {integrity: sha512-9fkkDevMefjg0mmzWFBW8YkFP91OrizzkW3diF7CpG+S2EYdy4+TVfGwz1zeF8x7hCx1ovSPTOE9Ngib74qqUg==}
+ engines: {node: '>=10'}
+ dependencies:
+ ansi-escapes: 4.3.2
+ cli-cursor: 3.1.0
+ slice-ansi: 4.0.0
+ wrap-ansi: 6.2.0
+ dev: true
+
+ /log4js/6.7.1:
+ resolution: {integrity: sha512-lzbd0Eq1HRdWM2abSD7mk6YIVY0AogGJzb/z+lqzRk+8+XJP+M6L1MS5FUSc3jjGru4dbKjEMJmqlsoYYpuivQ==}
+ engines: {node: '>=8.0'}
+ dependencies:
+ date-format: 4.0.14
+ debug: 4.3.4
+ flatted: 3.2.7
+ rfdc: 1.3.0
+ streamroller: 3.1.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /lru-cache/5.1.1:
+ resolution: {integrity: sha512-KpNARQA3Iwv+jTA0utUVVbrh+Jlrr1Fv0e56GGzAFOXN7dk/FviaDW8LHmK52DlcH4WP2n6gI8vN1aesBFgo9w==}
+ dependencies:
+ yallist: 3.1.1
+ dev: true
+
+ /lru-cache/6.0.0:
+ resolution: {integrity: sha512-Jo6dJ04CmSjuznwJSS3pUeWmd/H0ffTlkXXgwZi+eq1UCmqQwCh+eLsYOYCwY991i2Fah4h1BEMCx4qThGbsiA==}
+ engines: {node: '>=10'}
+ dependencies:
+ yallist: 4.0.0
+ dev: true
+
+ /lru-cache/7.14.1:
+ resolution: {integrity: sha512-ysxwsnTKdAx96aTRdhDOCQfDgbHnt8SK0KY8SEjO0wHinhWOFTESbjVCMPbU1uGXg/ch4lifqx0wfjOawU2+WA==}
+ engines: {node: '>=12'}
+ dev: true
+
+ /magic-string/0.26.7:
+ resolution: {integrity: sha512-hX9XH3ziStPoPhJxLq1syWuZMxbDvGNbVchfrdCtanC7D13888bMFow61x8axrx+GfHLtVeAx2kxL7tTGRl+Ow==}
+ engines: {node: '>=12'}
+ dependencies:
+ sourcemap-codec: 1.4.8
+ dev: true
+
+ /make-dir/2.1.0:
+ resolution: {integrity: sha512-LS9X+dc8KLxXCb8dni79fLIIUA5VyZoyjSMCwTluaXA0o27cCK0bhXkpgw+sTXVpPy/lSO57ilRixqk0vDmtRA==}
+ engines: {node: '>=6'}
+ dependencies:
+ pify: 4.0.1
+ semver: 5.7.1
+ dev: true
+
+ /make-fetch-happen/10.2.1:
+ resolution: {integrity: sha512-NgOPbRiaQM10DYXvN3/hhGVI2M5MtITFryzBGxHM5p4wnFxsVCbxkrBrDsk+EZ5OB4jEOT7AjDxtdF+KVEFT7w==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ agentkeepalive: 4.2.1
+ cacache: 16.1.3
+ http-cache-semantics: 4.1.0
+ http-proxy-agent: 5.0.0
+ https-proxy-agent: 5.0.1
+ is-lambda: 1.0.1
+ lru-cache: 7.14.1
+ minipass: 3.3.6
+ minipass-collect: 1.0.2
+ minipass-fetch: 2.1.2
+ minipass-flush: 1.0.5
+ minipass-pipeline: 1.2.4
+ negotiator: 0.6.3
+ promise-retry: 2.0.1
+ socks-proxy-agent: 7.0.0
+ ssri: 9.0.1
+ transitivePeerDependencies:
+ - bluebird
+ - supports-color
+ dev: true
+
+ /make-fetch-happen/11.0.2:
+ resolution: {integrity: sha512-5n/Pq41w/uZghpdlXAY5kIM85RgJThtTH/NYBRAZ9VUOBWV90USaQjwGrw76fZP3Lj5hl/VZjpVvOaRBMoL/2w==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ agentkeepalive: 4.2.1
+ cacache: 17.0.4
+ http-cache-semantics: 4.1.0
+ http-proxy-agent: 5.0.0
+ https-proxy-agent: 5.0.1
+ is-lambda: 1.0.1
+ lru-cache: 7.14.1
+ minipass: 4.0.0
+ minipass-collect: 1.0.2
+ minipass-fetch: 3.0.1
+ minipass-flush: 1.0.5
+ minipass-pipeline: 1.2.4
+ negotiator: 0.6.3
+ promise-retry: 2.0.1
+ socks-proxy-agent: 7.0.0
+ ssri: 10.0.1
+ transitivePeerDependencies:
+ - bluebird
+ - supports-color
+ dev: true
+
+ /media-typer/0.3.0:
+ resolution: {integrity: sha512-dq+qelQ9akHpcOl/gUVRTxVIOkAJ1wR3QAvb4RsVjS8oVoFjDGTc679wJYmUmknUF5HwMLOgb5O+a3KxfWapPQ==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /merge-stream/2.0.0:
+ resolution: {integrity: sha512-abv/qOcuPfk3URPfDzmZU1LKmuw8kT+0nIHvKrKgFrwifol/doWcdA4ZqsWQ8ENrFKkd67Mfpo/LovbIUsbt3w==}
+ dev: true
+
+ /mime-db/1.52.0:
+ resolution: {integrity: sha512-sPU4uV7dYlvtWJxwwxHD0PuihVNiE7TyAbQ5SWxDCB9mUYvOgroQOwYQQOKPJ8CIbE+1ETVlOoK1UC2nU3gYvg==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /mime-types/2.1.35:
+ resolution: {integrity: sha512-ZDY+bPm5zTTF+YpCrAU9nK0UgICYPT0QtT1NZWFv4s++TNkcgVaT0g6+4R2uI4MjQjzysHB1zxuWL50hzaeXiw==}
+ engines: {node: '>= 0.6'}
+ dependencies:
+ mime-db: 1.52.0
+ dev: true
+
+ /mime/2.6.0:
+ resolution: {integrity: sha512-USPkMeET31rOMiarsBNIHZKLGgvKc/LrjofAnBlOttf5ajRvqiRA8QsenbcooctK6d6Ts6aqZXBA+XbkKthiQg==}
+ engines: {node: '>=4.0.0'}
+ hasBin: true
+ dev: true
+
+ /mimic-fn/2.1.0:
+ resolution: {integrity: sha512-OqbOk5oEQeAZ8WXWydlu9HJjz9WVdEIvamMCcXmuqUYjTknH/sqsWvhQ3vgwKFRR1HpjvNBKQ37nbJgYzGqGcg==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /minimatch/3.1.2:
+ resolution: {integrity: sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==}
+ dependencies:
+ brace-expansion: 1.1.11
+ dev: true
+
+ /minimatch/5.1.4:
+ resolution: {integrity: sha512-U0iNYXt9wALljzfnGkhFSy5sAC6/SCR3JrHrlsdJz4kF8MvhTRQNiC59iUi1iqsitV7abrNAJWElVL9pdnoUgw==}
+ engines: {node: '>=10'}
+ dependencies:
+ brace-expansion: 2.0.1
+ dev: true
+
+ /minimist/1.2.7:
+ resolution: {integrity: sha512-bzfL1YUZsP41gmu/qjrEk0Q6i2ix/cVeAhbCbqH9u3zYutS1cLg00qhrD0M2MVdCcx4Sc0UpP2eBWo9rotpq6g==}
+ dev: true
+
+ /minipass-collect/1.0.2:
+ resolution: {integrity: sha512-6T6lH0H8OG9kITm/Jm6tdooIbogG9e0tLgpY6mphXSm/A9u8Nq1ryBG+Qspiub9LjWlBPsPS3tWQ/Botq4FdxA==}
+ engines: {node: '>= 8'}
+ dependencies:
+ minipass: 3.3.6
+ dev: true
+
+ /minipass-fetch/2.1.2:
+ resolution: {integrity: sha512-LT49Zi2/WMROHYoqGgdlQIZh8mLPZmOrN2NdJjMXxYe4nkN6FUyuPuOAOedNJDrx0IRGg9+4guZewtp8hE6TxA==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ minipass: 3.3.6
+ minipass-sized: 1.0.3
+ minizlib: 2.1.2
+ optionalDependencies:
+ encoding: 0.1.13
+ dev: true
+
+ /minipass-fetch/3.0.1:
+ resolution: {integrity: sha512-t9/wowtf7DYkwz8cfMSt0rMwiyNIBXf5CKZ3S5ZMqRqMYT0oLTp0x1WorMI9WTwvaPg21r1JbFxJMum8JrLGfw==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ minipass: 4.0.0
+ minipass-sized: 1.0.3
+ minizlib: 2.1.2
+ optionalDependencies:
+ encoding: 0.1.13
+ dev: true
+
+ /minipass-flush/1.0.5:
+ resolution: {integrity: sha512-JmQSYYpPUqX5Jyn1mXaRwOda1uQ8HP5KAT/oDSLCzt1BYRhQU0/hDtsB1ufZfEEzMZ9aAVmsBw8+FWsIXlClWw==}
+ engines: {node: '>= 8'}
+ dependencies:
+ minipass: 3.3.6
+ dev: true
+
+ /minipass-json-stream/1.0.1:
+ resolution: {integrity: sha512-ODqY18UZt/I8k+b7rl2AENgbWE8IDYam+undIJONvigAz8KR5GWblsFTEfQs0WODsjbSXWlm+JHEv8Gr6Tfdbg==}
+ dependencies:
+ jsonparse: 1.3.1
+ minipass: 3.3.6
+ dev: true
+
+ /minipass-pipeline/1.2.4:
+ resolution: {integrity: sha512-xuIq7cIOt09RPRJ19gdi4b+RiNvDFYe5JH+ggNvBqGqpQXcru3PcRmOZuHBKWK1Txf9+cQ+HMVN4d6z46LZP7A==}
+ engines: {node: '>=8'}
+ dependencies:
+ minipass: 3.3.6
+ dev: true
+
+ /minipass-sized/1.0.3:
+ resolution: {integrity: sha512-MbkQQ2CTiBMlA2Dm/5cY+9SWFEN8pzzOXi6rlM5Xxq0Yqbda5ZQy9sU75a673FE9ZK0Zsbr6Y5iP6u9nktfg2g==}
+ engines: {node: '>=8'}
+ dependencies:
+ minipass: 3.3.6
+ dev: true
+
+ /minipass/3.3.6:
+ resolution: {integrity: sha512-DxiNidxSEK+tHG6zOIklvNOwm3hvCrbUrdtzY74U6HKTJxvIDfOUL5W5P2Ghd3DTkhhKPYGqeNUIh5qcM4YBfw==}
+ engines: {node: '>=8'}
+ dependencies:
+ yallist: 4.0.0
+ dev: true
+
+ /minipass/4.0.0:
+ resolution: {integrity: sha512-g2Uuh2jEKoht+zvO6vJqXmYpflPqzRBT+Th2h01DKh5z7wbY/AZ2gCQ78cP70YoHPyFdY30YBV5WxgLOEwOykw==}
+ engines: {node: '>=8'}
+ dependencies:
+ yallist: 4.0.0
+ dev: true
+
+ /minizlib/2.1.2:
+ resolution: {integrity: sha512-bAxsR8BVfj60DWXHE3u30oHzfl4G7khkSuPW+qvpd7jFRHm7dLxOjUk1EHACJ/hxLY8phGJ0YhYHZo7jil7Qdg==}
+ engines: {node: '>= 8'}
+ dependencies:
+ minipass: 3.3.6
+ yallist: 4.0.0
+ dev: true
+
+ /mkdirp/0.5.6:
+ resolution: {integrity: sha512-FP+p8RB8OWpF3YZBCrP5gtADmtXApB5AMLn+vdyA+PyxCjrCs00mjyUozssO33cwDeT3wNGdLxJ5M//YqtHAJw==}
+ hasBin: true
+ dependencies:
+ minimist: 1.2.7
+ dev: true
+
+ /mkdirp/1.0.4:
+ resolution: {integrity: sha512-vVqVZQyf3WLx2Shd0qJ9xuvqgAyKPLAiqITEtqW0oIUjzo3PePDd6fW9iFz30ef7Ysp/oiWqbhszeGWW2T6Gzw==}
+ engines: {node: '>=10'}
+ hasBin: true
+ dev: true
+
+ /ms/2.0.0:
+ resolution: {integrity: sha512-Tpp60P6IUJDTuOq/5Z8cdskzJujfwqfOTkrwIwj7IRISpnkJnT6SyJ4PCPnGMoFjC9ddhal5KVIYtAt97ix05A==}
+ dev: true
+
+ /ms/2.1.2:
+ resolution: {integrity: sha512-sGkPx+VjMtmA6MX27oA4FBFELFCZZ4S4XqeGOXCv68tT+jb3vk/RyaKWP0PTKyWtmLSM0b+adUTEvbs1PEaH2w==}
+ dev: true
+
+ /ms/2.1.3:
+ resolution: {integrity: sha512-6FlzubTLZG3J2a/NVCAleEhjzq5oxgHyaCU9yYXvcLsvoVaHJq/s5xXI6/XXP6tz7R9xAOtHnSO/tXtF3WRTlA==}
+ dev: true
+
+ /mute-stream/0.0.8:
+ resolution: {integrity: sha512-nnbWWOkoWyUsTjKrhgD0dcz22mdkSnpYqbEjIm2nhwhuxlSkpywJmBo8h0ZqJdkp73mb90SssHkN4rsRaBAfAA==}
+ dev: true
+
+ /negotiator/0.6.3:
+ resolution: {integrity: sha512-+EUsqGPLsM+j/zdChZjsnX51g4XrHFOIXwfnCVPGlQk/k5giakcKsuxCObBRu6DSm9opw/O6slWbJdghQM4bBg==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /node-gyp/9.3.1:
+ resolution: {integrity: sha512-4Q16ZCqq3g8awk6UplT7AuxQ35XN4R/yf/+wSAwcBUAjg7l58RTactWaP8fIDTi0FzI7YcVLujwExakZlfWkXg==}
+ engines: {node: ^12.13 || ^14.13 || >=16}
+ hasBin: true
+ dependencies:
+ env-paths: 2.2.1
+ glob: 7.2.3
+ graceful-fs: 4.2.10
+ make-fetch-happen: 10.2.1
+ nopt: 6.0.0
+ npmlog: 6.0.2
+ rimraf: 3.0.2
+ semver: 7.3.8
+ tar: 6.1.13
+ which: 2.0.2
+ transitivePeerDependencies:
+ - bluebird
+ - supports-color
+ dev: true
+
+ /node-releases/2.0.8:
+ resolution: {integrity: sha512-dFSmB8fFHEH/s81Xi+Y/15DQY6VHW81nXRj86EMSL3lmuTmK1e+aT4wrFCkTbm+gSwkw4KpX+rT/pMM2c1mF+A==}
+ dev: true
+
+ /nopt/6.0.0:
+ resolution: {integrity: sha512-ZwLpbTgdhuZUnZzjd7nb1ZV+4DoiC6/sfiVKok72ym/4Tlf+DFdlHYmT2JPmcNNWV6Pi3SDf1kT+A4r9RTuT9g==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ hasBin: true
+ dependencies:
+ abbrev: 1.1.1
+ dev: true
+
+ /normalize-package-data/5.0.0:
+ resolution: {integrity: sha512-h9iPVIfrVZ9wVYQnxFgtw1ugSvGEMOlyPWWtm8BMJhnwyEL/FLbYbTY3V3PpjI/BUK67n9PEWDu6eHzu1fB15Q==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ hosted-git-info: 6.1.1
+ is-core-module: 2.11.0
+ semver: 7.3.8
+ validate-npm-package-license: 3.0.4
+ dev: true
+
+ /normalize-path/3.0.0:
+ resolution: {integrity: sha512-6eZs5Ls3WtCisHWp9S2GUy8dqkpGi4BVSz3GaqiE6ezub0512ESztXUwUB6C6IKbQkY2Pnb/mD4WYojCRwcwLA==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /npm-bundled/3.0.0:
+ resolution: {integrity: sha512-Vq0eyEQy+elFpzsKjMss9kxqb9tG3YHg4dsyWuUENuzvSUWe1TCnW/vV9FkhvBk/brEDoDiVd+M1Btosa6ImdQ==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ npm-normalize-package-bin: 3.0.0
+ dev: true
+
+ /npm-install-checks/6.0.0:
+ resolution: {integrity: sha512-SBU9oFglRVZnfElwAtF14NivyulDqF1VKqqwNsFW9HDcbHMAPHpRSsVFgKuwFGq/hVvWZExz62Th0kvxn/XE7Q==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ semver: 7.3.8
+ dev: true
+
+ /npm-normalize-package-bin/3.0.0:
+ resolution: {integrity: sha512-g+DPQSkusnk7HYXr75NtzkIP4+N81i3RPsGFidF3DzHd9MT9wWngmqoeg/fnHFz5MNdtG4w03s+QnhewSLTT2Q==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dev: true
+
+ /npm-package-arg/10.1.0:
+ resolution: {integrity: sha512-uFyyCEmgBfZTtrKk/5xDfHp6+MdrqGotX/VoOyEEl3mBwiEE5FlBaePanazJSVMPT7vKepcjYBY2ztg9A3yPIA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ hosted-git-info: 6.1.1
+ proc-log: 3.0.0
+ semver: 7.3.8
+ validate-npm-package-name: 5.0.0
+ dev: true
+
+ /npm-package-arg/9.1.2:
+ resolution: {integrity: sha512-pzd9rLEx4TfNJkovvlBSLGhq31gGu2QDexFPWT19yCDh0JgnRhlBLNo5759N0AJmBk+kQ9Y/hXoLnlgFD+ukmg==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ hosted-git-info: 5.2.1
+ proc-log: 2.0.1
+ semver: 7.3.8
+ validate-npm-package-name: 4.0.0
+ dev: true
+
+ /npm-packlist/7.0.4:
+ resolution: {integrity: sha512-d6RGEuRrNS5/N84iglPivjaJPxhDbZmlbTwTDX2IbcRHG5bZCdtysYMhwiPvcF4GisXHGn7xsxv+GQ7T/02M5Q==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ ignore-walk: 6.0.0
+ dev: true
+
+ /npm-pick-manifest/8.0.1:
+ resolution: {integrity: sha512-mRtvlBjTsJvfCCdmPtiu2bdlx8d/KXtF7yNXNWe7G0Z36qWA9Ny5zXsI2PfBZEv7SXgoxTmNaTzGSbbzDZChoA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ npm-install-checks: 6.0.0
+ npm-normalize-package-bin: 3.0.0
+ npm-package-arg: 10.1.0
+ semver: 7.3.8
+ dev: true
+
+ /npm-registry-fetch/14.0.3:
+ resolution: {integrity: sha512-YaeRbVNpnWvsGOjX2wk5s85XJ7l1qQBGAp724h8e2CZFFhMSuw9enom7K1mWVUtvXO1uUSFIAPofQK0pPN0ZcA==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ make-fetch-happen: 11.0.2
+ minipass: 4.0.0
+ minipass-fetch: 3.0.1
+ minipass-json-stream: 1.0.1
+ minizlib: 2.1.2
+ npm-package-arg: 10.1.0
+ proc-log: 3.0.0
+ transitivePeerDependencies:
+ - bluebird
+ - supports-color
+ dev: true
+
+ /npm-run-path/4.0.1:
+ resolution: {integrity: sha512-S48WzZW777zhNIrn7gxOlISNAqi9ZC/uQFnRdbeIHhZhCA6UqpkOT8T1G7BvfdgP4Er8gF4sUbaS0i7QvIfCWw==}
+ engines: {node: '>=8'}
+ dependencies:
+ path-key: 3.1.1
+ dev: true
+
+ /npmlog/6.0.2:
+ resolution: {integrity: sha512-/vBvz5Jfr9dT/aFWd0FIRf+T/Q2WBsLENygUaFUqstqsycmZAP/t5BvFJTK0viFmSUxiUKTUplWy5vt+rvKIxg==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ are-we-there-yet: 3.0.1
+ console-control-strings: 1.1.0
+ gauge: 4.0.4
+ set-blocking: 2.0.0
+ dev: true
+
+ /oauth-sign/0.9.0:
+ resolution: {integrity: sha512-fexhUFFPTGV8ybAtSIGbV6gOkSv8UtRbDBnAyLQw4QPKkgNlsH2ByPGtMUqdWkos6YCRmAqViwgZrJc/mRDzZQ==}
+ dev: true
+
+ /object-assign/4.1.1:
+ resolution: {integrity: sha512-rJgTQnkUnH1sFw8yT6VSU3zD3sWmu6sZhIseY8VX+GRu3P6F7Fu+JNDoXfklElbLJSnc3FUQHVe4cU5hj+BcUg==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /object-inspect/1.12.3:
+ resolution: {integrity: sha512-geUvdk7c+eizMNUDkRpW1wJwgfOiOeHbxBR/hLXK1aT6zmVSO0jsQcs7fj6MGw89jC/cjGfLcNOrtMYtGqm81g==}
+ dev: true
+
+ /on-finished/2.3.0:
+ resolution: {integrity: sha512-ikqdkGAAyf/X/gPhXGvfgAytDZtDbr+bkNUJ0N9h5MI/dmdgCs3l6hoHrcUv41sRKew3jIwrp4qQDXiK99Utww==}
+ engines: {node: '>= 0.8'}
+ dependencies:
+ ee-first: 1.1.1
+ dev: true
+
+ /on-finished/2.4.1:
+ resolution: {integrity: sha512-oVlzkg3ENAhCk2zdv7IJwd/QUD4z2RxRwpkcGY8psCVcCYZNq4wYnVWALHM+brtuJjePWiYF/ClmuDr8Ch5+kg==}
+ engines: {node: '>= 0.8'}
+ dependencies:
+ ee-first: 1.1.1
+ dev: true
+
+ /once/1.4.0:
+ resolution: {integrity: sha512-lNaJgI+2Q5URQBkccEKHTQOPaXdUxnZZElQTZY0MFUAuaEqe1E+Nyvgdz/aIyNi6Z9MzO5dv1H8n58/GELp3+w==}
+ dependencies:
+ wrappy: 1.0.2
+ dev: true
+
+ /onetime/5.1.2:
+ resolution: {integrity: sha512-kbpaSSGJTWdAY5KPVeMOKXSrPtr8C8C7wodJbcsd51jRnmD+GZu8Y0VoU6Dm5Z4vWr0Ig/1NKuWRKf7j5aaYSg==}
+ engines: {node: '>=6'}
+ dependencies:
+ mimic-fn: 2.1.0
+ dev: true
+
+ /open/8.4.0:
+ resolution: {integrity: sha512-XgFPPM+B28FtCCgSb9I+s9szOC1vZRSwgWsRUA5ylIxRTgKozqjOCrVOqGsYABPYK5qnfqClxZTFBa8PKt2v6Q==}
+ engines: {node: '>=12'}
+ dependencies:
+ define-lazy-prop: 2.0.0
+ is-docker: 2.2.1
+ is-wsl: 2.2.0
+ dev: true
+
+ /ora/5.4.1:
+ resolution: {integrity: sha512-5b6Y85tPxZZ7QytO+BQzysW31HJku27cRIlkbAXaNx+BdcVi+LlRFmVXzeF6a7JCwJpyw5c4b+YSVImQIrBpuQ==}
+ engines: {node: '>=10'}
+ dependencies:
+ bl: 4.1.0
+ chalk: 4.1.2
+ cli-cursor: 3.1.0
+ cli-spinners: 2.7.0
+ is-interactive: 1.0.0
+ is-unicode-supported: 0.1.0
+ log-symbols: 4.1.0
+ strip-ansi: 6.0.1
+ wcwidth: 1.0.1
+ dev: true
+
+ /os-tmpdir/1.0.2:
+ resolution: {integrity: sha512-D2FR03Vir7FIu45XBY20mTb+/ZSWB00sjU9jdQXt83gDrI4Ztz5Fs7/yy74g2N5SVQY4xY1qDr4rNddwYRVX0g==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /ospath/1.2.2:
+ resolution: {integrity: sha512-o6E5qJV5zkAbIDNhGSIlyOhScKXgQrSRMilfph0clDfM0nEnBOlKlH4sWDmG95BW/CvwNz0vmm7dJVtU2KlMiA==}
+ dev: true
+
+ /p-limit/2.3.0:
+ resolution: {integrity: sha512-//88mFWSJx8lxCzwdAABTJL2MyWB12+eIY7MDL2SqLmAkeKU9qxRvWuSyTjm3FUmpBEMuFfckAIqEaVGUDxb6w==}
+ engines: {node: '>=6'}
+ dependencies:
+ p-try: 2.2.0
+ dev: true
+
+ /p-locate/4.1.0:
+ resolution: {integrity: sha512-R79ZZ/0wAxKGu3oYMlz8jy/kbhsNrS7SKZ7PxEHBgJ5+F2mtFW2fK2cOtBh1cHYkQsbzFV7I+EoRKe6Yt0oK7A==}
+ engines: {node: '>=8'}
+ dependencies:
+ p-limit: 2.3.0
+ dev: true
+
+ /p-map/4.0.0:
+ resolution: {integrity: sha512-/bjOqmgETBYB5BoEeGVea8dmvHb2m9GLy1E9W43yeyfP6QQCZGFNa+XRceJEuDB6zqr+gKpIAmlLebMpykw/MQ==}
+ engines: {node: '>=10'}
+ dependencies:
+ aggregate-error: 3.1.0
+ dev: true
+
+ /p-try/2.2.0:
+ resolution: {integrity: sha512-R4nPAVTAU0B9D35/Gk3uJf/7XYbQcyohSKdvAxIRSNghFl4e71hVoGnBNQz9cWaXxO2I10KTC+3jMdvvoKw6dQ==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /pacote/15.0.6:
+ resolution: {integrity: sha512-dQwcz/sME7QIL+cdrw/jftQfMMXxSo17i2kJ/gnhBhUvvBAsxoBu1lw9B5IzCH/Ce8CvEkG/QYZ6txzKfn0bTw==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ hasBin: true
+ dependencies:
+ '@npmcli/git': 4.0.3
+ '@npmcli/installed-package-contents': 2.0.1
+ '@npmcli/promise-spawn': 6.0.2
+ '@npmcli/run-script': 6.0.0
+ cacache: 17.0.4
+ fs-minipass: 2.1.0
+ minipass: 3.3.6
+ npm-package-arg: 10.1.0
+ npm-packlist: 7.0.4
+ npm-pick-manifest: 8.0.1
+ npm-registry-fetch: 14.0.3
+ proc-log: 3.0.0
+ promise-retry: 2.0.1
+ read-package-json: 6.0.0
+ read-package-json-fast: 3.0.2
+ ssri: 10.0.1
+ tar: 6.1.13
+ transitivePeerDependencies:
+ - bluebird
+ - supports-color
+ dev: true
+
+ /pako/1.0.11:
+ resolution: {integrity: sha512-4hLB8Py4zZce5s4yd9XzopqwVv/yGNhV1Bl8NTmCq1763HeK2+EwVTv+leGeL13Dnh2wfbqowVPXCIO0z4taYw==}
+ dev: true
+
+ /parse5/6.0.1:
+ resolution: {integrity: sha512-Ofn/CTFzRGTTxwpNEs9PP93gXShHcTq255nzRYSKe8AkVpZY7e1fpmTfOyoIvjP5HG7Z2ZM7VS9PPhQGW2pOpw==}
+ dev: true
+
+ /parseurl/1.3.3:
+ resolution: {integrity: sha512-CiyeOxFT/JZyN5m0z9PfXw4SCBJ6Sygz1Dpl0wqjlhDEGGBP1GnsUVEL0p63hoG1fcj3fHynXi9NYO4nWOL+qQ==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /path-exists/4.0.0:
+ resolution: {integrity: sha512-ak9Qy5Q7jYb2Wwcey5Fpvg2KoAc/ZIhLSLOSBmRmygPsGwkVVt0fZa0qrtMz+m6tJTAHfZQ8FnmB4MG4LWy7/w==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /path-is-absolute/1.0.1:
+ resolution: {integrity: sha512-AVbw3UJ2e9bq64vSaS9Am0fje1Pa8pbGqTTsmXfaIiMpnr5DlDhfJOuLj9Sf95ZPVDAUerDfEk88MPmPe7UCQg==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /path-is-inside/1.0.2:
+ resolution: {integrity: sha512-DUWJr3+ULp4zXmol/SZkFf3JGsS9/SIv+Y3Rt93/UjPpDpklB5f1er4O3POIbUuUJ3FXgqte2Q7SrU6zAqwk8w==}
+ dev: true
+
+ /path-key/3.1.1:
+ resolution: {integrity: sha512-ojmeN0qd+y0jszEtoY48r0Peq5dwMEkIlCOu6Q5f41lfkswXuKtYrhgoTpLnyIcHm24Uhqx+5Tqm2InSwLhE6Q==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /path-parse/1.0.7:
+ resolution: {integrity: sha512-LDJzPVEEEPR+y48z93A0Ed0yXb8pAByGWo/k5YYdYgpY2/2EsOsksJrq7lOHxryrVOn1ejG6oAp8ahvOIQD8sw==}
+ dev: true
+
+ /pend/1.2.0:
+ resolution: {integrity: sha512-F3asv42UuXchdzt+xXqfW1OGlVBe+mxa2mqI0pg5yAHZPvFmY3Y6drSf/GQ1A86WgWEN9Kzh/WrgKa6iGcHXLg==}
+ dev: true
+
+ /performance-now/2.1.0:
+ resolution: {integrity: sha512-7EAHlyLHI56VEIdK57uwHdHKIaAGbnXPiw0yWbarQZOKaKpvUIgW0jWRVLiatnM+XXlSwsanIBH/hzGMJulMow==}
+ dev: true
+
+ /picocolors/1.0.0:
+ resolution: {integrity: sha512-1fygroTLlHu66zi26VoTDv8yRgm0Fccecssto+MhsZ0D/DGW2sm8E8AjW7NU5VVTRt5GxbeZ5qBuJr+HyLYkjQ==}
+ dev: true
+
+ /picomatch/2.3.1:
+ resolution: {integrity: sha512-JU3teHTNjmE2VCGFzuY8EXzCDVwEqB2a8fsIvwaStHhAWJEeVd1o1QD80CU6+ZdEXXSLbSsuLwJjkCBWqRQUVA==}
+ engines: {node: '>=8.6'}
+ dev: true
+
+ /pify/2.3.0:
+ resolution: {integrity: sha512-udgsAY+fTnvv7kI7aaxbqwWNb0AHiB0qBO89PZKPkoTmGOgdbrHDKD+0B2X4uTfJ/FT1R09r9gTsjUjNJotuog==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /pify/4.0.1:
+ resolution: {integrity: sha512-uB80kBFb/tfd68bVleG9T5GGsGPjJrLAUpR5PZIrhBnIaRTQRjqdJSsIKkOP6OAIFbj7GOrcudc5pNjZ+geV2g==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /pinkie-promise/2.0.1:
+ resolution: {integrity: sha512-0Gni6D4UcLTbv9c57DfxDGdr41XfgUjqWZu492f0cIGr16zDU06BWP/RAEvOuo7CQ0CNjHaLlM59YJJFm3NWlw==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ pinkie: 2.0.4
+ dev: true
+
+ /pinkie/2.0.4:
+ resolution: {integrity: sha512-MnUuEycAemtSaeFSjXKW/aroV7akBbY+Sv+RkyqFjgAe73F+MR0TBWKBRDkmfWq/HiFmdavfZ1G7h4SPZXaCSg==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /prettier/2.6.1:
+ resolution: {integrity: sha512-8UVbTBYGwN37Bs9LERmxCPjdvPxlEowx2urIL6urHzdb3SDq4B/Z6xLFCblrSnE4iKWcS6ziJ3aOYrc1kz/E2A==}
+ engines: {node: '>=10.13.0'}
+ hasBin: true
+ dev: true
+
+ /pretty-bytes/5.6.0:
+ resolution: {integrity: sha512-FFw039TmrBqFK8ma/7OL3sDz/VytdtJr044/QUJtH0wK9lb9jLq9tJyIxUwtQJHwar2BqtiA4iCWSwo9JLkzFg==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /proc-log/2.0.1:
+ resolution: {integrity: sha512-Kcmo2FhfDTXdcbfDH76N7uBYHINxc/8GW7UAVuVP9I+Va3uHSerrnKV6dLooga/gh7GlgzuCCr/eoldnL1muGw==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dev: true
+
+ /proc-log/3.0.0:
+ resolution: {integrity: sha512-++Vn7NS4Xf9NacaU9Xq3URUuqZETPsf8L4j5/ckhaRYsfPeRyzGw+iDjFhV/Jr3uNmTvvddEJFWh5R1gRgUH8A==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dev: true
+
+ /process-nextick-args/2.0.1:
+ resolution: {integrity: sha512-3ouUOpQhtgrbOa17J7+uxOTpITYWaGP7/AhoR3+A+/1e9skrzelGi/dXzEYyvbxubEF6Wn2ypscTKiKJFFn1ag==}
+ dev: true
+
+ /promise-inflight/1.0.1:
+ resolution: {integrity: sha512-6zWPyEOFaQBJYcGMHBKTKJ3u6TBsnMFOIZSa6ce1e/ZrrsOlnHRHbabMjLiBYKp+n44X9eUI6VUPaukCXHuG4g==}
+ peerDependencies:
+ bluebird: '*'
+ peerDependenciesMeta:
+ bluebird:
+ optional: true
+ dev: true
+
+ /promise-retry/2.0.1:
+ resolution: {integrity: sha512-y+WKFlBR8BGXnsNlIHFGPZmyDf3DFMoLhaflAnyZgV6rG6xu+JwesTo2Q9R6XwYmtmwAFCkAk3e35jEdoeh/3g==}
+ engines: {node: '>=10'}
+ dependencies:
+ err-code: 2.0.3
+ retry: 0.12.0
+ dev: true
+
+ /protractor/7.0.0:
+ resolution: {integrity: sha512-UqkFjivi4GcvUQYzqGYNe0mLzfn5jiLmO8w9nMhQoJRLhy2grJonpga2IWhI6yJO30LibWXJJtA4MOIZD2GgZw==}
+ engines: {node: '>=10.13.x'}
+ deprecated: We have news to share - Protractor is deprecated and will reach end-of-life by Summer 2023. To learn more and find out about other options please refer to this post on the Angular blog. Thank you for using and contributing to Protractor. https://goo.gle/state-of-e2e-in-angular
+ hasBin: true
+ dependencies:
+ '@types/q': 0.0.32
+ '@types/selenium-webdriver': 3.0.20
+ blocking-proxy: 1.0.1
+ browserstack: 1.6.1
+ chalk: 1.1.3
+ glob: 7.2.3
+ jasmine: 2.8.0
+ jasminewd2: 2.2.0
+ q: 1.4.1
+ saucelabs: 1.5.0
+ selenium-webdriver: 3.6.0
+ source-map-support: 0.4.18
+ webdriver-js-extender: 2.1.0
+ webdriver-manager: 12.1.8
+ yargs: 15.4.1
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /proxy-from-env/1.0.0:
+ resolution: {integrity: sha512-F2JHgJQ1iqwnHDcQjVBsq3n/uoaFL+iPW/eAeL7kVxy/2RrWaN4WroKjjvbsoRtv0ftelNyC01bjRhn/bhcf4A==}
+ dev: true
+
+ /psl/1.9.0:
+ resolution: {integrity: sha512-E/ZsdU4HLs/68gYzgGTkMicWTLPdAftJLfJFlLUAAKZGkStNU72sZjT66SnMDVOfOWY/YAoiD7Jxa9iHvngcag==}
+ dev: true
+
+ /pump/3.0.0:
+ resolution: {integrity: sha512-LwZy+p3SFs1Pytd/jYct4wpv49HiYCqd9Rlc5ZVdk0V+8Yzv6jR5Blk3TRmPL1ft69TxP0IMZGJ+WPFU2BFhww==}
+ dependencies:
+ end-of-stream: 1.4.4
+ once: 1.4.0
+ dev: true
+
+ /punycode/2.2.0:
+ resolution: {integrity: sha512-LN6QV1IJ9ZhxWTNdktaPClrNfp8xdSAYS0Zk2ddX7XsXZAxckMHPCBcHRo0cTcEIgYPRiGEkmji3Idkh2yFtYw==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /q/1.4.1:
+ resolution: {integrity: sha512-/CdEdaw49VZVmyIDGUQKDDT53c7qBkO6g5CefWz91Ae+l4+cRtcDYwMTXh6me4O8TMldeGHG3N2Bl84V78Ywbg==}
+ engines: {node: '>=0.6.0', teleport: '>=0.2.0'}
+ dev: true
+
+ /qjobs/1.2.0:
+ resolution: {integrity: sha512-8YOJEHtxpySA3fFDyCRxA+UUV+fA+rTWnuWvylOK/NCjhY+b4ocCtmu8TtsWb+mYeU+GCHf/S66KZF/AsteKHg==}
+ engines: {node: '>=0.9'}
+ dev: true
+
+ /qs/6.10.4:
+ resolution: {integrity: sha512-OQiU+C+Ds5qiH91qh/mg0w+8nwQuLjM4F4M/PbmhDOoYehPh+Fb0bDjtR1sOvy7YKxvj28Y/M0PhP5uVX0kB+g==}
+ engines: {node: '>=0.6'}
+ dependencies:
+ side-channel: 1.0.4
+ dev: true
+
+ /qs/6.11.0:
+ resolution: {integrity: sha512-MvjoMCJwEarSbUYk5O+nmoSzSutSsTwF85zcHPQ9OrlFoZOYIjaqBAJIqIXjptyD5vThxGq52Xu/MaJzRkIk4Q==}
+ engines: {node: '>=0.6'}
+ dependencies:
+ side-channel: 1.0.4
+ dev: true
+
+ /qs/6.5.3:
+ resolution: {integrity: sha512-qxXIEh4pCGfHICj1mAJQ2/2XVZkjCDTcEgfoSQxc/fYivUZxTkk7L3bDBJSoNrEzXI17oUO5Dp07ktqE5KzczA==}
+ engines: {node: '>=0.6'}
+ dev: true
+
+ /range-parser/1.2.1:
+ resolution: {integrity: sha512-Hrgsx+orqoygnmhFbKaHE6c296J+HTAQXoxEF6gNupROmmGJRoyzfG3ccAveqCBrwr/2yxQ5BVd/GTl5agOwSg==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /raw-body/2.5.1:
+ resolution: {integrity: sha512-qqJBtEyVgS0ZmPGdCFPWJ3FreoqvG4MVQln/kCgF7Olq95IbOp0/BWyMwbdtn4VTvkM8Y7khCQ2Xgk/tcrCXig==}
+ engines: {node: '>= 0.8'}
+ dependencies:
+ bytes: 3.1.2
+ http-errors: 2.0.0
+ iconv-lite: 0.4.24
+ unpipe: 1.0.0
+ dev: true
+
+ /read-package-json-fast/3.0.2:
+ resolution: {integrity: sha512-0J+Msgym3vrLOUB3hzQCuZHII0xkNGCtz/HJH9xZshwv9DbDwkw1KaE3gx/e2J5rpEY5rtOy6cyhKOPrkP7FZw==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ json-parse-even-better-errors: 3.0.0
+ npm-normalize-package-bin: 3.0.0
+ dev: true
+
+ /read-package-json/6.0.0:
+ resolution: {integrity: sha512-b/9jxWJ8EwogJPpv99ma+QwtqB7FSl3+V6UXS7Aaay8/5VwMY50oIFooY1UKXMWpfNCM6T/PoGqa5GD1g9xf9w==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ glob: 8.1.0
+ json-parse-even-better-errors: 3.0.0
+ normalize-package-data: 5.0.0
+ npm-normalize-package-bin: 3.0.0
+ dev: true
+
+ /readable-stream/2.3.7:
+ resolution: {integrity: sha512-Ebho8K4jIbHAxnuxi7o42OrZgF/ZTNcsZj6nRKyUmkhLFq8CHItp/fy6hQZuZmP/n3yZ9VBUbp4zz/mX8hmYPw==}
+ dependencies:
+ core-util-is: 1.0.3
+ inherits: 2.0.4
+ isarray: 1.0.0
+ process-nextick-args: 2.0.1
+ safe-buffer: 5.1.2
+ string_decoder: 1.1.1
+ util-deprecate: 1.0.2
+ dev: true
+
+ /readable-stream/3.6.0:
+ resolution: {integrity: sha512-BViHy7LKeTz4oNnkcLJ+lVSL6vpiFeX6/d3oSH8zCW7UxP2onchk+vTGB143xuFjHS3deTgkKoXXymXqymiIdA==}
+ engines: {node: '>= 6'}
+ dependencies:
+ inherits: 2.0.4
+ string_decoder: 1.3.0
+ util-deprecate: 1.0.2
+ dev: true
+
+ /readdirp/3.6.0:
+ resolution: {integrity: sha512-hOS089on8RduqdbhvQ5Z37A0ESjsqz6qnRcffsMU3495FuTdqSm+7bhJ29JvIOsBDEEnan5DPu9t3To9VRlMzA==}
+ engines: {node: '>=8.10.0'}
+ dependencies:
+ picomatch: 2.3.1
+ dev: true
+
+ /reflect-metadata/0.1.13:
+ resolution: {integrity: sha512-Ts1Y/anZELhSsjMcU605fU9RE4Oi3p5ORujwbIKXfWa+0Zxs510Qrmrce5/Jowq3cHSZSJqBjypxmHarc+vEWg==}
+ dev: true
+
+ /request-progress/3.0.0:
+ resolution: {integrity: sha512-MnWzEHHaxHO2iWiQuHrUPBi/1WeBf5PkxQqNyNvLl9VAYSdXkP8tQ3pBSeCPD+yw0v0Aq1zosWLz0BdeXpWwZg==}
+ dependencies:
+ throttleit: 1.0.0
+ dev: true
+
+ /request/2.88.2:
+ resolution: {integrity: sha512-MsvtOrfG9ZcrOwAW+Qi+F6HbD0CWXEh9ou77uOb7FM2WPhwT7smM833PzanhJLsgXjN89Ir6V2PczXNnMpwKhw==}
+ engines: {node: '>= 6'}
+ deprecated: request has been deprecated, see https://github.com/request/request/issues/3142
+ dependencies:
+ aws-sign2: 0.7.0
+ aws4: 1.12.0
+ caseless: 0.12.0
+ combined-stream: 1.0.8
+ extend: 3.0.2
+ forever-agent: 0.6.1
+ form-data: 2.3.3
+ har-validator: 5.1.5
+ http-signature: 1.2.0
+ is-typedarray: 1.0.0
+ isstream: 0.1.2
+ json-stringify-safe: 5.0.1
+ mime-types: 2.1.35
+ oauth-sign: 0.9.0
+ performance-now: 2.1.0
+ qs: 6.5.3
+ safe-buffer: 5.2.1
+ tough-cookie: 2.5.0
+ tunnel-agent: 0.6.0
+ uuid: 3.4.0
+ dev: true
+
+ /require-directory/2.1.1:
+ resolution: {integrity: sha512-fGxEI7+wsG9xrvdjsrlmL22OMTTiHRwAMroiEeMgq8gzoLC/PQr7RsRDSTLUg/bZAZtF+TVIkHc6/4RIKrui+Q==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /require-from-string/2.0.2:
+ resolution: {integrity: sha512-Xf0nWe6RseziFMu+Ap9biiUbmplq6S9/p+7w7YXP/JBHhrUDDUhwa+vANyubuqfZWTveU//DYVGsDG7RKL/vEw==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /require-main-filename/2.0.0:
+ resolution: {integrity: sha512-NKN5kMDylKuldxYLSUfrbo5Tuzh4hd+2E8NPPX02mZtn1VuREQToYe/ZdlJy+J3uCpfaiGF05e7B8W0iXbQHmg==}
+ dev: true
+
+ /requirejs/2.3.6:
+ resolution: {integrity: sha512-ipEzlWQe6RK3jkzikgCupiTbTvm4S0/CAU5GlgptkN5SO6F3u0UD0K18wy6ErDqiCyP4J4YYe1HuAShvsxePLg==}
+ engines: {node: '>=0.4.0'}
+ hasBin: true
+ dev: true
+
+ /requires-port/1.0.0:
+ resolution: {integrity: sha512-KigOCHcocU3XODJxsu8i/j8T9tzT4adHiecwORRQ0ZZFcp7ahwXuRU1m+yuO90C5ZUyGeGfocHDI14M3L3yDAQ==}
+ dev: true
+
+ /resolve/1.22.1:
+ resolution: {integrity: sha512-nBpuuYuY5jFsli/JIs1oldw6fOQCBioohqWZg/2hiaOybXOft4lonv85uDOKXdf8rhyK159cxU5cDcK/NKk8zw==}
+ hasBin: true
+ dependencies:
+ is-core-module: 2.11.0
+ path-parse: 1.0.7
+ supports-preserve-symlinks-flag: 1.0.0
+ dev: true
+
+ /restore-cursor/3.1.0:
+ resolution: {integrity: sha512-l+sSefzHpj5qimhFSE5a8nufZYAM3sBSVMAPtYkmC+4EH2anSGaEMXSD0izRQbu9nfyQ9y5JrVmp7E8oZrUjvA==}
+ engines: {node: '>=8'}
+ dependencies:
+ onetime: 5.1.2
+ signal-exit: 3.0.7
+ dev: true
+
+ /retry/0.12.0:
+ resolution: {integrity: sha512-9LkiTwjUh6rT555DtE9rTX+BKByPfrMzEAtnlEtdEwr3Nkffwiihqe2bWADg+OQRjt9gl6ICdmB/ZFDCGAtSow==}
+ engines: {node: '>= 4'}
+ dev: true
+
+ /rfdc/1.3.0:
+ resolution: {integrity: sha512-V2hovdzFbOi77/WajaSMXk2OLm+xNIeQdMMuB7icj7bk6zi2F8GGAxigcnDFpJHbNyNcgyJDiP+8nOrY5cZGrA==}
+ dev: true
+
+ /rimraf/2.7.1:
+ resolution: {integrity: sha512-uWjbaKIK3T1OSVptzX7Nl6PvQ3qAGtKEtVRjRuazjfL3Bx5eI409VZSqgND+4UNnmzLVdPj9FqFJNPqBZFve4w==}
+ hasBin: true
+ dependencies:
+ glob: 7.2.3
+ dev: true
+
+ /rimraf/3.0.2:
+ resolution: {integrity: sha512-JZkJMZkAGFFPP2YqXZXPbMlMBgsxzE8ILs4lMIX/2o0L9UBw9O/Y3o6wFw/i9YLapcUJWwqbi3kdxIPdC62TIA==}
+ hasBin: true
+ dependencies:
+ glob: 7.2.3
+ dev: true
+
+ /rollup/2.66.1:
+ resolution: {integrity: sha512-crSgLhSkLMnKr4s9iZ/1qJCplgAgrRY+igWv8KhG/AjKOJ0YX/WpmANyn8oxrw+zenF3BXWDLa7Xl/QZISH+7w==}
+ engines: {node: '>=10.0.0'}
+ hasBin: true
+ optionalDependencies:
+ fsevents: 2.3.2
+ dev: true
+
+ /run-async/2.4.1:
+ resolution: {integrity: sha512-tvVnVv01b8c1RrA6Ep7JkStj85Guv/YrMcwqYQnwjsAS2cTmmPGBBjAjpCW7RrSodNSoE2/qg9O4bceNvUuDgQ==}
+ engines: {node: '>=0.12.0'}
+ dev: true
+
+ /rxjs/6.6.7:
+ resolution: {integrity: sha512-hTdwr+7yYNIT5n4AMYp85KA6yw2Va0FLa3Rguvbpa4W3I5xynaBZo41cM3XM+4Q6fRMj3sBYIR1VAmZMXYJvRQ==}
+ engines: {npm: '>=2.0.0'}
+ dependencies:
+ tslib: 1.14.1
+ dev: true
+
+ /rxjs/7.5.7:
+ resolution: {integrity: sha512-z9MzKh/UcOqB3i20H6rtrlaE/CgjLOvheWK/9ILrbhROGTweAi1BaFsTT9FbwZi5Trr1qNRs+MXkhmR06awzQA==}
+ dependencies:
+ tslib: 2.4.1
+ dev: true
+
+ /safe-buffer/5.1.2:
+ resolution: {integrity: sha512-Gd2UZBJDkXlY7GbJxfsE8/nvKkUEU1G38c1siN6QP6a9PT9MmHB8GnpscSmMJSoF8LOIrt8ud/wPtojys4G6+g==}
+ dev: true
+
+ /safe-buffer/5.2.1:
+ resolution: {integrity: sha512-rp3So07KcdmmKbGvgaNxQSJr7bGVSVk5S9Eq1F+ppbRo70+YeaDxkw5Dd8NPN+GD6bjnYm2VuPuCXmpuYvmCXQ==}
+ dev: true
+
+ /safer-buffer/2.1.2:
+ resolution: {integrity: sha512-YZo3K82SD7Riyi0E1EQPojLz7kpepnSQI9IyPbHHg1XXXevb5dJI7tpyN2ADxGcQbHG7vcyRHk0cbwqcQriUtg==}
+ dev: true
+
+ /saucelabs/1.5.0:
+ resolution: {integrity: sha512-jlX3FGdWvYf4Q3LFfFWS1QvPg3IGCGWxIc8QBFdPTbpTJnt/v17FHXYVAn7C8sHf1yUXo2c7yIM0isDryfYtHQ==}
+ dependencies:
+ https-proxy-agent: 2.2.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /sax/1.2.4:
+ resolution: {integrity: sha512-NqVDv9TpANUjFm0N8uM5GxL36UgKi9/atZw+x7YFnQ8ckwFGKrl4xX4yWtrey3UJm5nP1kUbnYgLopqWNSRhWw==}
+ dev: true
+
+ /selenium-webdriver/3.6.0:
+ resolution: {integrity: sha512-WH7Aldse+2P5bbFBO4Gle/nuQOdVwpHMTL6raL3uuBj/vPG07k6uzt3aiahu352ONBr5xXh0hDlM3LhtXPOC4Q==}
+ engines: {node: '>= 6.9.0'}
+ dependencies:
+ jszip: 3.10.1
+ rimraf: 2.7.1
+ tmp: 0.0.30
+ xml2js: 0.4.23
+ dev: true
+
+ /semver/5.7.1:
+ resolution: {integrity: sha512-sauaDf/PZdVgrLTNYHRtpXa1iRiKcaebiKQ1BJdpQlWH2lCvexQdX55snPFyK7QzpudqbCI0qXFfOasHdyNDGQ==}
+ hasBin: true
+ dev: true
+
+ /semver/6.3.0:
+ resolution: {integrity: sha512-b39TBaTSfV6yBrapU89p5fKekE2m/NwnDocOVruQFS1/veMgdzuPcnOM34M6CwxW8jH/lxEa5rBoDeUwu5HHTw==}
+ hasBin: true
+ dev: true
+
+ /semver/7.3.8:
+ resolution: {integrity: sha512-NB1ctGL5rlHrPJtFDVIVzTyQylMLu9N9VICA6HSFJo8MCGVTMW6gfpicwKmmK/dAjTOrqu5l63JJOpDSrAis3A==}
+ engines: {node: '>=10'}
+ hasBin: true
+ dependencies:
+ lru-cache: 6.0.0
+ dev: true
+
+ /set-blocking/2.0.0:
+ resolution: {integrity: sha512-KiKBS8AnWGEyLzofFfmvKwpdPzqiy16LvQfK3yv/fVH7Bj13/wl3JSR1J+rfgRE9q7xUJK4qvgS8raSOeLUehw==}
+ dev: true
+
+ /setimmediate/1.0.5:
+ resolution: {integrity: sha512-MATJdZp8sLqDl/68LfQmbP8zKPLQNV6BIZoIgrscFDQ+RsvK/BxeDQOgyxKKoh0y/8h3BqVFnCqQ/gd+reiIXA==}
+ dev: true
+
+ /setprototypeof/1.2.0:
+ resolution: {integrity: sha512-E5LDX7Wrp85Kil5bhZv46j8jOeboKq5JMmYM3gVGdGH8xFpPWXUMsNrlODCrkoxMEeNi/XZIwuRvY4XNwYMJpw==}
+ dev: true
+
+ /shebang-command/2.0.0:
+ resolution: {integrity: sha512-kHxr2zZpYtdmrN1qDjrrX/Z1rR1kG8Dx+gkpK1G4eXmvXswmcE1hTWBWYUzlraYw1/yZp6YuDY77YtvbN0dmDA==}
+ engines: {node: '>=8'}
+ dependencies:
+ shebang-regex: 3.0.0
+ dev: true
+
+ /shebang-regex/3.0.0:
+ resolution: {integrity: sha512-7++dFhtcx3353uBaq8DDR4NuxBetBzC7ZQOhmTQInHEd6bSrXdiEyzCvG07Z44UYdLShWUyXt5M/yhz8ekcb1A==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /side-channel/1.0.4:
+ resolution: {integrity: sha512-q5XPytqFEIKHkGdiMIrY10mvLRvnQh42/+GoBlFW3b2LXLE2xxJpZFdm94we0BaoV3RwJyGqg5wS7epxTv0Zvw==}
+ dependencies:
+ call-bind: 1.0.2
+ get-intrinsic: 1.1.3
+ object-inspect: 1.12.3
+ dev: true
+
+ /signal-exit/3.0.7:
+ resolution: {integrity: sha512-wnD2ZE+l+SPC/uoS0vXeE9L1+0wuaMqKlfz9AMUo38JsyLSBWSFcHR1Rri62LZc12vLr1gb3jl7iwQhgwpAbGQ==}
+ dev: true
+
+ /slash/2.0.0:
+ resolution: {integrity: sha512-ZYKh3Wh2z1PpEXWr0MpSBZ0V6mZHAQfYevttO11c51CaWjGTaadiKZ+wVt1PbMlDV5qhMFslpZCemhwOK7C89A==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /slice-ansi/3.0.0:
+ resolution: {integrity: sha512-pSyv7bSTC7ig9Dcgbw9AuRNUb5k5V6oDudjZoMBSr13qpLBG7tB+zgCkARjq7xIUgdz5P1Qe8u+rSGdouOOIyQ==}
+ engines: {node: '>=8'}
+ dependencies:
+ ansi-styles: 4.3.0
+ astral-regex: 2.0.0
+ is-fullwidth-code-point: 3.0.0
+ dev: true
+
+ /slice-ansi/4.0.0:
+ resolution: {integrity: sha512-qMCMfhY040cVHT43K9BFygqYbUPFZKHOg7K73mtTWJRb8pyP3fzf4Ixd5SzdEJQ6MRUg/WBnOLxghZtKKurENQ==}
+ engines: {node: '>=10'}
+ dependencies:
+ ansi-styles: 4.3.0
+ astral-regex: 2.0.0
+ is-fullwidth-code-point: 3.0.0
+ dev: true
+
+ /smart-buffer/4.2.0:
+ resolution: {integrity: sha512-94hK0Hh8rPqQl2xXc3HsaBoOXKV20MToPkcXvwbISWLEs+64sBq5kFgn2kJDHb1Pry9yrP0dxrCI9RRci7RXKg==}
+ engines: {node: '>= 6.0.0', npm: '>= 3.0.0'}
+ dev: true
+
+ /socket.io-adapter/2.4.0:
+ resolution: {integrity: sha512-W4N+o69rkMEGVuk2D/cvca3uYsvGlMwsySWV447y99gUPghxq42BxqLNMndb+a1mm/5/7NeXVQS7RLa2XyXvYg==}
+ dev: true
+
+ /socket.io-parser/4.2.1:
+ resolution: {integrity: sha512-V4GrkLy+HeF1F/en3SpUaM+7XxYXpuMUWLGde1kSSh5nQMN4hLrbPIkD+otwh6q9R6NOQBN4AMaOZ2zVjui82g==}
+ engines: {node: '>=10.0.0'}
+ dependencies:
+ '@socket.io/component-emitter': 3.1.0
+ debug: 4.3.4
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /socket.io/4.5.4:
+ resolution: {integrity: sha512-m3GC94iK9MfIEeIBfbhJs5BqFibMtkRk8ZpKwG2QwxV0m/eEhPIV4ara6XCF1LWNAus7z58RodiZlAH71U3EhQ==}
+ engines: {node: '>=10.0.0'}
+ dependencies:
+ accepts: 1.3.8
+ base64id: 2.0.0
+ debug: 4.3.4
+ engine.io: 6.2.1
+ socket.io-adapter: 2.4.0
+ socket.io-parser: 4.2.1
+ transitivePeerDependencies:
+ - bufferutil
+ - supports-color
+ - utf-8-validate
+ dev: true
+
+ /socks-proxy-agent/7.0.0:
+ resolution: {integrity: sha512-Fgl0YPZ902wEsAyiQ+idGd1A7rSFx/ayC1CQVMw5P+EQx2V0SgpGtf6OKFhVjPflPUl9YMmEOnmfjCdMUsygww==}
+ engines: {node: '>= 10'}
+ dependencies:
+ agent-base: 6.0.2
+ debug: 4.3.4
+ socks: 2.7.1
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /socks/2.7.1:
+ resolution: {integrity: sha512-7maUZy1N7uo6+WVEX6psASxtNlKaNVMlGQKkG/63nEDdLOWNbiUMoLK7X4uYoLhQstau72mLgfEWcXcwsaHbYQ==}
+ engines: {node: '>= 10.13.0', npm: '>= 3.0.0'}
+ dependencies:
+ ip: 2.0.0
+ smart-buffer: 4.2.0
+ dev: true
+
+ /source-map-support/0.4.18:
+ resolution: {integrity: sha512-try0/JqxPLF9nOjvSta7tVondkP5dwgyLDjVoyMDlmjugT2lRZ1OfsrYTkCd2hkDnJTKRbO/Rl3orm8vlsUzbA==}
+ dependencies:
+ source-map: 0.5.7
+ dev: true
+
+ /source-map-support/0.5.21:
+ resolution: {integrity: sha512-uBHU3L3czsIyYXKX88fdrGovxdSCoTGDRZ6SYXtSRxLZUzHg5P/66Ht6uoUlHu9EZod+inXhKo3qQgwXUT/y1w==}
+ dependencies:
+ buffer-from: 1.1.2
+ source-map: 0.6.1
+ dev: true
+
+ /source-map/0.5.7:
+ resolution: {integrity: sha512-LbrmJOMUSdEVxIKvdcJzQC+nQhe8FUZQTXQy6+I75skNgn3OoQ0DZA8YnFa7gp8tqtL3KPf1kmo0R5DoApeSGQ==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /source-map/0.6.1:
+ resolution: {integrity: sha512-UjgapumWlbMhkBgzT7Ykc5YXUT46F0iKu8SGXq0bcwP5dz/h0Plj6enJqjz1Zbq2l5WaqYnrVbwWOWMyF3F47g==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /source-map/0.7.4:
+ resolution: {integrity: sha512-l3BikUxvPOcn5E74dZiq5BGsTb5yEwhaTSzccU6t4sDOH8NWJCstKO5QT2CvtFoK6F0saL7p9xHAqHOlCPJygA==}
+ engines: {node: '>= 8'}
+ dev: true
+
+ /sourcemap-codec/1.4.8:
+ resolution: {integrity: sha512-9NykojV5Uih4lgo5So5dtw+f0JgJX30KCNI8gwhz2J9A15wD0Ml6tjHKwf6fTSa6fAdVBdZeNOs9eJ71qCk8vA==}
+ deprecated: Please use @jridgewell/sourcemap-codec instead
+ dev: true
+
+ /spdx-correct/3.1.1:
+ resolution: {integrity: sha512-cOYcUWwhCuHCXi49RhFRCyJEK3iPj1Ziz9DpViV3tbZOwXD49QzIN3MpOLJNxh2qwq2lJJZaKMVw9qNi4jTC0w==}
+ dependencies:
+ spdx-expression-parse: 3.0.1
+ spdx-license-ids: 3.0.12
+ dev: true
+
+ /spdx-exceptions/2.3.0:
+ resolution: {integrity: sha512-/tTrYOC7PPI1nUAgx34hUpqXuyJG+DTHJTnIULG4rDygi4xu/tfgmq1e1cIRwRzwZgo4NLySi+ricLkZkw4i5A==}
+ dev: true
+
+ /spdx-expression-parse/3.0.1:
+ resolution: {integrity: sha512-cbqHunsQWnJNE6KhVSMsMeH5H/L9EpymbzqTQ3uLwNCLZ1Q481oWaofqH7nO6V07xlXwY6PhQdQ2IedWx/ZK4Q==}
+ dependencies:
+ spdx-exceptions: 2.3.0
+ spdx-license-ids: 3.0.12
+ dev: true
+
+ /spdx-license-ids/3.0.12:
+ resolution: {integrity: sha512-rr+VVSXtRhO4OHbXUiAF7xW3Bo9DuuF6C5jH+q/x15j2jniycgKbxU09Hr0WqlSLUs4i4ltHGXqTe7VHclYWyA==}
+ dev: true
+
+ /sshpk/1.17.0:
+ resolution: {integrity: sha512-/9HIEs1ZXGhSPE8X6Ccm7Nam1z8KcoCqPdI7ecm1N33EzAetWahvQWVqLZtaZQ+IDKX4IyA2o0gBzqIMkAagHQ==}
+ engines: {node: '>=0.10.0'}
+ hasBin: true
+ dependencies:
+ asn1: 0.2.6
+ assert-plus: 1.0.0
+ bcrypt-pbkdf: 1.0.2
+ dashdash: 1.14.1
+ ecc-jsbn: 0.1.2
+ getpass: 0.1.7
+ jsbn: 0.1.1
+ safer-buffer: 2.1.2
+ tweetnacl: 0.14.5
+ dev: true
+
+ /ssri/10.0.1:
+ resolution: {integrity: sha512-WVy6di9DlPOeBWEjMScpNipeSX2jIZBGEn5Uuo8Q7aIuFEuDX0pw8RxcOjlD1TWP4obi24ki7m/13+nFpcbXrw==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ minipass: 4.0.0
+ dev: true
+
+ /ssri/9.0.1:
+ resolution: {integrity: sha512-o57Wcn66jMQvfHG1FlYbWeZWW/dHZhJXjpIcTfXldXEk5nz5lStPo3mK0OJQfGR3RbZUlbISexbljkJzuEj/8Q==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ minipass: 3.3.6
+ dev: true
+
+ /statuses/1.5.0:
+ resolution: {integrity: sha512-OpZ3zP+jT1PI7I8nemJX4AKmAX070ZkYPVWV/AaKTJl+tXCTGyVdC1a4SL8RUQYEwk/f34ZX8UTykN68FwrqAA==}
+ engines: {node: '>= 0.6'}
+ dev: true
+
+ /statuses/2.0.1:
+ resolution: {integrity: sha512-RwNA9Z/7PrK06rYLIzFMlaF+l73iwpzsqRIFgbMLbTcLD6cOao82TaWefPXQvB2fOC4AjuYSEndS7N/mTCbkdQ==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /streamroller/3.1.4:
+ resolution: {integrity: sha512-Ha1Ccw2/N5C/IF8Do6zgNe8F3jQo8MPBnMBGvX0QjNv/I97BcNRzK6/mzOpZHHK7DjMLTI3c7Xw7Y1KvdChkvw==}
+ engines: {node: '>=8.0'}
+ dependencies:
+ date-format: 4.0.14
+ debug: 4.3.4
+ fs-extra: 8.1.0
+ transitivePeerDependencies:
+ - supports-color
+ dev: true
+
+ /string-width/4.2.3:
+ resolution: {integrity: sha512-wKyQRQpjJ0sIp62ErSZdGsjMJWsap5oRNihHhu6G7JVO/9jIB6UyevL+tXuOqrng8j/cxKTWyWUwvSTriiZz/g==}
+ engines: {node: '>=8'}
+ dependencies:
+ emoji-regex: 8.0.0
+ is-fullwidth-code-point: 3.0.0
+ strip-ansi: 6.0.1
+ dev: true
+
+ /string_decoder/1.1.1:
+ resolution: {integrity: sha512-n/ShnvDi6FHbbVfviro+WojiFzv+s8MPMHBczVePfUpDJLwoLT0ht1l4YwBCbi8pJAveEEdnkHyPyTP/mzRfwg==}
+ dependencies:
+ safe-buffer: 5.1.2
+ dev: true
+
+ /string_decoder/1.3.0:
+ resolution: {integrity: sha512-hkRX8U1WjJFd8LsDJ2yQ/wWWxaopEsABU1XfkM8A+j0+85JAGppt16cr1Whg6KIbb4okU6Mql6BOj+uup/wKeA==}
+ dependencies:
+ safe-buffer: 5.2.1
+ dev: true
+
+ /strip-ansi/3.0.1:
+ resolution: {integrity: sha512-VhumSSbBqDTP8p2ZLKj40UjBCV4+v8bUSEpUb4KjRgWk9pbqGF4REFj6KEagidb2f/M6AzC0EmFyDNGaw9OCzg==}
+ engines: {node: '>=0.10.0'}
+ dependencies:
+ ansi-regex: 2.1.1
+ dev: true
+
+ /strip-ansi/6.0.1:
+ resolution: {integrity: sha512-Y38VPSHcqkFrCpFnQ9vuSXmquuv5oXOKpGeT6aGrr3o3Gc9AlVa6JBfUSOCnbxGGZF+/0ooI7KrPuUSztUdU5A==}
+ engines: {node: '>=8'}
+ dependencies:
+ ansi-regex: 5.0.1
+ dev: true
+
+ /strip-final-newline/2.0.0:
+ resolution: {integrity: sha512-BrpvfNAE3dcvq7ll3xVumzjKjZQ5tI1sEUIKr3Uoks0XUl45St3FlatVqef9prk4jRDzhW6WZg+3bk93y6pLjA==}
+ engines: {node: '>=6'}
+ dev: true
+
+ /supports-color/2.0.0:
+ resolution: {integrity: sha512-KKNVtd6pCYgPIKU4cp2733HWYCpplQhddZLBUryaAHou723x+FRzQ5Df824Fj+IyyuiQTRoub4SnIFfIcrp70g==}
+ engines: {node: '>=0.8.0'}
+ dev: true
+
+ /supports-color/5.5.0:
+ resolution: {integrity: sha512-QjVjwdXIt408MIiAqCX4oUKsgU2EqAGzs2Ppkm4aQYbjm+ZEWEcW4SfFNTr4uMNZma0ey4f5lgLrkB0aX0QMow==}
+ engines: {node: '>=4'}
+ dependencies:
+ has-flag: 3.0.0
+ dev: true
+
+ /supports-color/7.2.0:
+ resolution: {integrity: sha512-qpCAvRl9stuOHveKsn7HncJRvv501qIacKzQlO/+Lwxc9+0q2wLyv4Dfvt80/DPn2pqOBsJdDiogXGR9+OvwRw==}
+ engines: {node: '>=8'}
+ dependencies:
+ has-flag: 4.0.0
+ dev: true
+
+ /supports-color/8.1.1:
+ resolution: {integrity: sha512-MpUEN2OodtUzxvKQl72cUF7RQ5EiHsGvSsVG0ia9c5RbWGL2CI4C7EpPS8UTBIplnlzZiNuV56w+FuNxy3ty2Q==}
+ engines: {node: '>=10'}
+ dependencies:
+ has-flag: 4.0.0
+ dev: true
+
+ /supports-preserve-symlinks-flag/1.0.0:
+ resolution: {integrity: sha512-ot0WnXS9fgdkgIcePe6RHNk1WA8+muPa6cSjeR3V8K27q9BB1rTE3R1p7Hv0z1ZyAc8s6Vvv8DIyWf681MAt0w==}
+ engines: {node: '>= 0.4'}
+ dev: true
+
+ /symbol-observable/4.0.0:
+ resolution: {integrity: sha512-b19dMThMV4HVFynSAM1++gBHAbk2Tc/osgLIBZMKsyqh34jb2e8Os7T6ZW/Bt3pJFdBTd2JwAnAAEQV7rSNvcQ==}
+ engines: {node: '>=0.10'}
+ dev: true
+
+ /tar/6.1.13:
+ resolution: {integrity: sha512-jdIBIN6LTIe2jqzay/2vtYLlBHa3JF42ot3h1dW8Q0PaAG4v8rm0cvpVePtau5C6OKXGGcgO9q2AMNSWxiLqKw==}
+ engines: {node: '>=10'}
+ dependencies:
+ chownr: 2.0.0
+ fs-minipass: 2.1.0
+ minipass: 4.0.0
+ minizlib: 2.1.2
+ mkdirp: 1.0.4
+ yallist: 4.0.0
+ dev: true
+
+ /terser/5.10.0:
+ resolution: {integrity: sha512-AMmF99DMfEDiRJfxfY5jj5wNH/bYO09cniSqhfoyxc8sFoYIgkJy86G04UoZU5VjlpnplVu0K6Tx6E9b5+DlHA==}
+ engines: {node: '>=10'}
+ hasBin: true
+ peerDependenciesMeta:
+ acorn:
+ optional: true
+ dependencies:
+ acorn: 8.8.1
+ commander: 2.20.3
+ source-map: 0.7.4
+ source-map-support: 0.5.21
+ dev: true
+
+ /throttleit/1.0.0:
+ resolution: {integrity: sha512-rkTVqu6IjfQ/6+uNuuc3sZek4CEYxTJom3IktzgdSxcZqdARuebbA/f4QmAxMQIxqq9ZLEUkSYqvuk1I6VKq4g==}
+ dev: true
+
+ /through/2.3.8:
+ resolution: {integrity: sha512-w89qg7PI8wAdvX60bMDP+bFoD5Dvhm9oLheFp5O4a2QF0cSBGsBX4qZmadPMvVqlLJBBci+WqGGOAPvcDeNSVg==}
+ dev: true
+
+ /tmp/0.0.30:
+ resolution: {integrity: sha512-HXdTB7lvMwcb55XFfrTM8CPr/IYREk4hVBFaQ4b/6nInrluSL86hfHm7vu0luYKCfyBZp2trCjpc8caC3vVM3w==}
+ engines: {node: '>=0.4.0'}
+ dependencies:
+ os-tmpdir: 1.0.2
+ dev: true
+
+ /tmp/0.0.33:
+ resolution: {integrity: sha512-jRCJlojKnZ3addtTOjdIqoRuPEKBvNXcGYqzO6zWZX8KfKEpnGY5jfggJQ3EjKuu8D4bJRr0y+cYJFmYbImXGw==}
+ engines: {node: '>=0.6.0'}
+ dependencies:
+ os-tmpdir: 1.0.2
+ dev: true
+
+ /tmp/0.2.1:
+ resolution: {integrity: sha512-76SUhtfqR2Ijn+xllcI5P1oyannHNHByD80W1q447gU3mp9G9PSpGdWmjUOHRDPiHYacIk66W7ubDTuPF3BEtQ==}
+ engines: {node: '>=8.17.0'}
+ dependencies:
+ rimraf: 3.0.2
+ dev: true
+
+ /to-fast-properties/2.0.0:
+ resolution: {integrity: sha512-/OaKK0xYrs3DmxRYqL/yDc+FxFUVYhDlXMhRmv3z915w2HF1tnN1omB354j8VUGO/hbRzyD6Y3sA7v7GS/ceog==}
+ engines: {node: '>=4'}
+ dev: true
+
+ /to-regex-range/5.0.1:
+ resolution: {integrity: sha512-65P7iz6X5yEr1cwcgvQxbbIw7Uk3gOy5dIdtZ4rDveLqhrdJP+Li/Hx6tyK0NEb+2GCyneCMJiGqrADCSNk8sQ==}
+ engines: {node: '>=8.0'}
+ dependencies:
+ is-number: 7.0.0
+ dev: true
+
+ /toidentifier/1.0.1:
+ resolution: {integrity: sha512-o5sSPKEkg/DIQNmH43V0/uerLrpzVedkUh8tGNvaeXpfpuwjKenlSox/2O/BTlZUtEe+JG7s5YhEz608PlAHRA==}
+ engines: {node: '>=0.6'}
+ dev: true
+
+ /tough-cookie/2.5.0:
+ resolution: {integrity: sha512-nlLsUzgm1kfLXSXfRZMc1KLAugd4hqJHDTvc2hDIwS3mZAfMEuMbc03SujMF+GEcpaX/qboeycw6iO8JwVv2+g==}
+ engines: {node: '>=0.8'}
+ dependencies:
+ psl: 1.9.0
+ punycode: 2.2.0
+ dev: true
+
+ /tslib/1.14.1:
+ resolution: {integrity: sha512-Xni35NKzjgMrwevysHTCArtLDpPvye8zV/0E4EyYn43P7/7qvQwPh9BGkHewbMulVntbigmcT7rdX3BNo9wRJg==}
+ dev: true
+
+ /tslib/2.4.1:
+ resolution: {integrity: sha512-tGyy4dAjRIEwI7BzsB0lynWgOpfqjUdq91XXAlIWD2OwKBH7oCl/GZG/HT4BOHrTlPMOASlMQ7veyTqpmRcrNA==}
+
+ /tunnel-agent/0.6.0:
+ resolution: {integrity: sha512-McnNiV1l8RYeY8tBgEpuodCC1mLUdbSN+CYBL7kJsJNInOP8UjDDEwdk6Mw60vdLLrr5NHKZhMAOSrR2NZuQ+w==}
+ dependencies:
+ safe-buffer: 5.2.1
+ dev: true
+
+ /tweetnacl/0.14.5:
+ resolution: {integrity: sha512-KXXFFdAbFXY4geFIwoyNK+f5Z1b7swfXABfL7HXCmoIWMKU3dmS26672A4EeQtDzLKy7SXmfBu51JolvEKwtGA==}
+ dev: true
+
+ /type-fest/0.21.3:
+ resolution: {integrity: sha512-t0rzBq87m3fVcduHDUFhKmyyX+9eo6WQjZvf51Ea/M0Q7+T374Jp1aUiyUl0GKxp8M/OETVHSDvmkyPgvX+X2w==}
+ engines: {node: '>=10'}
+ dev: true
+
+ /type-is/1.6.18:
+ resolution: {integrity: sha512-TkRKr9sUTxEH8MdfuCSP7VizJyzRNMjj2J2do2Jr3Kym598JVdEksuzPQCnlFPW4ky9Q+iA+ma9BGm06XQBy8g==}
+ engines: {node: '>= 0.6'}
+ dependencies:
+ media-typer: 0.3.0
+ mime-types: 2.1.35
+ dev: true
+
+ /typescript/4.8.4:
+ resolution: {integrity: sha512-QCh+85mCy+h0IGff8r5XWzOVSbBO+KfeYrMQh7NJ58QujwcE22u+NUSmUxqF+un70P9GXKxa2HCNiTTMJknyjQ==}
+ engines: {node: '>=4.2.0'}
+ hasBin: true
+ dev: true
+
+ /ua-parser-js/0.7.32:
+ resolution: {integrity: sha512-f9BESNVhzlhEFf2CHMSj40NWOjYPl1YKYbrvIr/hFTDEmLq7SRbWvm7FcdcpCYT95zrOhC7gZSxjdnnTpBcwVw==}
+ dev: true
+
+ /unique-filename/2.0.1:
+ resolution: {integrity: sha512-ODWHtkkdx3IAR+veKxFV+VBkUMcN+FaqzUUd7IZzt+0zhDZFPFxhlqwPF3YQvMHx1TD0tdgYl+kuPnJ8E6ql7A==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ unique-slug: 3.0.0
+ dev: true
+
+ /unique-filename/3.0.0:
+ resolution: {integrity: sha512-afXhuC55wkAmZ0P18QsVE6kp8JaxrEokN2HGIoIVv2ijHQd419H0+6EigAFcIzXeMIkcIkNBpB3L/DXB3cTS/g==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ unique-slug: 4.0.0
+ dev: true
+
+ /unique-slug/3.0.0:
+ resolution: {integrity: sha512-8EyMynh679x/0gqE9fT9oilG+qEt+ibFyqjuVTsZn1+CMxH+XLlpvr2UZx4nVcCwTpx81nICr2JQFkM+HPLq4w==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ imurmurhash: 0.1.4
+ dev: true
+
+ /unique-slug/4.0.0:
+ resolution: {integrity: sha512-WrcA6AyEfqDX5bWige/4NQfPZMtASNVxdmWR76WESYQVAACSgWcR6e9i0mofqqBxYFtL4oAxPIptY73/0YE1DQ==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ imurmurhash: 0.1.4
+ dev: true
+
+ /universalify/0.1.2:
+ resolution: {integrity: sha512-rBJeI5CXAlmy1pV+617WB9J63U6XcazHHF2f2dbJix4XzpUF0RS3Zbj0FGIOCAva5P/d/GBOYaACQ1w+0azUkg==}
+ engines: {node: '>= 4.0.0'}
+ dev: true
+
+ /universalify/2.0.0:
+ resolution: {integrity: sha512-hAZsKq7Yy11Zu1DE0OzWjw7nnLZmJZYTDZZyEFHZdUhV8FkH5MCfoU1XMaxXovpyW5nq5scPqq0ZDP9Zyl04oQ==}
+ engines: {node: '>= 10.0.0'}
+ dev: true
+
+ /unpipe/1.0.0:
+ resolution: {integrity: sha512-pjy2bYhSsufwWlKwPc+l3cN7+wuJlK6uz0YdJEOlQDbl6jo/YlPi4mb8agUkVC8BF7V8NuzeyPNqRksA3hztKQ==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /untildify/4.0.0:
+ resolution: {integrity: sha512-KK8xQ1mkzZeg9inewmFVDNkg3l5LUhoq9kN6iWYB/CC9YMG8HA+c1Q8HwDe6dEX7kErrEVNVBO3fWsVq5iDgtw==}
+ engines: {node: '>=8'}
+ dev: true
+
+ /update-browserslist-db/1.0.10_browserslist@4.21.4:
+ resolution: {integrity: sha512-OztqDenkfFkbSG+tRxBeAnCVPckDBcvibKd35yDONx6OU8N7sqgwc7rCbkJ/WcYtVRZ4ba68d6byhC21GFh7sQ==}
+ hasBin: true
+ peerDependencies:
+ browserslist: '>= 4.21.0'
+ dependencies:
+ browserslist: 4.21.4
+ escalade: 3.1.1
+ picocolors: 1.0.0
+ dev: true
+
+ /uri-js/4.4.1:
+ resolution: {integrity: sha512-7rKUyy33Q1yc98pQ1DAmLtwX109F7TIfWlW1Ydo8Wl1ii1SeHieeh0HHfPeL2fMXK6z0s8ecKs9frCuLJvndBg==}
+ dependencies:
+ punycode: 2.2.0
+ dev: true
+
+ /util-deprecate/1.0.2:
+ resolution: {integrity: sha512-EPD5q1uXyFxJpCrLnCc1nHnq3gOa6DZBocAIiI2TaSCA7VCJ1UJDMagCzIkXNsUYfD1daK//LTEQ8xiIbrHtcw==}
+ dev: true
+
+ /utils-merge/1.0.1:
+ resolution: {integrity: sha512-pMZTvIkT1d+TFGvDOqodOclx0QWkkgi6Tdoa8gC8ffGAAqz9pzPTZWAybbsHHoED/ztMtkv/VoYTYyShUn81hA==}
+ engines: {node: '>= 0.4.0'}
+ dev: true
+
+ /uuid/3.4.0:
+ resolution: {integrity: sha512-HjSDRw6gZE5JMggctHBcjVak08+KEVhSIiDzFnT9S9aegmp85S/bReBVTb4QTFaRNptJ9kuYaNhnbNEOkbKb/A==}
+ deprecated: Please upgrade to version 7 or higher. Older versions may use Math.random() in certain circumstances, which is known to be problematic. See https://v8.dev/blog/math-random for details.
+ hasBin: true
+ dev: true
+
+ /uuid/8.3.2:
+ resolution: {integrity: sha512-+NYs2QeMWy+GWFOEm9xnn6HCDp0l7QBD7ml8zLUmJ+93Q5NF0NocErnwkTkXVFNiX3/fpC6afS8Dhb/gz7R7eg==}
+ hasBin: true
+ dev: true
+
+ /validate-npm-package-license/3.0.4:
+ resolution: {integrity: sha512-DpKm2Ui/xN7/HQKCtpZxoRWBhZ9Z0kqtygG8XCgNQ8ZlDnxuQmWhj566j8fN4Cu3/JmbhsDo7fcAJq4s9h27Ew==}
+ dependencies:
+ spdx-correct: 3.1.1
+ spdx-expression-parse: 3.0.1
+ dev: true
+
+ /validate-npm-package-name/4.0.0:
+ resolution: {integrity: sha512-mzR0L8ZDktZjpX4OB46KT+56MAhl4EIazWP/+G/HPGuvfdaqg4YsCdtOm6U9+LOFyYDoh4dpnpxZRB9MQQns5Q==}
+ engines: {node: ^12.13.0 || ^14.15.0 || >=16.0.0}
+ dependencies:
+ builtins: 5.0.1
+ dev: true
+
+ /validate-npm-package-name/5.0.0:
+ resolution: {integrity: sha512-YuKoXDAhBYxY7SfOKxHBDoSyENFeW5VvIIQp2TGQuit8gpK6MnWaQelBKxso72DoxTZfZdcP3W90LqpSkgPzLQ==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ dependencies:
+ builtins: 5.0.1
+ dev: true
+
+ /vary/1.1.2:
+ resolution: {integrity: sha512-BNGbWLfd0eUPabhkXUVm0j8uuvREyTh5ovRa/dyow/BqAbZJyC+5fU+IzQOzmAKzYqYRAISoRhdQr3eIZ/PXqg==}
+ engines: {node: '>= 0.8'}
+ dev: true
+
+ /verror/1.10.0:
+ resolution: {integrity: sha512-ZZKSmDAEFOijERBLkmYfJ+vmk3w+7hOLYDNkRCuRuMJGEmqYNCNLyBBFwWKVMhfwaEF3WOd0Zlw86U/WC/+nYw==}
+ engines: {'0': node >=0.6.0}
+ dependencies:
+ assert-plus: 1.0.0
+ core-util-is: 1.0.2
+ extsprintf: 1.3.0
+ dev: true
+
+ /void-elements/2.0.1:
+ resolution: {integrity: sha512-qZKX4RnBzH2ugr8Lxa7x+0V6XD9Sb/ouARtiasEQCHB1EVU4NXtmHsDDrx1dO4ne5fc3J6EW05BP1Dl0z0iung==}
+ engines: {node: '>=0.10.0'}
+ dev: true
+
+ /wcwidth/1.0.1:
+ resolution: {integrity: sha512-XHPEwS0q6TaxcvG85+8EYkbiCux2XtWG2mkc47Ng2A77BQu9+DqIOJldST4HgPkuea7dvKSj5VgX3P1d4rW8Tg==}
+ dependencies:
+ defaults: 1.0.4
+ dev: true
+
+ /webdriver-js-extender/2.1.0:
+ resolution: {integrity: sha512-lcUKrjbBfCK6MNsh7xaY2UAUmZwe+/ib03AjVOpFobX4O7+83BUveSrLfU0Qsyb1DaKJdQRbuU+kM9aZ6QUhiQ==}
+ engines: {node: '>=6.9.x'}
+ dependencies:
+ '@types/selenium-webdriver': 3.0.20
+ selenium-webdriver: 3.6.0
+ dev: true
+
+ /webdriver-manager/12.1.8:
+ resolution: {integrity: sha512-qJR36SXG2VwKugPcdwhaqcLQOD7r8P2Xiv9sfNbfZrKBnX243iAkOueX1yAmeNgIKhJ3YAT/F2gq6IiEZzahsg==}
+ engines: {node: '>=6.9.x'}
+ hasBin: true
+ dependencies:
+ adm-zip: 0.4.16
+ chalk: 1.1.3
+ del: 2.2.2
+ glob: 7.2.3
+ ini: 1.3.8
+ minimist: 1.2.7
+ q: 1.4.1
+ request: 2.88.2
+ rimraf: 2.7.1
+ semver: 5.7.1
+ xml2js: 0.4.23
+ dev: true
+
+ /which-module/2.0.0:
+ resolution: {integrity: sha512-B+enWhmw6cjfVC7kS8Pj9pCrKSc5txArRyaYGe088shv/FGWH+0Rjx/xPgtsWfsUtS27FkP697E4DDhgrgoc0Q==}
+ dev: true
+
+ /which/1.3.1:
+ resolution: {integrity: sha512-HxJdYWq1MTIQbJ3nw0cqssHoTNU267KlrDuGZ1WYlxDStUtKUhOaJmh112/TZmHxxUfuJqPXSOm7tDyas0OSIQ==}
+ hasBin: true
+ dependencies:
+ isexe: 2.0.0
+ dev: true
+
+ /which/2.0.2:
+ resolution: {integrity: sha512-BLI3Tl1TW3Pvl70l3yq3Y64i+awpwXqsGBYWkkqMtnbXgrMD+yj7rhW0kuEDxzJaYXGjEW5ogapKNMEKNMjibA==}
+ engines: {node: '>= 8'}
+ hasBin: true
+ dependencies:
+ isexe: 2.0.0
+ dev: true
+
+ /which/3.0.0:
+ resolution: {integrity: sha512-nla//68K9NU6yRiwDY/Q8aU6siKlSs64aEC7+IV56QoAuyQT2ovsJcgGYGyqMOmI/CGN1BOR6mM5EN0FBO+zyQ==}
+ engines: {node: ^14.17.0 || ^16.13.0 || >=18.0.0}
+ hasBin: true
+ dependencies:
+ isexe: 2.0.0
+ dev: true
+
+ /wide-align/1.1.5:
+ resolution: {integrity: sha512-eDMORYaPNZ4sQIuuYPDHdQvf4gyCF9rEEV/yPxGfwPkRodwEgiMUUXTx/dex+Me0wxx53S+NgUHaP7y3MGlDmg==}
+ dependencies:
+ string-width: 4.2.3
+ dev: true
+
+ /wrap-ansi/6.2.0:
+ resolution: {integrity: sha512-r6lPcBGxZXlIcymEu7InxDMhdW0KDxpLgoFLcguasxCaJ/SOIZwINatK9KY/tf+ZrlywOKU0UDj3ATXUBfxJXA==}
+ engines: {node: '>=8'}
+ dependencies:
+ ansi-styles: 4.3.0
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ dev: true
+
+ /wrap-ansi/7.0.0:
+ resolution: {integrity: sha512-YVGIj2kamLSTxw6NsZjoBxfSwsn0ycdesmc4p+Q21c5zPuZ1pl+NfxVdxPtdHvmNVOQ6XSYG4AUtyt/Fi7D16Q==}
+ engines: {node: '>=10'}
+ dependencies:
+ ansi-styles: 4.3.0
+ string-width: 4.2.3
+ strip-ansi: 6.0.1
+ dev: true
+
+ /wrappy/1.0.2:
+ resolution: {integrity: sha512-l4Sp/DRseor9wL6EvV2+TuQn63dMkPjZ/sp9XkghTEbV9KlPS1xUsZ3u7/IQO4wxtcFB4bgpQPRcR3QCvezPcQ==}
+ dev: true
+
+ /ws/8.2.3:
+ resolution: {integrity: sha512-wBuoj1BDpC6ZQ1B7DWQBYVLphPWkm8i9Y0/3YdHjHKHiohOJ1ws+3OccDWtH+PoC9DZD5WOTrJvNbWvjS6JWaA==}
+ engines: {node: '>=10.0.0'}
+ peerDependencies:
+ bufferutil: ^4.0.1
+ utf-8-validate: ^5.0.2
+ peerDependenciesMeta:
+ bufferutil:
+ optional: true
+ utf-8-validate:
+ optional: true
+ dev: true
+
+ /xml2js/0.4.23:
+ resolution: {integrity: sha512-ySPiMjM0+pLDftHgXY4By0uswI3SPKLDw/i3UXbnO8M/p28zqexCUoPmQFrYD+/1BzhGJSs2i1ERWKJAtiLrug==}
+ engines: {node: '>=4.0.0'}
+ dependencies:
+ sax: 1.2.4
+ xmlbuilder: 11.0.1
+ dev: true
+
+ /xmlbuilder/11.0.1:
+ resolution: {integrity: sha512-fDlsI/kFEx7gLvbecc0/ohLG50fugQp8ryHzMTuW9vSa1GJ0XYWKnhsUx7oie3G98+r56aTQIUB4kht42R3JvA==}
+ engines: {node: '>=4.0'}
+ dev: true
+
+ /y18n/4.0.3:
+ resolution: {integrity: sha512-JKhqTOwSrqNA1NY5lSztJ1GrBiUodLMmIZuLiDaMRJ+itFd+ABVE8XBjOvIWL+rSqNDC74LCSFmlb/U4UZ4hJQ==}
+ dev: true
+
+ /y18n/5.0.8:
+ resolution: {integrity: sha512-0pfFzegeDWJHJIAmTLRP2DwHjdF5s7jo9tuztdQxAhINCdvS+3nGINqPd00AphqJR/0LhANUS6/+7SCb98YOfA==}
+ engines: {node: '>=10'}
+ dev: true
+
+ /yallist/3.1.1:
+ resolution: {integrity: sha512-a4UGQaWPH59mOXUYnAG2ewncQS4i4F43Tv3JoAM+s2VDAmS9NsK8GpDMLrCHPksFT7h3K6TOoUNn2pb7RoXx4g==}
+ dev: true
+
+ /yallist/4.0.0:
+ resolution: {integrity: sha512-3wdGidZyq5PB084XLES5TpOSRA3wjXAlIWMhum2kRcv/41Sn2emQ0dycQW4uZXLejwKvg6EsvbdlVL+FYEct7A==}
+ dev: true
+
+ /yargs-parser/18.1.3:
+ resolution: {integrity: sha512-o50j0JeToy/4K6OZcaQmW6lyXXKhq7csREXcDwk2omFPJEwUNOVtJKvmDr9EI1fAJZUyZcRF7kxGBWmRXudrCQ==}
+ engines: {node: '>=6'}
+ dependencies:
+ camelcase: 5.3.1
+ decamelize: 1.2.0
+ dev: true
+
+ /yargs-parser/20.2.9:
+ resolution: {integrity: sha512-y11nGElTIV+CT3Zv9t7VKl+Q3hTQoT9a1Qzezhhl6Rp21gJ/IVTW7Z3y9EWXhuUBC2Shnf+DX0antecpAwSP8w==}
+ engines: {node: '>=10'}
+ dev: true
+
+ /yargs-parser/21.1.1:
+ resolution: {integrity: sha512-tVpsJW7DdjecAiFpbIB1e3qxIQsE6NoPc5/eTdrbbIC4h0LVsWhnoa3g+m2HclBIujHzsxZ4VJVA+GUuc2/LBw==}
+ engines: {node: '>=12'}
+ dev: true
+
+ /yargs/15.4.1:
+ resolution: {integrity: sha512-aePbxDmcYW++PaqBsJ+HYUFwCdv4LVvdnhBy78E57PIor8/OVvhMrADFFEDh8DHDFRv/O9i3lPhsENjO7QX0+A==}
+ engines: {node: '>=8'}
+ dependencies:
+ cliui: 6.0.0
+ decamelize: 1.2.0
+ find-up: 4.1.0
+ get-caller-file: 2.0.5
+ require-directory: 2.1.1
+ require-main-filename: 2.0.0
+ set-blocking: 2.0.0
+ string-width: 4.2.3
+ which-module: 2.0.0
+ y18n: 4.0.3
+ yargs-parser: 18.1.3
+ dev: true
+
+ /yargs/16.2.0:
+ resolution: {integrity: sha512-D1mvvtDG0L5ft/jGWkLpG1+m0eQxOfaBvTNELraWj22wSVUMWxZUvYgJYcKh6jGGIkJFhH4IZPQhR4TKpc8mBw==}
+ engines: {node: '>=10'}
+ dependencies:
+ cliui: 7.0.4
+ escalade: 3.1.1
+ get-caller-file: 2.0.5
+ require-directory: 2.1.1
+ string-width: 4.2.3
+ y18n: 5.0.8
+ yargs-parser: 20.2.9
+ dev: true
+
+ /yargs/17.6.2:
+ resolution: {integrity: sha512-1/9UrdHjDZc0eOU0HxOHoS78C69UD3JRMvzlJ7S79S2nTaWRA/whGCTV8o9e/N/1Va9YIV7Q4sOxD8VV4pCWOw==}
+ engines: {node: '>=12'}
+ dependencies:
+ cliui: 8.0.1
+ escalade: 3.1.1
+ get-caller-file: 2.0.5
+ require-directory: 2.1.1
+ string-width: 4.2.3
+ y18n: 5.0.8
+ yargs-parser: 21.1.1
+ dev: true
+
+ /yauzl/2.10.0:
+ resolution: {integrity: sha512-p4a9I6X6nu6IhoGmBqAcbJy1mlC4j27vEPZX9F4L4/vZT3Lyq1VkFHw/V/PUcB9Buo+DG3iHkT0x3Qya58zc3g==}
+ dependencies:
+ buffer-crc32: 0.2.13
+ fd-slicer: 1.1.0
+ dev: true
+
+ /zone.js/0.11.8:
+ resolution: {integrity: sha512-82bctBg2hKcEJ21humWIkXRlLBBmrc3nN7DFh5LGGhcyycO2S7FN8NmdvlcKaGFDNVL4/9kFLmwmInTavdJERA==}
+ dependencies:
+ tslib: 2.4.1
+ dev: true
diff --git a/scouting/testing/BUILD b/scouting/testing/BUILD
index 7e26763..7f0b0dd 100644
--- a/scouting/testing/BUILD
+++ b/scouting/testing/BUILD
@@ -8,6 +8,7 @@
"//scouting",
"//scouting/db/testdb_server",
"//scouting/scraping:test_data",
+ "@rules_python//python/runfiles",
],
visibility = ["//visibility:public"],
)
diff --git a/scouting/testing/scouting_test_servers.py b/scouting/testing/scouting_test_servers.py
index 9df23c1..d1e4e32 100644
--- a/scouting/testing/scouting_test_servers.py
+++ b/scouting/testing/scouting_test_servers.py
@@ -18,6 +18,10 @@
import time
from typing import List
+from rules_python.python.runfiles import runfiles
+
+RUNFILES = runfiles.Create()
+
def wait_for_server(port: int):
"""Waits for the server at the specified port to respond to TCP connections."""
@@ -59,15 +63,22 @@
tba_api_dir = tmpdir / "api" / "v3" / "event" / f"{year}{event_code}"
tba_api_dir.mkdir(parents=True, exist_ok=True)
(tba_api_dir / "matches").write_text(
- Path(f"scouting/scraping/test_data/{year}_{event_code}.json").
- read_text())
+ Path(
+ RUNFILES.Rlocation(
+ f"org_frc971/scouting/scraping/test_data/{year}_{event_code}.json"
+ )).read_text())
class Runner:
"""Helps manage the services we need for testing the scouting app."""
- def start(self, port: int):
- """Starts the services needed for testing the scouting app."""
+ def start(self, port: int, notify_fd: int = 0):
+ """Starts the services needed for testing the scouting app.
+
+ if notify_fd is set to a non-zero value, the string "READY" is written
+ to that file descriptor once everything is set up.
+ """
+
self.tmpdir = Path(os.environ["TEST_TMPDIR"]) / "servers"
self.tmpdir.mkdir(exist_ok=True)
@@ -76,12 +87,15 @@
# The database needs to be running and addressable before the scouting
# webserver can start.
- self.testdb_server = subprocess.Popen(
- ["scouting/db/testdb_server/testdb_server_/testdb_server"])
+ self.testdb_server = subprocess.Popen([
+ RUNFILES.Rlocation(
+ "org_frc971/scouting/db/testdb_server/testdb_server_/testdb_server"
+ )
+ ])
wait_for_server(5432)
self.webserver = subprocess.Popen([
- "scouting/scouting",
+ RUNFILES.Rlocation("org_frc971/scouting/scouting"),
f"--port={port}",
f"--db_config={db_config}",
f"--tba_config={tba_config}",
@@ -99,6 +113,10 @@
wait_for_server(7000)
wait_for_server(port)
+ if notify_fd:
+ with os.fdopen(notify_fd, "w") as file:
+ file.write("READY")
+
def stop(self):
"""Stops the services needed for testing the scouting app."""
servers = (self.webserver, self.testdb_server, self.fake_tba_api)
@@ -127,10 +145,17 @@
parser.add_argument("--port",
type=int,
help="The port for the actual web server.")
+ parser.add_argument(
+ "--notify_fd",
+ type=int,
+ default=0,
+ help=("If non-zero, indicates a file descriptor to which 'READY' is "
+ "written when everything has started up."),
+ )
args = parser.parse_args(argv[1:])
runner = Runner()
- runner.start(args.port)
+ runner.start(args.port, args.notify_fd)
# Wait until we're asked to shut down via CTRL-C or SIGTERM.
signal.signal(signal.SIGINT, discard_signal)
diff --git a/y2018/BUILD b/y2018/BUILD
index ac59493..8feaac4 100644
--- a/y2018/BUILD
+++ b/y2018/BUILD
@@ -57,9 +57,10 @@
"//aos/network:team_number",
"//aos/stl_mutex",
"//frc971:constants",
+ "//frc971/control_loops/double_jointed_arm:dynamics",
"//frc971/shooter_interpolation:interpolation",
"//y2018/control_loops/drivetrain:polydrivetrain_plants",
- "//y2018/control_loops/superstructure/arm:dynamics",
+ "//y2018/control_loops/superstructure/arm:arm_constants",
"//y2018/control_loops/superstructure/intake:intake_plants",
"@com_github_google_glog//:glog",
],
diff --git a/y2018/constants.h b/y2018/constants.h
index 16f1f8c..2a6f0ac 100644
--- a/y2018/constants.h
+++ b/y2018/constants.h
@@ -6,7 +6,8 @@
#include "frc971/constants.h"
#include "y2018/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "y2018/control_loops/superstructure/arm/arm_constants.h"
#include "y2018/control_loops/superstructure/intake/intake_plant.h"
namespace y2018 {
@@ -49,8 +50,8 @@
return (12.0 / 60.0) * (18.0 / 84.0);
}
static constexpr double kMaxProximalEncoderPulsesPerSecond() {
- return control_loops::superstructure::arm::Dynamics::kFreeSpeed /
- (2.0 * M_PI) / control_loops::superstructure::arm::Dynamics::kG1 /
+ return control_loops::superstructure::arm::kArmConstants.free_speed /
+ (2.0 * M_PI) / control_loops::superstructure::arm::kArmConstants.g1 /
kProximalEncoderRatio() * kProximalEncoderCountsPerRevolution();
}
static constexpr double kProximalPotRatio() { return (12.0 / 60.0); }
@@ -58,8 +59,8 @@
static constexpr double kDistalEncoderCountsPerRevolution() { return 4096.0; }
static constexpr double kDistalEncoderRatio() { return (12.0 / 60.0); }
static constexpr double kMaxDistalEncoderPulsesPerSecond() {
- return control_loops::superstructure::arm::Dynamics::kFreeSpeed /
- (2.0 * M_PI) / control_loops::superstructure::arm::Dynamics::kG2 /
+ return control_loops::superstructure::arm::kArmConstants.free_speed /
+ (2.0 * M_PI) / control_loops::superstructure::arm::kArmConstants.g2 /
kDistalEncoderRatio() * kProximalEncoderCountsPerRevolution();
}
static constexpr double kDistalPotRatio() {
diff --git a/y2018/control_loops/python/graph_codegen.py b/y2018/control_loops/python/graph_codegen.py
index e7f8ce1..be267de 100644
--- a/y2018/control_loops/python/graph_codegen.py
+++ b/y2018/control_loops/python/graph_codegen.py
@@ -27,12 +27,12 @@
cc_file.append(" %s," % (alpha_unitizer))
if reverse:
cc_file.append(
- " Trajectory(Path::Reversed(%s()), 0.005));"
+ " Trajectory(dynamics, Path::Reversed(%s()), 0.005));"
% (path_function_name(str(name))))
else:
cc_file.append(
- " Trajectory(%s(), 0.005));" %
- (path_function_name(str(name))))
+ " Trajectory(dynamics, %s(), 0.005));"
+ % (path_function_name(str(name))))
start_index = None
end_index = None
@@ -68,9 +68,14 @@
cc_file.append("#include <memory>")
cc_file.append("")
cc_file.append(
- "#include \"y2018/control_loops/superstructure/arm/trajectory.h\"")
+ "#include \"frc971/control_loops/double_jointed_arm/trajectory.h\"")
cc_file.append(
- "#include \"y2018/control_loops/superstructure/arm/graph.h\"")
+ "#include \"frc971/control_loops/double_jointed_arm/graph.h\"")
+
+ cc_file.append("using frc971::control_loops::arm::Trajectory;")
+ cc_file.append("using frc971::control_loops::arm::Path;")
+ cc_file.append("using frc971::control_loops::arm::SearchGraph;")
+
cc_file.append("")
cc_file.append("namespace y2018 {")
cc_file.append("namespace control_loops {")
@@ -86,15 +91,21 @@
h_file.append("#include <memory>")
h_file.append("")
h_file.append(
- "#include \"y2018/control_loops/superstructure/arm/trajectory.h\"")
+ "#include \"frc971/control_loops/double_jointed_arm/trajectory.h\"")
h_file.append(
- "#include \"y2018/control_loops/superstructure/arm/graph.h\"")
+ "#include \"frc971/control_loops/double_jointed_arm/graph.h\"")
+ h_file.append(
+ "#include \"frc971/control_loops/double_jointed_arm/dynamics.h\"")
h_file.append("")
h_file.append("namespace y2018 {")
h_file.append("namespace control_loops {")
h_file.append("namespace superstructure {")
h_file.append("namespace arm {")
+ h_file.append("using frc971::control_loops::arm::Trajectory;")
+ h_file.append("using frc971::control_loops::arm::Path;")
+ h_file.append("using frc971::control_loops::arm::SearchGraph;")
+
h_file.append("")
h_file.append("struct TrajectoryAndParams {")
h_file.append(" TrajectoryAndParams(double new_vmax,")
@@ -182,11 +193,13 @@
h_file.append("")
h_file.append("// Builds a search graph.")
h_file.append("SearchGraph MakeSearchGraph("
+ "const frc971::control_loops::arm::Dynamics *dynamics, "
"::std::vector<TrajectoryAndParams> *trajectories,")
h_file.append(" "
"const ::Eigen::Matrix<double, 2, 2> &alpha_unitizer,")
h_file.append(" double vmax);")
cc_file.append("SearchGraph MakeSearchGraph("
+ "const frc971::control_loops::arm::Dynamics *dynamics, "
"::std::vector<TrajectoryAndParams> *trajectories,")
cc_file.append(" "
"const ::Eigen::Matrix<double, 2, 2> &alpha_unitizer,")
diff --git a/y2018/control_loops/superstructure/BUILD b/y2018/control_loops/superstructure/BUILD
index 567810d..a3cb808 100644
--- a/y2018/control_loops/superstructure/BUILD
+++ b/y2018/control_loops/superstructure/BUILD
@@ -94,6 +94,7 @@
"//frc971/control_loops:control_loop_test",
"//frc971/control_loops:position_sensor_sim",
"//frc971/control_loops:team_number_test_environment",
+ "//y2018/control_loops/superstructure/arm:arm_constants",
"//y2018/control_loops/superstructure/intake:intake_plants",
],
)
diff --git a/y2018/control_loops/superstructure/arm/BUILD b/y2018/control_loops/superstructure/arm/BUILD
index f90cc92..9f969ff 100644
--- a/y2018/control_loops/superstructure/arm/BUILD
+++ b/y2018/control_loops/superstructure/arm/BUILD
@@ -1,128 +1,4 @@
cc_library(
- name = "trajectory",
- srcs = [
- "trajectory.cc",
- ],
- hdrs = [
- "trajectory.h",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- visibility = ["//visibility:public"],
- deps = [
- ":dynamics",
- "//aos/logging",
- "//frc971/control_loops:dlqr",
- "//frc971/control_loops:jacobian",
- "@org_tuxfamily_eigen//:eigen",
- ],
-)
-
-cc_test(
- name = "trajectory_test",
- srcs = [
- "trajectory_test.cc",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- deps = [
- ":demo_path",
- ":dynamics",
- ":ekf",
- ":trajectory",
- "//aos/testing:googletest",
- "@org_tuxfamily_eigen//:eigen",
- ],
-)
-
-cc_library(
- name = "dynamics",
- srcs = [
- "dynamics.cc",
- ],
- hdrs = [
- "dynamics.h",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- visibility = ["//visibility:public"],
- deps = [
- "//frc971/control_loops:runge_kutta",
- "@com_github_gflags_gflags//:gflags",
- "@org_tuxfamily_eigen//:eigen",
- ],
-)
-
-cc_library(
- name = "demo_path",
- srcs = [
- "demo_path.cc",
- ],
- hdrs = ["demo_path.h"],
- target_compatible_with = ["@platforms//os:linux"],
- deps = [":trajectory"],
-)
-
-cc_test(
- name = "dynamics_test",
- srcs = [
- "dynamics_test.cc",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- deps = [
- ":dynamics",
- "//aos/testing:googletest",
- ],
-)
-
-cc_binary(
- name = "trajectory_plot",
- srcs = [
- "trajectory_plot.cc",
- ],
- target_compatible_with = ["@platforms//cpu:x86_64"],
- deps = [
- ":ekf",
- ":generated_graph",
- ":trajectory",
- "//frc971/analysis:in_process_plotter",
- "@com_github_gflags_gflags//:gflags",
- "@org_tuxfamily_eigen//:eigen",
- ],
-)
-
-cc_library(
- name = "ekf",
- srcs = [
- "ekf.cc",
- ],
- hdrs = [
- "ekf.h",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- visibility = ["//visibility:public"],
- deps = [
- ":dynamics",
- "//frc971/control_loops:jacobian",
- "@org_tuxfamily_eigen//:eigen",
- ],
-)
-
-cc_library(
- name = "graph",
- srcs = ["graph.cc"],
- hdrs = ["graph.h"],
- target_compatible_with = ["@platforms//os:linux"],
-)
-
-cc_test(
- name = "graph_test",
- srcs = ["graph_test.cc"],
- target_compatible_with = ["@platforms//os:linux"],
- deps = [
- ":graph",
- "//aos/testing:googletest",
- ],
-)
-
-cc_library(
name = "arm",
srcs = [
"arm.cc",
@@ -133,15 +9,16 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- ":demo_path",
- ":ekf",
":generated_graph",
- ":graph",
- ":trajectory",
+ "//frc971/control_loops/double_jointed_arm:demo_path",
+ "//frc971/control_loops/double_jointed_arm:ekf",
+ "//frc971/control_loops/double_jointed_arm:graph",
+ "//frc971/control_loops/double_jointed_arm:trajectory",
"//frc971/zeroing",
"//y2018:constants",
"//y2018/control_loops/superstructure:superstructure_position_fbs",
"//y2018/control_loops/superstructure:superstructure_status_fbs",
+ "//y2018/control_loops/superstructure/arm:arm_constants",
],
)
@@ -170,7 +47,35 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- ":graph",
- ":trajectory",
+ ":arm_constants",
+ "//frc971/control_loops/double_jointed_arm:graph",
+ "//frc971/control_loops/double_jointed_arm:trajectory",
+ ],
+)
+
+cc_library(
+ name = "arm_constants",
+ hdrs = ["arm_constants.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops/double_jointed_arm:dynamics",
+ ],
+)
+
+cc_binary(
+ name = "trajectory_plot",
+ srcs = [
+ "trajectory_plot.cc",
+ ],
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ ":arm_constants",
+ ":generated_graph",
+ "//frc971/analysis:in_process_plotter",
+ "//frc971/control_loops/double_jointed_arm:ekf",
+ "//frc971/control_loops/double_jointed_arm:trajectory",
+ "@com_github_gflags_gflags//:gflags",
+ "@org_tuxfamily_eigen//:eigen",
],
)
diff --git a/y2018/control_loops/superstructure/arm/arm.cc b/y2018/control_loops/superstructure/arm/arm.cc
index 1c29157..ab5deea 100644
--- a/y2018/control_loops/superstructure/arm/arm.cc
+++ b/y2018/control_loops/superstructure/arm/arm.cc
@@ -5,8 +5,9 @@
#include "aos/logging/logging.h"
#include "y2018/constants.h"
-#include "y2018/control_loops/superstructure/arm/demo_path.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/demo_path.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "y2018/control_loops/superstructure/arm/arm_constants.h"
#include "y2018/control_loops/superstructure/arm/generated_graph.h"
namespace y2018 {
@@ -29,9 +30,12 @@
alpha_unitizer_((::Eigen::Matrix<double, 2, 2>() << 1.0 / kAlpha0Max(),
0.0, 0.0, 1.0 / kAlpha1Max())
.finished()),
- search_graph_(MakeSearchGraph(&trajectories_, alpha_unitizer_, kVMax())),
+ dynamics_(kArmConstants),
+ search_graph_(MakeSearchGraph(&dynamics_, &trajectories_, alpha_unitizer_,
+ kVMax())),
+ arm_ekf_(&dynamics_),
// Go to the start of the first trajectory.
- follower_(ReadyAboveBoxPoint()),
+ follower_(&dynamics_, ReadyAboveBoxPoint()),
points_(PointList()) {
int i = 0;
for (const auto &trajectory : trajectories_) {
diff --git a/y2018/control_loops/superstructure/arm/arm.h b/y2018/control_loops/superstructure/arm/arm.h
index 7ceb001..51d6c4d 100644
--- a/y2018/control_loops/superstructure/arm/arm.h
+++ b/y2018/control_loops/superstructure/arm/arm.h
@@ -4,14 +4,17 @@
#include "aos/time/time.h"
#include "frc971/zeroing/zeroing.h"
#include "y2018/constants.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
-#include "y2018/control_loops/superstructure/arm/ekf.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/ekf.h"
#include "y2018/control_loops/superstructure/arm/generated_graph.h"
-#include "y2018/control_loops/superstructure/arm/graph.h"
-#include "y2018/control_loops/superstructure/arm/trajectory.h"
+#include "frc971/control_loops/double_jointed_arm/graph.h"
+#include "frc971/control_loops/double_jointed_arm/trajectory.h"
#include "y2018/control_loops/superstructure/superstructure_position_generated.h"
#include "y2018/control_loops/superstructure/superstructure_status_generated.h"
+using frc971::control_loops::arm::TrajectoryFollower;
+using frc971::control_loops::arm::EKF;
+
namespace y2018 {
namespace control_loops {
namespace superstructure {
@@ -114,6 +117,8 @@
double vmax_ = kVMax();
+ frc971::control_loops::arm::Dynamics dynamics_;
+
::std::vector<TrajectoryAndParams> trajectories_;
SearchGraph search_graph_;
diff --git a/y2018/control_loops/superstructure/arm/arm_constants.h b/y2018/control_loops/superstructure/arm/arm_constants.h
new file mode 100644
index 0000000..9ac7020
--- /dev/null
+++ b/y2018/control_loops/superstructure/arm/arm_constants.h
@@ -0,0 +1,53 @@
+#ifndef Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_CONSTANTS_H_
+#define Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_CONSTANTS_H_
+
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+
+namespace y2018 {
+namespace control_loops {
+namespace superstructure {
+namespace arm {
+
+constexpr double kEfficiencyTweak = 0.95;
+constexpr double kStallTorque = 1.41 * kEfficiencyTweak;
+constexpr double kFreeSpeed = (5840.0 / 60.0) * 2.0 * M_PI;
+constexpr double kStallCurrent = 89.0;
+
+constexpr ::frc971::control_loops::arm::ArmConstants kArmConstants = {
+ .l1 = 46.25 * 0.0254,
+ .l2 = 41.80 * 0.0254,
+ .m1 = 9.34 / 2.2,
+ .m2 = 9.77 / 2.2,
+
+ // Moment of inertia of the joints in kg m^2
+ .j1 = 2957.05 * 0.0002932545454545454,
+ .j2 = 2824.70 * 0.0002932545454545454,
+
+ // Radius of the center of mass of the joints in meters.
+ .r1 = 21.64 * 0.0254,
+ .r2 = 26.70 * 0.0254,
+
+ // Gear ratios for the two joints.
+ .g1 = 140.0,
+ .g2 = 90.0,
+
+ // MiniCIM motor constants.
+ .efficiency_tweak = kEfficiencyTweak,
+ .stall_torque = kStallTorque,
+ .free_speed = kFreeSpeed,
+ .stall_current = kStallCurrent,
+ .resistance = 12.0 / kStallCurrent,
+ .Kv = kFreeSpeed / 12.0,
+ .Kt = kStallTorque / kStallCurrent,
+
+ // Number of motors on the distal joint.
+ .num_distal_motors = 2.0,
+};
+
+
+} // namespace arm
+} // namespace superstructure
+} // namespace control_loops
+} // namespace y2018
+
+#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_CONSTANTS_H_
diff --git a/y2018/control_loops/superstructure/arm/demo_path.h b/y2018/control_loops/superstructure/arm/demo_path.h
deleted file mode 100644
index 0c18103..0000000
--- a/y2018/control_loops/superstructure/arm/demo_path.h
+++ /dev/null
@@ -1,21 +0,0 @@
-#ifndef Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_DEMO_PATH_H_
-#define Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_DEMO_PATH_H_
-
-#include <memory>
-
-#include "y2018/control_loops/superstructure/arm/trajectory.h"
-
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
-
-::std::unique_ptr<Path> MakeDemoPath();
-::std::unique_ptr<Path> MakeReversedDemoPath();
-
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
-
-#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_DEMO_PATH_H_
diff --git a/y2018/control_loops/superstructure/arm/dynamics.cc b/y2018/control_loops/superstructure/arm/dynamics.cc
deleted file mode 100644
index 02a2861..0000000
--- a/y2018/control_loops/superstructure/arm/dynamics.cc
+++ /dev/null
@@ -1,35 +0,0 @@
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
-
-DEFINE_bool(gravity, true, "If true, enable gravity.");
-
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
-
-const ::Eigen::Matrix<double, 2, 2> Dynamics::K3 =
- (::Eigen::Matrix<double, 2, 2>()
- << Dynamics::kG1 * Dynamics::Kt / Dynamics::kResistance,
- 0.0, 0.0, Dynamics::kG2 *Dynamics::kNumDistalMotors *Dynamics::Kt /
- Dynamics::kResistance)
- .finished();
-
-const ::Eigen::Matrix<double, 2, 2> Dynamics::K3_inverse = K3.inverse();
-
-const ::Eigen::Matrix<double, 2, 2> Dynamics::K4 =
- (::Eigen::Matrix<double, 2, 2>()
- << Dynamics::kG1 * Dynamics::kG1 * Dynamics::Kt /
- (Dynamics::Kv * Dynamics::kResistance),
- 0.0, 0.0,
- Dynamics::kG2 *Dynamics::kG2 *Dynamics::Kt *Dynamics::kNumDistalMotors /
- (Dynamics::Kv * Dynamics::kResistance))
- .finished();
-
-constexpr double Dynamics::kAlpha;
-constexpr double Dynamics::kBeta;
-constexpr double Dynamics::kGamma;
-
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
diff --git a/y2018/control_loops/superstructure/arm/dynamics.h b/y2018/control_loops/superstructure/arm/dynamics.h
deleted file mode 100644
index b1ebc97..0000000
--- a/y2018/control_loops/superstructure/arm/dynamics.h
+++ /dev/null
@@ -1,189 +0,0 @@
-#ifndef Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_DYNAMICS_H_
-#define Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_DYNAMICS_H_
-
-#include "Eigen/Dense"
-
-#include "frc971/control_loops/runge_kutta.h"
-#include "gflags/gflags.h"
-
-DECLARE_bool(gravity);
-
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
-
-// This class captures the dynamics of our system. It doesn't actually need to
-// store state yet, so everything can be constexpr and/or static.
-class Dynamics {
- public:
- // Below, 1 refers to the proximal joint, and 2 refers to the distal joint.
- // Length of the joints in meters.
- static constexpr double kL1 = 46.25 * 0.0254;
- static constexpr double kL2 = 41.80 * 0.0254;
-
- // Mass of the joints in kilograms.
- static constexpr double kM1 = 9.34 / 2.2;
- static constexpr double kM2 = 9.77 / 2.2;
-
- // Moment of inertia of the joints in kg m^2
- static constexpr double kJ1 = 2957.05 * 0.0002932545454545454;
- static constexpr double kJ2 = 2824.70 * 0.0002932545454545454;
-
- // Radius of the center of mass of the joints in meters.
- static constexpr double r1 = 21.64 * 0.0254;
- static constexpr double r2 = 26.70 * 0.0254;
-
- // Gear ratios for the two joints.
- static constexpr double kG1 = 140.0;
- static constexpr double kG2 = 90.0;
-
- // MiniCIM motor constants.
- static constexpr double kEfficiencyTweak = 0.95;
- static constexpr double kStallTorque = 1.41 * kEfficiencyTweak;
- static constexpr double kFreeSpeed = (5840.0 / 60.0) * 2.0 * M_PI;
- static constexpr double kStallCurrent = 89.0;
- static constexpr double kResistance = 12.0 / kStallCurrent;
- static constexpr double Kv = kFreeSpeed / 12.0;
- static constexpr double Kt = kStallTorque / kStallCurrent;
-
- // Number of motors on the distal joint.
- static constexpr double kNumDistalMotors = 2.0;
-
- static constexpr double kAlpha = kJ1 + r1 * r1 * kM1 + kL1 * kL1 * kM2;
- static constexpr double kBeta = kL1 * r2 * kM2;
- static constexpr double kGamma = kJ2 + r2 * r2 * kM2;
-
- // K3, K4 matricies described below.
- static const ::Eigen::Matrix<double, 2, 2> K3;
- static const ::Eigen::Matrix<double, 2, 2> K3_inverse;
- static const ::Eigen::Matrix<double, 2, 2> K4;
-
- // Generates K1-2 for the arm ODE.
- // K1 * d^2 theta / dt^2 + K2 * d theta / dt = K3 * V - K4 * d theta/dt
- // These matricies are missing the velocity factor for K2[1, 0], and K2[0, 1].
- // You probbaly want MatriciesForState.
- static void NormilizedMatriciesForState(
- const ::Eigen::Matrix<double, 4, 1> &X,
- ::Eigen::Matrix<double, 2, 2> *K1_result,
- ::Eigen::Matrix<double, 2, 2> *K2_result) {
- const double angle = X(0, 0) - X(2, 0);
- const double s = ::std::sin(angle);
- const double c = ::std::cos(angle);
- *K1_result << kAlpha, c * kBeta, c * kBeta, kGamma;
- *K2_result << 0.0, s * kBeta, -s * kBeta, 0.0;
- }
-
- // Generates K1-2 for the arm ODE.
- // K1 * d^2 theta / dt^2 + K2 * d theta / dt = K3 * V - K4 * d theta/dt
- static void MatriciesForState(const ::Eigen::Matrix<double, 4, 1> &X,
- ::Eigen::Matrix<double, 2, 2> *K1_result,
- ::Eigen::Matrix<double, 2, 2> *K2_result) {
- NormilizedMatriciesForState(X, K1_result, K2_result);
- (*K2_result)(1, 0) *= X(1, 0);
- (*K2_result)(0, 1) *= X(3, 0);
- }
-
- // TODO(austin): We may want a way to provide K1 and K2 to save CPU cycles.
-
- // Calculates the acceleration given the current state and control input.
- static const ::Eigen::Matrix<double, 4, 1> Acceleration(
- const ::Eigen::Matrix<double, 4, 1> &X,
- const ::Eigen::Matrix<double, 2, 1> &U) {
- ::Eigen::Matrix<double, 2, 2> K1;
- ::Eigen::Matrix<double, 2, 2> K2;
-
- MatriciesForState(X, &K1, &K2);
-
- const ::Eigen::Matrix<double, 2, 1> velocity =
- (::Eigen::Matrix<double, 2, 1>() << X(1, 0), X(3, 0)).finished();
-
- const ::Eigen::Matrix<double, 2, 1> torque = K3 * U - K4 * velocity;
- const ::Eigen::Matrix<double, 2, 1> gravity_torque = GravityTorque(X);
-
- const ::Eigen::Matrix<double, 2, 1> accel =
- K1.inverse() * (torque + gravity_torque - K2 * velocity);
-
- return (::Eigen::Matrix<double, 4, 1>() << X(1, 0), accel(0, 0), X(3, 0),
- accel(1, 0))
- .finished();
- }
-
- // Calculates the acceleration given the current augmented kalman filter state
- // and control input.
- static const ::Eigen::Matrix<double, 6, 1> EKFAcceleration(
- const ::Eigen::Matrix<double, 6, 1> &X,
- const ::Eigen::Matrix<double, 2, 1> &U) {
- ::Eigen::Matrix<double, 2, 2> K1;
- ::Eigen::Matrix<double, 2, 2> K2;
-
- MatriciesForState(X.block<4, 1>(0, 0), &K1, &K2);
-
- const ::Eigen::Matrix<double, 2, 1> velocity =
- (::Eigen::Matrix<double, 2, 1>() << X(1, 0), X(3, 0)).finished();
-
- const ::Eigen::Matrix<double, 2, 1> torque =
- K3 *
- (U +
- (::Eigen::Matrix<double, 2, 1>() << X(4, 0), X(5, 0)).finished()) -
- K4 * velocity;
- const ::Eigen::Matrix<double, 2, 1> gravity_torque =
- GravityTorque(X.block<4, 1>(0, 0));
-
- const ::Eigen::Matrix<double, 2, 1> accel =
- K1.inverse() * (torque + gravity_torque - K2 * velocity);
-
- return (::Eigen::Matrix<double, 6, 1>() << X(1, 0), accel(0, 0), X(3, 0),
- accel(1, 0), 0.0, 0.0)
- .finished();
- }
-
- // Calculates the voltage required to follow the trajectory. This requires
- // knowing the current state, desired angular velocity and acceleration.
- static const ::Eigen::Matrix<double, 2, 1> FF_U(
- const ::Eigen::Matrix<double, 4, 1> &X,
- const ::Eigen::Matrix<double, 2, 1> &omega_t,
- const ::Eigen::Matrix<double, 2, 1> &alpha_t) {
- ::Eigen::Matrix<double, 2, 2> K1;
- ::Eigen::Matrix<double, 2, 2> K2;
-
- MatriciesForState(X, &K1, &K2);
-
- const ::Eigen::Matrix<double, 2, 1> gravity_torque = GravityTorque(X);
-
- return K3_inverse *
- (K1 * alpha_t + K2 * omega_t + K4 * omega_t - gravity_torque);
- }
-
- static ::Eigen::Matrix<double, 2, 1> GravityTorque(
- const ::Eigen::Matrix<double, 4, 1> &X) {
- constexpr double kAccelDueToGravity = 9.8 * kEfficiencyTweak;
- return (::Eigen::Matrix<double, 2, 1>() << (r1 * kM1 + kL1 * kM2) *
- ::std::sin(X(0)) *
- kAccelDueToGravity,
- r2 * kM2 * ::std::sin(X(2)) * kAccelDueToGravity)
- .finished() *
- (FLAGS_gravity ? 1.0 : 0.0);
- }
-
- static const ::Eigen::Matrix<double, 4, 1> UnboundedDiscreteDynamics(
- const ::Eigen::Matrix<double, 4, 1> &X,
- const ::Eigen::Matrix<double, 2, 1> &U, double dt) {
- return ::frc971::control_loops::RungeKuttaU(Dynamics::Acceleration, X, U,
- dt);
- }
-
- static const ::Eigen::Matrix<double, 6, 1> UnboundedEKFDiscreteDynamics(
- const ::Eigen::Matrix<double, 6, 1> &X,
- const ::Eigen::Matrix<double, 2, 1> &U, double dt) {
- return ::frc971::control_loops::RungeKuttaU(Dynamics::EKFAcceleration, X, U,
- dt);
- }
-};
-
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
-
-#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_DYNAMICS_H_
diff --git a/y2018/control_loops/superstructure/arm/dynamics_test.cc b/y2018/control_loops/superstructure/arm/dynamics_test.cc
deleted file mode 100644
index 23e5adc..0000000
--- a/y2018/control_loops/superstructure/arm/dynamics_test.cc
+++ /dev/null
@@ -1,52 +0,0 @@
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
-
-#include "gtest/gtest.h"
-
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
-namespace testing {
-
-// Tests that zero inputs result in no acceleration and no motion.
-// This isn't all that rigerous, but it's a good start.
-TEST(DynamicsTest, Acceleration) {
- Dynamics dynamics;
-
- EXPECT_TRUE(dynamics
- .Acceleration(::Eigen::Matrix<double, 4, 1>::Zero(),
- ::Eigen::Matrix<double, 2, 1>::Zero())
- .isApprox(::Eigen::Matrix<double, 4, 1>::Zero()));
-
- EXPECT_TRUE(dynamics
- .UnboundedDiscreteDynamics(
- ::Eigen::Matrix<double, 4, 1>::Zero(),
- ::Eigen::Matrix<double, 2, 1>::Zero(), 0.1)
- .isApprox(::Eigen::Matrix<double, 4, 1>::Zero()));
-
- const ::Eigen::Matrix<double, 4, 1> X =
- (::Eigen::Matrix<double, 4, 1>() << M_PI / 2.0, 0.0, 0.0, 0.0).finished();
-
- ::std::cout << dynamics.FF_U(X, ::Eigen::Matrix<double, 2, 1>::Zero(),
- ::Eigen::Matrix<double, 2, 1>::Zero())
- << ::std::endl;
-
- ::std::cout << dynamics.UnboundedDiscreteDynamics(
- X, dynamics.FF_U(X, ::Eigen::Matrix<double, 2, 1>::Zero(),
- ::Eigen::Matrix<double, 2, 1>::Zero()),
- 0.01)
- << ::std::endl;
-
- EXPECT_TRUE(dynamics
- .UnboundedDiscreteDynamics(
- X, dynamics.FF_U(X, ::Eigen::Matrix<double, 2, 1>::Zero(),
- ::Eigen::Matrix<double, 2, 1>::Zero()),
- 0.01)
- .isApprox(X));
-}
-
-} // namespace testing
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
diff --git a/y2018/control_loops/superstructure/arm/trajectory_plot.cc b/y2018/control_loops/superstructure/arm/trajectory_plot.cc
index 10b39bc..0cee664 100644
--- a/y2018/control_loops/superstructure/arm/trajectory_plot.cc
+++ b/y2018/control_loops/superstructure/arm/trajectory_plot.cc
@@ -1,10 +1,11 @@
#include "aos/init.h"
#include "frc971/analysis/in_process_plotter.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/ekf.h"
+#include "frc971/control_loops/double_jointed_arm/trajectory.h"
#include "gflags/gflags.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
-#include "y2018/control_loops/superstructure/arm/ekf.h"
+#include "y2018/control_loops/superstructure/arm/arm_constants.h"
#include "y2018/control_loops/superstructure/arm/generated_graph.h"
-#include "y2018/control_loops/superstructure/arm/trajectory.h"
DEFINE_bool(forwards, true, "If true, run the forwards simulation.");
DEFINE_bool(plot, true, "If true, plot");
@@ -16,10 +17,12 @@
namespace arm {
void Main() {
- Trajectory trajectory(FLAGS_forwards
- ? MakeNeutralToFrontHighPath()
- : Path::Reversed(MakeNeutralToFrontHighPath()),
- 0.001);
+ frc971::control_loops::arm::Dynamics dynamics(kArmConstants);
+ frc971::control_loops::arm::Trajectory trajectory(
+ &dynamics,
+ FLAGS_forwards ? MakeNeutralToFrontHighPath()
+ : Path::Reversed(MakeNeutralToFrontHighPath()),
+ 0.001);
constexpr double kAlpha0Max = 30.0;
constexpr double kAlpha1Max = 50.0;
@@ -96,7 +99,7 @@
const ::Eigen::Matrix<double, 6, 1> R = trajectory.R(theta_t, omega_t);
const ::Eigen::Matrix<double, 2, 1> U =
- Dynamics::FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t)
+ dynamics.FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t)
.array()
.max(-20)
.min(20);
@@ -118,7 +121,7 @@
const ::Eigen::Matrix<double, 6, 1> R = trajectory.R(theta_t, omega_t);
const ::Eigen::Matrix<double, 2, 1> U =
- Dynamics::FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t)
+ dynamics.FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t)
.array()
.max(-20)
.min(20);
@@ -140,7 +143,7 @@
const ::Eigen::Matrix<double, 6, 1> R = trajectory.R(theta_t, omega_t);
const ::Eigen::Matrix<double, 2, 1> U =
- Dynamics::FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t)
+ dynamics.FF_U(R.block<4, 1>(0, 0), omega_t, alpha_t)
.array()
.max(-20)
.min(20);
@@ -156,7 +159,8 @@
X << theta_t(0), 0.0, theta_t(1), 0.0;
}
- TrajectoryFollower follower(&trajectory);
+ frc971::control_loops::arm::TrajectoryFollower follower(&dynamics,
+ &trajectory);
::std::vector<double> t_array;
::std::vector<double> theta0_goal_t_array;
@@ -187,7 +191,7 @@
::std::vector<double> torque0_hat_t_array;
::std::vector<double> torque1_hat_t_array;
- EKF arm_ekf;
+ frc971::control_loops::arm::EKF arm_ekf(&dynamics);
arm_ekf.Reset(X);
::std::cout << "Reset P: " << arm_ekf.P_reset() << ::std::endl;
::std::cout << "Stabilized P: " << arm_ekf.P_half_converged() << ::std::endl;
@@ -236,9 +240,9 @@
actual_U(0) += 1.0;
const ::Eigen::Matrix<double, 4, 1> xdot =
- Dynamics::Acceleration(X, actual_U);
+ dynamics.Acceleration(X, actual_U);
- X = Dynamics::UnboundedDiscreteDynamics(X, actual_U, sim_dt);
+ X = dynamics.UnboundedDiscreteDynamics(X, actual_U, sim_dt);
arm_ekf.Predict(follower.U(), sim_dt);
alpha0_t_array.push_back(xdot(1));
@@ -270,10 +274,14 @@
plotter.AddLine(distance_array, alpha0_array, "alpha0");
plotter.AddLine(distance_array, alpha1_array, "alpha1");
- plotter.AddLine(integrated_distance, integrated_theta0_array, "integrated theta0");
- plotter.AddLine(integrated_distance, integrated_theta1_array, "integrated theta1");
- plotter.AddLine(integrated_distance, integrated_omega0_array, "integrated omega0");
- plotter.AddLine(integrated_distance, integrated_omega1_array, "integrated omega1");
+ plotter.AddLine(integrated_distance, integrated_theta0_array,
+ "integrated theta0");
+ plotter.AddLine(integrated_distance, integrated_theta1_array,
+ "integrated theta1");
+ plotter.AddLine(integrated_distance, integrated_omega0_array,
+ "integrated omega0");
+ plotter.AddLine(integrated_distance, integrated_omega1_array,
+ "integrated omega1");
plotter.Publish();
plotter.AddFigure();
diff --git a/y2018/control_loops/superstructure/superstructure_lib_test.cc b/y2018/control_loops/superstructure/superstructure_lib_test.cc
index 285c8c3..54342c5 100644
--- a/y2018/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2018/control_loops/superstructure/superstructure_lib_test.cc
@@ -8,7 +8,8 @@
#include "frc971/control_loops/team_number_test_environment.h"
#include "gtest/gtest.h"
#include "y2018/constants.h"
-#include "y2018/control_loops/superstructure/arm/dynamics.h"
+#include "frc971/control_loops/double_jointed_arm/dynamics.h"
+#include "y2018/control_loops/superstructure/arm/arm_constants.h"
#include "y2018/control_loops/superstructure/arm/generated_graph.h"
#include "y2018/control_loops/superstructure/intake/intake_plant.h"
#include "y2018/control_loops/superstructure/superstructure.h"
@@ -129,7 +130,8 @@
constants::Values::kProximalEncoderRatio()),
distal_zeroing_constants_(distal_zeroing_constants),
distal_pot_encoder_(M_PI * 2.0 *
- constants::Values::kDistalEncoderRatio()) {
+ constants::Values::kDistalEncoderRatio()),
+ dynamics_(arm::kArmConstants) {
X_.setZero();
}
@@ -174,7 +176,7 @@
AOS_CHECK_LE(::std::abs(U(1)), voltage_check);
if (release_arm_brake) {
- X_ = arm::Dynamics::UnboundedDiscreteDynamics(X_, U, 0.00505);
+ X_ = dynamics_.UnboundedDiscreteDynamics(X_, U, 0.00505);
} else {
// Well, the brake shouldn't stop both joints, but this will get the tests
// to pass.
@@ -197,6 +199,8 @@
const ::frc971::constants::PotAndAbsoluteEncoderZeroingConstants
distal_zeroing_constants_;
PositionSensorSimulator distal_pot_encoder_;
+
+ ::frc971::control_loops::arm::Dynamics dynamics_;
};
class SuperstructureSimulation {
diff --git a/y2020/control_loops/drivetrain/localizer_plotter.ts b/y2020/control_loops/drivetrain/localizer_plotter.ts
index b2120ef..03450ef 100644
--- a/y2020/control_loops/drivetrain/localizer_plotter.ts
+++ b/y2020/control_loops/drivetrain/localizer_plotter.ts
@@ -1,10 +1,10 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
-import {MessageHandler, TimestampedMessage} from 'org_frc971/aos/network/www/aos_plotter';
-import {Point} from 'org_frc971/aos/network/www/plotter';
-import {Table} from 'org_frc971/aos/network/www/reflection';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import {Connection} from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import {MessageHandler, TimestampedMessage} from '../../../aos/network/www/aos_plotter';
+import {Point} from '../../../aos/network/www/plotter';
+import {Table} from '../../../aos/network/www/reflection';
import {ByteBuffer} from 'flatbuffers';
import {Schema} from 'flatbuffers_reflection/reflection_generated';
diff --git a/y2020/control_loops/superstructure/accelerator_plotter.ts b/y2020/control_loops/superstructure/accelerator_plotter.ts
index e1bc5bc..a5014dc 100644
--- a/y2020/control_loops/superstructure/accelerator_plotter.ts
+++ b/y2020/control_loops/superstructure/accelerator_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, BLACK} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, BLACK} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2020/control_loops/superstructure/finisher_plotter.ts b/y2020/control_loops/superstructure/finisher_plotter.ts
index f2127f5..9799e2c 100644
--- a/y2020/control_loops/superstructure/finisher_plotter.ts
+++ b/y2020/control_loops/superstructure/finisher_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, BLACK} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, BLACK} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2020/control_loops/superstructure/hood_plotter.ts b/y2020/control_loops/superstructure/hood_plotter.ts
index 55b1ba8..4102464 100644
--- a/y2020/control_loops/superstructure/hood_plotter.ts
+++ b/y2020/control_loops/superstructure/hood_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2020/control_loops/superstructure/turret_plotter.ts b/y2020/control_loops/superstructure/turret_plotter.ts
index 5cb15c6..4de5e1d 100644
--- a/y2020/control_loops/superstructure/turret_plotter.ts
+++ b/y2020/control_loops/superstructure/turret_plotter.ts
@@ -1,11 +1,11 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import * as configuration from 'org_frc971/aos/configuration_generated';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
-import {MessageHandler, TimestampedMessage} from 'org_frc971/aos/network/www/aos_plotter';
-import {Point} from 'org_frc971/aos/network/www/plotter';
-import {Table} from 'org_frc971/aos/network/www/reflection';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import * as configuration from '../../../aos/configuration_generated';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import {MessageHandler, TimestampedMessage} from '../../../aos/network/www/aos_plotter';
+import {Point} from '../../../aos/network/www/plotter';
+import {Table} from '../../../aos/network/www/reflection';
import {ByteBuffer} from 'flatbuffers';
import {Schema} from 'flatbuffers_reflection/reflection_generated';
diff --git a/y2020/www/camera_main.ts b/y2020/www/camera_main.ts
index 58e5bed..2c47cc5 100644
--- a/y2020/www/camera_main.ts
+++ b/y2020/www/camera_main.ts
@@ -1,7 +1,7 @@
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Connection} from '../../aos/network/www/proxy';
import {ImageHandler} from './image_handler';
-import {ConfigHandler} from 'org_frc971/aos/network/www/config_handler';
+import {ConfigHandler} from '../../aos/network/www/config_handler';
const conn = new Connection();
diff --git a/y2020/www/field_main.ts b/y2020/www/field_main.ts
index 7e2e392..d71a45e 100644
--- a/y2020/www/field_main.ts
+++ b/y2020/www/field_main.ts
@@ -1,4 +1,4 @@
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Connection} from '../../aos/network/www/proxy';
import {FieldHandler} from './field_handler';
diff --git a/y2020/www/image_handler.ts b/y2020/www/image_handler.ts
index 856ee8b..07cee10 100644
--- a/y2020/www/image_handler.ts
+++ b/y2020/www/image_handler.ts
@@ -1,8 +1,8 @@
-import {Channel, Configuration} from 'org_frc971/aos/configuration_generated';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Channel, Configuration} from '../../aos/configuration_generated';
+import {Connection} from '../../aos/network/www/proxy';
import {ByteBuffer} from 'flatbuffers';
-import {ImageMatchResult, Feature} from 'org_frc971/y2020/vision/sift/sift_generated'
-import {CameraImage} from 'org_frc971/frc971/vision/vision_generated';
+import {ImageMatchResult, Feature} from '../vision/sift/sift_generated'
+import {CameraImage} from '../../frc971/vision/vision_generated';
export class ImageHandler {
private canvas = document.createElement('canvas');
diff --git a/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts b/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts
index f453d64..4fb397d 100644
--- a/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts
+++ b/y2021_bot3/control_loops/superstructure/superstructure_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2022/control_loops/superstructure/catapult_plotter.ts b/y2022/control_loops/superstructure/catapult_plotter.ts
index 90db40b..579aeff 100644
--- a/y2022/control_loops/superstructure/catapult_plotter.ts
+++ b/y2022/control_loops/superstructure/catapult_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2022/control_loops/superstructure/climber_plotter.ts b/y2022/control_loops/superstructure/climber_plotter.ts
index e24a993..127eb5a 100644
--- a/y2022/control_loops/superstructure/climber_plotter.ts
+++ b/y2022/control_loops/superstructure/climber_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2022/control_loops/superstructure/intake_plotter.ts b/y2022/control_loops/superstructure/intake_plotter.ts
index 8904d8b..d66964d 100644
--- a/y2022/control_loops/superstructure/intake_plotter.ts
+++ b/y2022/control_loops/superstructure/intake_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2022/control_loops/superstructure/superstructure_plotter.ts b/y2022/control_loops/superstructure/superstructure_plotter.ts
index 8590d7b..782353e 100644
--- a/y2022/control_loops/superstructure/superstructure_plotter.ts
+++ b/y2022/control_loops/superstructure/superstructure_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import * as proxy from '../../../aos/network/www/proxy';
import Connection = proxy.Connection;
diff --git a/y2022/control_loops/superstructure/turret_plotter.ts b/y2022/control_loops/superstructure/turret_plotter.ts
index 6753880..c0b5b6f 100644
--- a/y2022/control_loops/superstructure/turret_plotter.ts
+++ b/y2022/control_loops/superstructure/turret_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import * as proxy from '../../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE, ORANGE} from '../../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2022/localizer/localizer_plotter.ts b/y2022/localizer/localizer_plotter.ts
index bcd8894..8344eb8 100644
--- a/y2022/localizer/localizer_plotter.ts
+++ b/y2022/localizer/localizer_plotter.ts
@@ -1,8 +1,8 @@
// Provides a plot for debugging drivetrain-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {ImuMessageHandler} from 'org_frc971/frc971/wpilib/imu_plot_utils';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import {AosPlotter} from '../../aos/network/www/aos_plotter';
+import {ImuMessageHandler} from '../../frc971/wpilib/imu_plot_utils';
+import * as proxy from '../../aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../aos/network/www/colors';
import Connection = proxy.Connection;
diff --git a/y2022/vision/vision_plotter.ts b/y2022/vision/vision_plotter.ts
index adbf900..d557a36 100644
--- a/y2022/vision/vision_plotter.ts
+++ b/y2022/vision/vision_plotter.ts
@@ -1,11 +1,11 @@
import {ByteBuffer} from 'flatbuffers';
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {MessageHandler, TimestampedMessage} from 'org_frc971/aos/network/www/aos_plotter';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
-import {Connection} from 'org_frc971/aos/network/www/proxy';
-import {Table} from 'org_frc971/aos/network/www/reflection';
+import {AosPlotter} from '../../aos/network/www/aos_plotter';
+import {MessageHandler, TimestampedMessage} from '../../aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../aos/network/www/colors';
+import {Connection} from '../../aos/network/www/proxy';
+import {Table} from '../../aos/network/www/reflection';
import {Schema} from 'flatbuffers_reflection/reflection_generated';
-import {TargetEstimate} from 'org_frc971/y2022/vision/target_estimate_generated';
+import {TargetEstimate} from './target_estimate_generated';
const TIME = AosPlotter.TIME;
diff --git a/y2022/www/field_main.ts b/y2022/www/field_main.ts
index 7e2e392..d71a45e 100644
--- a/y2022/www/field_main.ts
+++ b/y2022/www/field_main.ts
@@ -1,4 +1,4 @@
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Connection} from '../../aos/network/www/proxy';
import {FieldHandler} from './field_handler';
diff --git a/y2023/BUILD b/y2023/BUILD
index c060688..32965ae 100644
--- a/y2023/BUILD
+++ b/y2023/BUILD
@@ -3,6 +3,35 @@
load("//tools/build_rules:template.bzl", "jinja2_template")
robot_downloader(
+ binaries = [
+ "//aos/network:web_proxy_main",
+ "//aos/events/logging:log_cat",
+ ],
+ data = [
+ ":aos_config",
+ "@ctre_phoenix_api_cpp_athena//:shared_libraries",
+ "@ctre_phoenix_cci_athena//:shared_libraries",
+ "@ctre_phoenixpro_api_cpp_athena//:shared_libraries",
+ "@ctre_phoenixpro_tools_athena//:shared_libraries",
+ ],
+ dirs = [
+ "//y2023/www:www_files",
+ ],
+ start_binaries = [
+ "//aos/events/logging:logger_main",
+ "//aos/network:web_proxy_main",
+ ":joystick_reader",
+ ":wpilib_interface",
+ "//aos/network:message_bridge_client",
+ "//aos/network:message_bridge_server",
+ "//y2023/control_loops/drivetrain:drivetrain",
+ "//y2023/control_loops/drivetrain:trajectory_generator",
+ "//y2023/control_loops/superstructure:superstructure",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+robot_downloader(
name = "pi_download",
binaries = [
"//frc971/vision:intrinsics_calibration",
@@ -148,6 +177,7 @@
"//aos/network:timestamp_fbs",
"//y2019/control_loops/drivetrain:target_selector_fbs",
"//y2023/control_loops/superstructure:superstructure_goal_fbs",
+ "//y2023/control_loops/drivetrain:drivetrain_can_position_fbs",
"//y2023/control_loops/superstructure:superstructure_output_fbs",
"//y2023/control_loops/superstructure:superstructure_position_fbs",
"//y2023/control_loops/superstructure:superstructure_status_fbs",
@@ -204,6 +234,7 @@
":constants",
"//aos:init",
"//aos:math",
+ "//aos/containers:sized_array",
"//aos/events:shm_event_loop",
"//aos/logging",
"//aos/stl_mutex",
@@ -230,7 +261,9 @@
"//frc971/wpilib:wpilib_interface",
"//frc971/wpilib:wpilib_robot_base",
"//third_party:phoenix",
+ "//third_party:phoenixpro",
"//third_party:wpilib",
+ "//y2023/control_loops/drivetrain:drivetrain_can_position_fbs",
"//y2023/control_loops/superstructure:superstructure_output_fbs",
"//y2023/control_loops/superstructure:superstructure_position_fbs",
],
diff --git a/y2023/constants.h b/y2023/constants.h
index 03a6cae..edcb794 100644
--- a/y2023/constants.h
+++ b/y2023/constants.h
@@ -20,6 +20,10 @@
struct Values {
static const int kZeroingSampleSize = 200;
+ static const int kDrivetrainWriterPriority = 35;
+ static const int kDrivetrainTxPriority = 36;
+ static const int kDrivetrainRxPriority = 36;
+
static constexpr double kDrivetrainCyclesPerRevolution() { return 512.0; }
static constexpr double kDrivetrainEncoderCountsPerRevolution() {
return kDrivetrainCyclesPerRevolution() * 4;
@@ -32,6 +36,9 @@
kDrivetrainEncoderCountsPerRevolution();
}
+ static constexpr double kDrivetrainSupplyCurrentLimit() { return 35.0; }
+ static constexpr double kDrivetrainStatorCurrentLimit() { return 40.0; }
+
static double DrivetrainEncoderToMeters(int32_t in) {
return ((static_cast<double>(in) /
kDrivetrainEncoderCountsPerRevolution()) *
@@ -39,6 +46,12 @@
kDrivetrainEncoderRatio() * control_loops::drivetrain::kWheelRadius;
}
+ static double DrivetrainCANEncoderToMeters(double rotations) {
+ return (rotations * (2.0 * M_PI)) *
+ control_loops::drivetrain::kHighOutputRatio *
+ control_loops::drivetrain::kWheelRadius;
+ }
+
struct PotConstants {
::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
::frc971::zeroing::RelativeEncoderZeroingEstimator>
diff --git a/y2023/control_loops/drivetrain/BUILD b/y2023/control_loops/drivetrain/BUILD
index 8a06d00..ac00e2b 100644
--- a/y2023/control_loops/drivetrain/BUILD
+++ b/y2023/control_loops/drivetrain/BUILD
@@ -1,4 +1,5 @@
load("//aos:config.bzl", "aos_config")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
genrule(
name = "genrule_drivetrain",
@@ -111,3 +112,12 @@
"//frc971/control_loops/drivetrain:trajectory_generator",
],
)
+
+flatbuffer_cc_library(
+ name = "drivetrain_can_position_fbs",
+ srcs = [
+ "drivetrain_can_position.fbs",
+ ],
+ gen_reflections = 1,
+ visibility = ["//visibility:public"],
+)
diff --git a/y2023/control_loops/drivetrain/drivetrain_can_position.fbs b/y2023/control_loops/drivetrain/drivetrain_can_position.fbs
new file mode 100644
index 0000000..10d7c9a
--- /dev/null
+++ b/y2023/control_loops/drivetrain/drivetrain_can_position.fbs
@@ -0,0 +1,39 @@
+namespace y2023.control_loops.drivetrain;
+
+table CANFalcon {
+ // The CAN id of the falcon
+ id:int (id: 0);
+
+ // In Amps
+ supply_current:float (id: 1);
+
+ // In Amps
+ // Stator current where positive current means torque is applied in
+ // the motor's forward direction as determined by its Inverted setting.
+ torque_current:float (id: 2);
+
+ // In Volts
+ supply_voltage:float (id: 3);
+
+ // In degrees Celsius
+ device_temp:float (id: 4);
+
+ // In meters traveled on the drivetrain
+ position:float (id: 5);
+}
+
+// CAN readings from the CAN sensor reader loop
+table CANPosition {
+ falcons: [CANFalcon] (id: 0);
+
+ // The timestamp of the measurement on the canivore clock in nanoseconds
+ // This will have less jitter than the
+ // timestamp of the message being sent out.
+ timestamp:int64 (id: 1);
+
+ // The ctre::phoenix::StatusCode of the measurement
+ // Should be OK = 0
+ status:int (id: 2);
+}
+
+root_type CANPosition;
diff --git a/y2023/control_loops/drivetrain/drivetrain_main.cc b/y2023/control_loops/drivetrain/drivetrain_main.cc
index cf8aa8a..0817b3d 100644
--- a/y2023/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2023/control_loops/drivetrain/drivetrain_main.cc
@@ -19,6 +19,9 @@
std::make_unique<::frc971::control_loops::drivetrain::DeadReckonEkf>(
&event_loop,
::y2023::control_loops::drivetrain::GetDrivetrainConfig());
+ std::unique_ptr<DrivetrainLoop> drivetrain = std::make_unique<DrivetrainLoop>(
+ y2023::control_loops::drivetrain::GetDrivetrainConfig(), &event_loop,
+ localizer.get());
event_loop.Run();
diff --git a/y2023/control_loops/python/graph_edit.py b/y2023/control_loops/python/graph_edit.py
index 448103b..3ef9d07 100644
--- a/y2023/control_loops/python/graph_edit.py
+++ b/y2023/control_loops/python/graph_edit.py
@@ -11,17 +11,30 @@
gi.require_version('Gtk', '3.0')
from gi.repository import Gdk, Gtk
import cairo
-from graph_tools import XYSegment, AngleSegment, to_theta, to_xy, alpha_blend, draw_lines
-from graph_tools import back_to_xy_loop, subdivide_theta, to_theta_loop, px
+from graph_tools import XYSegment, AngleSegment, to_theta, to_xy, alpha_blend
+from graph_tools import back_to_xy_loop, subdivide_theta, to_theta_loop
from graph_tools import l1, l2, joint_center
import graph_paths
-from frc971.control_loops.python.basic_window import quit_main_loop, set_color
+from frc971.control_loops.python.basic_window import quit_main_loop, set_color, OverrideMatrix, identity
import shapely
from shapely.geometry import Polygon
+def px(cr):
+ return OverrideMatrix(cr, identity)
+
+
+# Draw lines to cr + stroke.
+def draw_lines(cr, lines):
+ cr.move_to(lines[0][0], lines[0][1])
+ for pt in lines[1:]:
+ cr.line_to(pt[0], pt[1])
+ with px(cr):
+ cr.stroke()
+
+
def draw_px_cross(cr, length_px):
"""Draws a cross with fixed dimensions in pixel space."""
with px(cr):
diff --git a/y2023/control_loops/python/graph_paths.py b/y2023/control_loops/python/graph_paths.py
index da0ad4f..6d8f489 100644
--- a/y2023/control_loops/python/graph_paths.py
+++ b/y2023/control_loops/python/graph_paths.py
@@ -17,6 +17,12 @@
circular_index=-1)
cone_perch_pos = to_theta_with_circular_index(1.0, 2.0, circular_index=-1)
+points = []
+front_points = []
+back_points = []
+unnamed_segments = []
+named_segments = []
+
segments = [
ThetaSplineSegment(neutral, neutral_to_cone_1, neutral_to_cone_2, cone_pos,
"NeutralToCone"),
diff --git a/y2023/control_loops/python/graph_tools.py b/y2023/control_loops/python/graph_tools.py
index 3ddfb37..dafa294 100644
--- a/y2023/control_loops/python/graph_tools.py
+++ b/y2023/control_loops/python/graph_tools.py
@@ -1,7 +1,4 @@
import numpy
-import cairo
-
-from frc971.control_loops.python.basic_window import OverrideMatrix, identity
# joint_center in x-y space.
joint_center = (-0.299, 0.299)
@@ -16,10 +13,6 @@
theta_end_circle_size = 0.07
-def px(cr):
- return OverrideMatrix(cr, identity)
-
-
# Convert from x-y coordinates to theta coordinates.
# orientation is a bool. This orientation is circular_index mod 2.
# where circular_index is the circular index, or the position in the
@@ -215,13 +208,11 @@
return (a[0], a[1], d1[0], d1[1], accel[0], accel[1])
-# Draw lines to cr + stroke.
+# Draw a list of lines to a cairo context.
def draw_lines(cr, lines):
cr.move_to(lines[0][0], lines[0][1])
for pt in lines[1:]:
cr.line_to(pt[0], pt[1])
- with px(cr):
- cr.stroke()
# Segment in angle space.
diff --git a/y2023/control_loops/superstructure/superstructure_plotter.ts b/y2023/control_loops/superstructure/superstructure_plotter.ts
index ae20119..2e32445 100644
--- a/y2023/control_loops/superstructure/superstructure_plotter.ts
+++ b/y2023/control_loops/superstructure/superstructure_plotter.ts
@@ -1,7 +1,7 @@
// Provides a plot for debugging robot state-related issues.
-import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
-import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
-import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {AosPlotter} from '../../../aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import * as proxy from '../../../aos/network/www/proxy';
import Connection = proxy.Connection;
diff --git a/y2023/wpilib_interface.cc b/y2023/wpilib_interface.cc
index 77ff5af..690d4bf 100644
--- a/y2023/wpilib_interface.cc
+++ b/y2023/wpilib_interface.cc
@@ -23,6 +23,7 @@
#undef ERROR
#include "aos/commonmath.h"
+#include "aos/containers/sized_array.h"
#include "aos/events/event_loop.h"
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
@@ -32,8 +33,10 @@
#include "aos/util/log_interval.h"
#include "aos/util/phased_loop.h"
#include "aos/util/wrapping_counter.h"
+#include "ctre/phoenix/cci/Diagnostics_CCI.h"
#include "ctre/phoenix/motorcontrol/can/TalonFX.h"
#include "ctre/phoenix/motorcontrol/can/TalonSRX.h"
+#include "ctre/phoenixpro/TalonFX.hpp"
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
#include "frc971/input/robot_state_generated.h"
@@ -51,12 +54,18 @@
#include "frc971/wpilib/sensor_reader.h"
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2023/constants.h"
+#include "y2023/control_loops/drivetrain/drivetrain_can_position_generated.h"
#include "y2023/control_loops/superstructure/superstructure_output_generated.h"
#include "y2023/control_loops/superstructure/superstructure_position_generated.h"
+DEFINE_bool(ctre_diag_server, false,
+ "If true, enable the diagnostics server for interacting with "
+ "devices on the CAN bus using Phoenix Tuner");
+
using ::aos::monotonic_clock;
using ::y2023::constants::Values;
namespace superstructure = ::y2023::control_loops::superstructure;
+namespace drivetrain = ::y2023::control_loops::drivetrain;
namespace chrono = ::std::chrono;
using std::make_unique;
@@ -122,6 +131,16 @@
autonomous_modes_.at(i) = ::std::move(sensor);
}
+ void set_heading_input(::std::unique_ptr<frc::DigitalInput> sensor) {
+ imu_heading_input_ = ::std::move(sensor);
+ imu_heading_reader_.set_input(imu_heading_input_.get());
+ }
+
+ void set_yaw_rate_input(::std::unique_ptr<frc::DigitalInput> sensor) {
+ imu_yaw_rate_input_ = ::std::move(sensor);
+ imu_yaw_rate_reader_.set_input(imu_yaw_rate_input_.get());
+ }
+
void RunIteration() override {
superstructure_reading_->Set(true);
{ auto builder = superstructure_position_sender_.MakeBuilder(); }
@@ -220,6 +239,8 @@
std::array<std::unique_ptr<frc::DigitalInput>, 2> autonomous_modes_;
+ std::unique_ptr<frc::DigitalInput> imu_heading_input_, imu_yaw_rate_input_;
+
frc971::wpilib::DMAPulseWidthReader imu_heading_reader_, imu_yaw_rate_reader_;
};
@@ -256,6 +277,326 @@
}
};
+static constexpr int kCANFalconCount = 6;
+static constexpr int kCANSignalsCount = 3;
+static constexpr units::frequency::hertz_t kCANUpdateFreqHz = 200_Hz;
+
+class Falcon {
+ public:
+ Falcon(int device_id, std::string canbus,
+ aos::SizedArray<ctre::phoenixpro::BaseStatusSignalValue *,
+ kCANFalconCount * kCANSignalsCount> *signals)
+ : talon_(device_id, canbus),
+ device_id_(device_id),
+ device_temp_(talon_.GetDeviceTemp()),
+ supply_voltage_(talon_.GetSupplyVoltage()),
+ supply_current_(talon_.GetSupplyCurrent()),
+ torque_current_(talon_.GetTorqueCurrent()),
+ position_(talon_.GetPosition()) {
+ // device temp is not timesynced so don't add it to the list of signals
+ device_temp_.SetUpdateFrequency(kCANUpdateFreqHz);
+
+ CHECK_EQ(kCANSignalsCount, 3);
+ CHECK_NOTNULL(signals);
+ CHECK_LE(signals->size() + 3u, signals->capacity());
+
+ supply_voltage_.SetUpdateFrequency(kCANUpdateFreqHz);
+ signals->push_back(&supply_voltage_);
+
+ supply_current_.SetUpdateFrequency(kCANUpdateFreqHz);
+ signals->push_back(&supply_current_);
+
+ torque_current_.SetUpdateFrequency(kCANUpdateFreqHz);
+ signals->push_back(&torque_current_);
+
+ position_.SetUpdateFrequency(kCANUpdateFreqHz);
+ signals->push_back(&position_);
+ }
+
+ void WriteConfigs(ctre::phoenixpro::signals::InvertedValue invert) {
+ inverted_ = invert;
+
+ ctre::phoenixpro::configs::CurrentLimitsConfigs current_limits;
+ current_limits.StatorCurrentLimit =
+ constants::Values::kDrivetrainStatorCurrentLimit();
+ current_limits.StatorCurrentLimitEnable = true;
+ current_limits.SupplyCurrentLimit =
+ constants::Values::kDrivetrainSupplyCurrentLimit();
+ current_limits.SupplyCurrentLimitEnable = true;
+
+ ctre::phoenixpro::configs::MotorOutputConfigs output_configs;
+ output_configs.NeutralMode =
+ ctre::phoenixpro::signals::NeutralModeValue::Brake;
+ output_configs.DutyCycleNeutralDeadband = 0;
+
+ output_configs.Inverted = inverted_;
+
+ ctre::phoenixpro::configs::TalonFXConfiguration configuration;
+ configuration.CurrentLimits = current_limits;
+ configuration.MotorOutput = output_configs;
+
+ ctre::phoenix::StatusCode status =
+ talon_.GetConfigurator().Apply(configuration);
+ if (!status.IsOK()) {
+ AOS_LOG(ERROR, "Failed to set falcon configuration: %s: %s",
+ status.GetName(), status.GetDescription());
+ }
+ }
+
+ ctre::phoenixpro::hardware::TalonFX *talon() { return &talon_; }
+
+ flatbuffers::Offset<drivetrain::CANFalcon> WritePosition(
+ flatbuffers::FlatBufferBuilder *fbb) {
+ drivetrain::CANFalcon::Builder builder(*fbb);
+ builder.add_id(device_id_);
+ builder.add_device_temp(device_temp_.GetValue().value());
+ builder.add_supply_voltage(supply_voltage_.GetValue().value());
+ builder.add_supply_current(supply_current_.GetValue().value());
+ builder.add_torque_current(torque_current_.GetValue().value());
+
+ double invert =
+ (inverted_ ==
+ ctre::phoenixpro::signals::InvertedValue::Clockwise_Positive
+ ? 1
+ : -1);
+
+ builder.add_position(constants::Values::DrivetrainCANEncoderToMeters(
+ position_.GetValue().value()) *
+ invert);
+
+ return builder.Finish();
+ }
+
+ // returns the monotonic timestamp of the latest timesynced reading in the
+ // timebase of the the syncronized CAN bus clock.
+ int64_t GetTimestamp() {
+ std::chrono::nanoseconds latest_timestamp =
+ torque_current_.GetTimestamp().GetTime();
+
+ return latest_timestamp.count();
+ }
+
+ void RefreshNontimesyncedSignals() { device_temp_.Refresh(); };
+
+ private:
+ ctre::phoenixpro::hardware::TalonFX talon_;
+ int device_id_;
+
+ ctre::phoenixpro::signals::InvertedValue inverted_;
+
+ ctre::phoenixpro::StatusSignalValue<units::temperature::celsius_t>
+ device_temp_;
+ ctre::phoenixpro::StatusSignalValue<units::voltage::volt_t> supply_voltage_;
+ ctre::phoenixpro::StatusSignalValue<units::current::ampere_t> supply_current_,
+ torque_current_;
+ ctre::phoenixpro::StatusSignalValue<units::angle::turn_t> position_;
+};
+
+class CANSensorReader {
+ public:
+ CANSensorReader(aos::EventLoop *event_loop)
+ : event_loop_(event_loop),
+ can_position_sender_(
+ event_loop->MakeSender<drivetrain::CANPosition>("/drivetrain")) {
+ event_loop->SetRuntimeRealtimePriority(35);
+ timer_handler_ = event_loop->AddTimer([this]() { Loop(); });
+ timer_handler_->set_name("CANSensorReader Loop");
+
+ event_loop->OnRun([this]() {
+ timer_handler_->Setup(event_loop_->monotonic_now(), 1 / kCANUpdateFreqHz);
+ });
+ }
+
+ aos::SizedArray<ctre::phoenixpro::BaseStatusSignalValue *,
+ kCANFalconCount * kCANSignalsCount>
+ *get_signals_registry() {
+ return &signals_;
+ };
+
+ void set_falcons(std::shared_ptr<Falcon> right_front,
+ std::shared_ptr<Falcon> right_back,
+ std::shared_ptr<Falcon> right_under,
+ std::shared_ptr<Falcon> left_front,
+ std::shared_ptr<Falcon> left_back,
+ std::shared_ptr<Falcon> left_under) {
+ right_front_ = std::move(right_front);
+ right_back_ = std::move(right_back);
+ right_under_ = std::move(right_under);
+ left_front_ = std::move(left_front);
+ left_back_ = std::move(left_back);
+ left_under_ = std::move(left_under);
+ }
+
+ private:
+ void Loop() {
+ CHECK_EQ(signals_.size(), 18u);
+ ctre::phoenix::StatusCode status =
+ ctre::phoenixpro::BaseStatusSignalValue::WaitForAll(
+ 2000_ms,
+ {signals_[0], signals_[1], signals_[2], signals_[3], signals_[4],
+ signals_[5], signals_[6], signals_[7], signals_[8], signals_[9],
+ signals_[10], signals_[11], signals_[12], signals_[13],
+ signals_[14], signals_[15], signals_[16], signals_[17]});
+
+ if (!status.IsOK()) {
+ AOS_LOG(ERROR, "Failed to read signals from falcons: %s: %s",
+ status.GetName(), status.GetDescription());
+ }
+
+ auto builder = can_position_sender_.MakeBuilder();
+
+ for (auto falcon : {right_front_, right_back_, right_under_, left_front_,
+ left_back_, left_under_}) {
+ falcon->RefreshNontimesyncedSignals();
+ }
+
+ aos::SizedArray<flatbuffers::Offset<drivetrain::CANFalcon>, kCANFalconCount>
+ falcons;
+
+ for (auto falcon : {right_front_, right_back_, right_under_, left_front_,
+ left_back_, left_under_}) {
+ falcons.push_back(falcon->WritePosition(builder.fbb()));
+ }
+
+ auto falcons_list =
+ builder.fbb()->CreateVector<flatbuffers::Offset<drivetrain::CANFalcon>>(
+ falcons);
+
+ drivetrain::CANPosition::Builder can_position_builder =
+ builder.MakeBuilder<drivetrain::CANPosition>();
+
+ can_position_builder.add_falcons(falcons_list);
+ can_position_builder.add_timestamp(right_front_->GetTimestamp());
+ can_position_builder.add_status(static_cast<int>(status));
+
+ builder.CheckOk(builder.Send(can_position_builder.Finish()));
+ }
+
+ aos::EventLoop *event_loop_;
+
+ aos::SizedArray<ctre::phoenixpro::BaseStatusSignalValue *,
+ kCANFalconCount * kCANSignalsCount>
+ signals_;
+ aos::Sender<drivetrain::CANPosition> can_position_sender_;
+
+ std::shared_ptr<Falcon> right_front_, right_back_, right_under_, left_front_,
+ left_back_, left_under_;
+
+ // Pointer to the timer handler used to modify the wakeup.
+ ::aos::TimerHandler *timer_handler_;
+};
+
+class DrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler<
+ ::frc971::control_loops::drivetrain::Output> {
+ public:
+ DrivetrainWriter(::aos::EventLoop *event_loop)
+ : ::frc971::wpilib::LoopOutputHandler<
+ ::frc971::control_loops::drivetrain::Output>(event_loop,
+ "/drivetrain") {
+ event_loop->SetRuntimeRealtimePriority(
+ constants::Values::kDrivetrainWriterPriority);
+
+ if (!FLAGS_ctre_diag_server) {
+ c_Phoenix_Diagnostics_SetSecondsToStart(-1);
+ c_Phoenix_Diagnostics_Dispose();
+ }
+
+ ctre::phoenix::platform::can::CANComm_SetRxSchedPriority(
+ constants::Values::kDrivetrainRxPriority, true, "Drivetrain Bus");
+ ctre::phoenix::platform::can::CANComm_SetTxSchedPriority(
+ constants::Values::kDrivetrainTxPriority, true, "Drivetrain Bus");
+
+ event_loop->OnRun([this]() { WriteConfigs(); });
+ }
+
+ void set_falcons(std::shared_ptr<Falcon> right_front,
+ std::shared_ptr<Falcon> right_back,
+ std::shared_ptr<Falcon> right_under,
+ std::shared_ptr<Falcon> left_front,
+ std::shared_ptr<Falcon> left_back,
+ std::shared_ptr<Falcon> left_under) {
+ right_front_ = std::move(right_front);
+ right_back_ = std::move(right_back);
+ right_under_ = std::move(right_under);
+ left_front_ = std::move(left_front);
+ left_back_ = std::move(left_back);
+ left_under_ = std::move(left_under);
+ }
+
+ void set_right_inverted(ctre::phoenixpro::signals::InvertedValue invert) {
+ right_inverted_ = invert;
+ }
+
+ void set_left_inverted(ctre::phoenixpro::signals::InvertedValue invert) {
+ left_inverted_ = invert;
+ }
+
+ private:
+ void WriteConfigs() {
+ for (auto falcon :
+ {right_front_.get(), right_back_.get(), right_under_.get()}) {
+ falcon->WriteConfigs(right_inverted_);
+ }
+
+ for (auto falcon :
+ {left_front_.get(), left_back_.get(), left_under_.get()}) {
+ falcon->WriteConfigs(left_inverted_);
+ }
+ }
+
+ void Write(
+ const ::frc971::control_loops::drivetrain::Output &output) override {
+ ctre::phoenixpro::controls::DutyCycleOut left_control(
+ SafeSpeed(output.left_voltage()));
+ left_control.UpdateFreqHz = 0_Hz;
+ left_control.EnableFOC = true;
+
+ ctre::phoenixpro::controls::DutyCycleOut right_control(
+ SafeSpeed(output.right_voltage()));
+ right_control.UpdateFreqHz = 0_Hz;
+ right_control.EnableFOC = true;
+
+ for (auto falcon :
+ {left_front_.get(), left_back_.get(), left_under_.get()}) {
+ ctre::phoenix::StatusCode status =
+ falcon->talon()->SetControl(left_control);
+
+ if (!status.IsOK()) {
+ AOS_LOG(ERROR, "Failed to write control to falcon: %s: %s",
+ status.GetName(), status.GetDescription());
+ }
+ }
+
+ for (auto falcon :
+ {right_front_.get(), right_back_.get(), right_under_.get()}) {
+ ctre::phoenix::StatusCode status =
+ falcon->talon()->SetControl(right_control);
+
+ if (!status.IsOK()) {
+ AOS_LOG(ERROR, "Failed to write control to falcon: %s: %s",
+ status.GetName(), status.GetDescription());
+ }
+ }
+ }
+
+ void Stop() override {
+ AOS_LOG(WARNING, "drivetrain output too old\n");
+ ctre::phoenixpro::controls::NeutralOut stop_command;
+ for (auto falcon :
+ {right_front_.get(), right_back_.get(), right_under_.get(),
+ left_front_.get(), left_back_.get(), left_under_.get()}) {
+ falcon->talon()->SetControl(stop_command);
+ }
+ }
+
+ double SafeSpeed(double voltage) {
+ return (::aos::Clip(voltage, -kMaxBringupPower, kMaxBringupPower) / 12.0);
+ }
+
+ ctre::phoenixpro::signals::InvertedValue left_inverted_, right_inverted_;
+ std::shared_ptr<Falcon> right_front_, right_back_, right_under_, left_front_,
+ left_back_, left_under_;
+};
class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
public:
@@ -272,6 +613,11 @@
aos::configuration::ReadConfig("aos_config.json");
// Thread 1.
+ ::aos::ShmEventLoop joystick_sender_event_loop(&config.message());
+ ::frc971::wpilib::JoystickSender joystick_sender(
+ &joystick_sender_event_loop);
+ AddLoop(&joystick_sender_event_loop);
+
// Thread 2.
::aos::ShmEventLoop pdp_fetcher_event_loop(&config.message());
::frc971::wpilib::PDPFetcher pdp_fetcher(&pdp_fetcher_event_loop);
@@ -288,11 +634,43 @@
sensor_reader.set_drivetrain_right_encoder(make_encoder(0));
sensor_reader.set_superstructure_reading(superstructure_reading);
+ sensor_reader.set_heading_input(make_unique<frc::DigitalInput>(9));
+ sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(8));
+
AddLoop(&sensor_reader_event_loop);
// Thread 4.
+ ::aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
+ CANSensorReader can_sensor_reader(&can_sensor_reader_event_loop);
+
+ std::shared_ptr<Falcon> right_front = std::make_shared<Falcon>(
+ 1, "Drivetrain Bus", can_sensor_reader.get_signals_registry());
+ std::shared_ptr<Falcon> right_back = std::make_shared<Falcon>(
+ 2, "Drivetrain Bus", can_sensor_reader.get_signals_registry());
+ std::shared_ptr<Falcon> right_under = std::make_shared<Falcon>(
+ 3, "Drivetrain Bus", can_sensor_reader.get_signals_registry());
+ std::shared_ptr<Falcon> left_front = std::make_shared<Falcon>(
+ 4, "Drivetrain Bus", can_sensor_reader.get_signals_registry());
+ std::shared_ptr<Falcon> left_back = std::make_shared<Falcon>(
+ 5, "Drivetrain Bus", can_sensor_reader.get_signals_registry());
+ std::shared_ptr<Falcon> left_under = std::make_shared<Falcon>(
+ 6, "Drivetrain Bus", can_sensor_reader.get_signals_registry());
+
+ can_sensor_reader.set_falcons(right_front, right_back, right_under,
+ left_front, left_back, left_under);
+
+ AddLoop(&can_sensor_reader_event_loop);
+
+ // Thread 5.
::aos::ShmEventLoop output_event_loop(&config.message());
- ::frc971::wpilib::DrivetrainWriter drivetrain_writer(&output_event_loop);
+ DrivetrainWriter drivetrain_writer(&output_event_loop);
+
+ drivetrain_writer.set_falcons(right_front, right_back, right_under,
+ left_front, left_back, left_under);
+ drivetrain_writer.set_right_inverted(
+ ctre::phoenixpro::signals::InvertedValue::Clockwise_Positive);
+ drivetrain_writer.set_left_inverted(
+ ctre::phoenixpro::signals::InvertedValue::CounterClockwise_Positive);
SuperstructureWriter superstructure_writer(&output_event_loop);
diff --git a/y2023/www/field_main.ts b/y2023/www/field_main.ts
index 7e2e392..d71a45e 100644
--- a/y2023/www/field_main.ts
+++ b/y2023/www/field_main.ts
@@ -1,4 +1,4 @@
-import {Connection} from 'org_frc971/aos/network/www/proxy';
+import {Connection} from '../../aos/network/www/proxy';
import {FieldHandler} from './field_handler';
diff --git a/y2023/y2023_roborio.json b/y2023/y2023_roborio.json
index 572aadc..e12d612 100644
--- a/y2023/y2023_roborio.json
+++ b/y2023/y2023_roborio.json
@@ -287,6 +287,14 @@
},
{
"name": "/drivetrain",
+ "type": "y2023.control_loops.drivetrain.CANPosition",
+ "source_node": "roborio",
+ "frequency": 220,
+ "num_senders": 2,
+ "max_size": 400
+ },
+ {
+ "name": "/drivetrain",
"type": "frc971.sensors.GyroReading",
"source_node": "roborio",
"frequency": 200,
@@ -490,7 +498,7 @@
]
},
{
- "name": "web_proxy",
+ "name": "roborio_web_proxy",
"executable_name": "web_proxy_main",
"args": ["--min_ice_port=5800", "--max_ice_port=5810"],
"nodes": [
@@ -506,7 +514,7 @@
]
},
{
- "name": "message_bridge_server",
+ "name": "roborio_message_bridge_server",
"executable_name": "message_bridge_server",
"args": ["--rt_priority=16"],
"nodes": [