Merge "Update 2022 comp bot intake zeros"
diff --git a/aos/starter/BUILD b/aos/starter/BUILD
index 4a366c9..5690bda 100644
--- a/aos/starter/BUILD
+++ b/aos/starter/BUILD
@@ -226,6 +226,7 @@
srcs = [
"irq_affinity.cc",
],
+ visibility = ["//visibility:public"],
deps = [
":irq_affinity_lib",
":kthread_fbs",
diff --git a/aos/starter/irq_affinity.cc b/aos/starter/irq_affinity.cc
index 33ab589..3f32ec9 100644
--- a/aos/starter/irq_affinity.cc
+++ b/aos/starter/irq_affinity.cc
@@ -296,8 +296,16 @@
"affinity": [2]
},
{
+ "name": "ff6e0000.dma-controller",
+ "affinity": [0]
+ },
+ {
+ "name": "ff1d0000.spi",
+ "affinity": [0]
+ },
+ {
"name": "eth0",
- "affinity": [3]
+ "affinity": [1]
}
],
"kthreads": [
@@ -340,7 +348,13 @@
{
"name": "irq/*-adis16505",
"scheduler": "SCHEDULER_FIFO",
- "priority": 58,
+ "priority": 59,
+ "affinity": [0]
+ },
+ {
+ "name": "irq/*-ff6e0000.dma-controller",
+ "scheduler": "SCHEDULER_FIFO",
+ "priority": 59,
"affinity": [0]
},
{
diff --git a/aos/starter/starter.sh b/aos/starter/starter.sh
index 9bc7605..d4281c5 100755
--- a/aos/starter/starter.sh
+++ b/aos/starter/starter.sh
@@ -14,7 +14,7 @@
# We have systemd configured to handle restarting, so just exec.
export PATH="${PATH}:/home/pi/bin"
rm -rf /dev/shm/aos
- exec starterd
+ exec starterd --user=pi
else
ROBOT_CODE="${HOME}/bin"
fi
diff --git a/aos/starter/starterd.cc b/aos/starter/starterd.cc
index f284819..54f1bb4 100644
--- a/aos/starter/starterd.cc
+++ b/aos/starter/starterd.cc
@@ -31,7 +31,7 @@
constexpr int kUnchanged = -1;
if (setresgid(/* ruid */ gid, /* euid */ gid,
/* suid */ kUnchanged) != 0) {
- PLOG(FATAL) << "Failed to change GID to " << FLAGS_user;
+ PLOG(FATAL) << "Failed to change GID to " << FLAGS_user << ", group " << gid;
}
if (setresuid(/* ruid */ uid, /* euid */ uid,
diff --git a/frc971/downloader/downloader.py b/frc971/downloader/downloader.py
index bed72b9..f45a162 100644
--- a/frc971/downloader/downloader.py
+++ b/frc971/downloader/downloader.py
@@ -103,7 +103,8 @@
# permissions or the executables won't be visible to init.
os.chmod(temp_dir, 0o775)
# Starter needs to be SUID so we transition from lvuser to admin.
- os.chmod(os.path.join(temp_dir, "starterd"), 0o775 | stat.S_ISUID)
+ if args.type != "pi":
+ os.chmod(os.path.join(temp_dir, "starterd"), 0o775 | stat.S_ISUID)
rsync_cmd = ([
"external/rsync/usr/bin/rsync",
diff --git a/frc971/vision/charuco_lib.cc b/frc971/vision/charuco_lib.cc
index 82cf56b..1fb1795 100644
--- a/frc971/vision/charuco_lib.cc
+++ b/frc971/vision/charuco_lib.cc
@@ -29,6 +29,11 @@
"Type of target: april_tag|aruco|charuco|charuco_diamond");
DEFINE_bool(visualize, false, "Whether to visualize the resulting data.");
+DEFINE_uint32(age, 5, "Age to start dropping frames at.");
+DEFINE_uint32(disable_delay, 100, "Time after an issue to disable tracing at.");
+
+DECLARE_bool(enable_ftrace);
+
namespace frc971 {
namespace vision {
namespace chrono = std::chrono;
@@ -102,7 +107,8 @@
event_loop_->GetChannel<CameraImage>(channel)
->source_node()
->string_view())),
- handle_image_(std::move(handle_image_fn)) {
+ handle_image_(std::move(handle_image_fn)),
+ timer_fn_(event_loop->AddTimer([this]() { DisableTracing(); })) {
event_loop_->MakeWatcher(channel, [this](const CameraImage &image) {
const monotonic_clock::time_point eof_source_node =
monotonic_clock::time_point(
@@ -141,7 +147,20 @@
const monotonic_clock::duration age = event_loop_->monotonic_now() - eof;
const double age_double =
std::chrono::duration_cast<std::chrono::duration<double>>(age).count();
- if (age > std::chrono::milliseconds(100)) {
+ if (age > std::chrono::milliseconds(FLAGS_age)) {
+ if (FLAGS_enable_ftrace) {
+ ftrace_.FormatMessage("Too late receiving image, age: %f\n",
+ age_double);
+ if (FLAGS_disable_delay > 0) {
+ if (!disabling_) {
+ timer_fn_->Setup(event_loop_->monotonic_now() +
+ chrono::milliseconds(FLAGS_disable_delay));
+ disabling_ = true;
+ }
+ } else {
+ DisableTracing();
+ }
+ }
VLOG(2) << "Age: " << age_double << ", getting behind, skipping";
return;
}
@@ -149,12 +168,30 @@
cv::Mat image_color_mat(cv::Size(image.cols(), image.rows()), CV_8UC2,
(void *)image.data()->data());
const cv::Size image_size(image.cols(), image.rows());
- cv::Mat rgb_image(image_size, CV_8UC3);
- cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
- handle_image_(rgb_image, eof);
+ switch (format_) {
+ case Format::GRAYSCALE: {
+ ftrace_.FormatMessage("Starting yuyv->greyscale\n");
+ cv::Mat gray_image(image_size, CV_8UC3);
+ cv::cvtColor(image_color_mat, gray_image, cv::COLOR_YUV2GRAY_YUYV);
+ handle_image_(gray_image, eof);
+ } break;
+ case Format::BGR: {
+ cv::Mat rgb_image(image_size, CV_8UC3);
+ cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV);
+ handle_image_(rgb_image, eof);
+ } break;
+ case Format::YUYV2: {
+ handle_image_(image_color_mat, eof);
+ };
+ }
});
}
+void ImageCallback::DisableTracing() {
+ disabling_ = false;
+ ftrace_.TurnOffOrDie();
+}
+
void CharucoExtractor::SetupTargetData() {
// TODO(Jim): Put correct values here
marker_length_ = 0.15;
diff --git a/frc971/vision/charuco_lib.h b/frc971/vision/charuco_lib.h
index 362bb7d..f4f1233 100644
--- a/frc971/vision/charuco_lib.h
+++ b/frc971/vision/charuco_lib.h
@@ -51,15 +51,33 @@
// full-service callback functionality
class ImageCallback {
public:
+ enum class Format {
+ YUYV2 = 0,
+ BGR = 1,
+ GRAYSCALE = 2,
+ };
ImageCallback(aos::EventLoop *event_loop, std::string_view channel,
std::function<void(cv::Mat, aos::monotonic_clock::time_point)>
&&handle_image_fn);
+ void set_format(Format format) {
+ format_ = format;
+ }
+
private:
+ void DisableTracing();
+
aos::EventLoop *event_loop_;
aos::Fetcher<aos::message_bridge::ServerStatistics> server_fetcher_;
const aos::Node *source_node_;
std::function<void(cv::Mat, aos::monotonic_clock::time_point)> handle_image_;
+ aos::TimerHandler *timer_fn_;
+
+ bool disabling_ = false;
+
+ aos::Ftrace ftrace_;
+
+ Format format_ = Format::BGR;
};
// Class which calls a callback each time an image arrives with the information
diff --git a/y2023/BUILD b/y2023/BUILD
new file mode 100644
index 0000000..60764ce
--- /dev/null
+++ b/y2023/BUILD
@@ -0,0 +1,145 @@
+load("//frc971:downloader.bzl", "robot_downloader")
+load("//aos:config.bzl", "aos_config")
+load("//tools/build_rules:template.bzl", "jinja2_template")
+
+robot_downloader(
+ name = "pi_download",
+ binaries = [
+ "//y2023/vision:viewer",
+ "//y2022/localizer:imu_main",
+ "//y2022/localizer:localizer_main",
+ "//aos/events/logging:log_cat",
+ ],
+ data = [
+ ":aos_config",
+ ],
+ dirs = [
+ "//y2022/www:www_files",
+ ],
+ start_binaries = [
+ "//aos/events/logging:logger_main",
+ "//aos/network:message_bridge_client",
+ "//aos/network:message_bridge_server",
+ "//aos/network:web_proxy_main",
+ "//aos/starter:irq_affinity",
+ "//y2023/vision:camera_reader",
+ ],
+ target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
+ target_type = "pi",
+)
+
+aos_config(
+ name = "aos_config",
+ src = "y2023.json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//frc971/input:robot_state_fbs",
+ "//frc971/vision:vision_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":config_imu",
+ ":config_logger",
+ ":config_pi1",
+ ":config_pi2",
+ ":config_pi3",
+ ":config_pi4",
+ ":config_roborio",
+ ],
+)
+
+[
+ aos_config(
+ name = "config_" + pi,
+ src = "y2023_" + pi + ".json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//aos/network:remote_message_fbs",
+ "//frc971/vision:vision_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ "//frc971/input:aos_config",
+ ],
+ )
+ for pi in [
+ "pi1",
+ "pi2",
+ "pi3",
+ "pi4",
+ ]
+]
+
+aos_config(
+ name = "config_imu",
+ src = "y2023_imu.json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//aos/network:remote_message_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ ],
+)
+
+aos_config(
+ name = "config_logger",
+ src = "y2023_logger.json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//aos/network:remote_message_fbs",
+ "//frc971/vision:vision_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ "//frc971/input:aos_config",
+ ],
+)
+
+aos_config(
+ name = "config_roborio",
+ src = "y2023_roborio.json",
+ flatbuffers = [
+ "//aos/network:remote_message_fbs",
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//y2019/control_loops/drivetrain:target_selector_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/autonomous:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ "//frc971/input:aos_config",
+ "//frc971/wpilib:aos_config",
+ ],
+)
+
+[
+ jinja2_template(
+ name = "y2023_pi" + str(num) + ".json",
+ src = "y2023_pi_template.json",
+ parameters = {"NUM": str(num)},
+ target_compatible_with = ["@platforms//os:linux"],
+ )
+ for num in range(1, 6)
+]
diff --git a/y2023/vision/camera_reader.cc b/y2023/vision/camera_reader.cc
index 0e86c32..3466c83 100644
--- a/y2023/vision/camera_reader.cc
+++ b/y2023/vision/camera_reader.cc
@@ -2,6 +2,7 @@
#include "absl/strings/str_split.h"
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
+#include "aos/realtime.h"
#include "frc971/vision/media_device.h"
#include "frc971/vision/v4l2_reader.h"
@@ -76,6 +77,7 @@
aos::ShmEventLoop event_loop(&config.message());
event_loop.SetRuntimeRealtimePriority(55);
+ event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({2}));
RockchipV4L2Reader v4l2_reader(&event_loop, event_loop.epoll(),
rkisp1_selfpath->device());
diff --git a/y2023/y2023.json b/y2023/y2023.json
new file mode 100644
index 0000000..76f0e52
--- /dev/null
+++ b/y2023/y2023.json
@@ -0,0 +1,23 @@
+{
+ "channel_storage_duration": 2000000000,
+ "maps": [
+ {
+ "match": {
+ "name": "/aos",
+ "type": "aos.RobotState"
+ },
+ "rename": {
+ "name": "/roborio/aos"
+ }
+ }
+ ],
+ "imports": [
+ "y2023_roborio.json",
+ "y2023_pi1.json",
+ "y2023_pi2.json",
+ "y2023_pi3.json",
+ "y2023_pi4.json",
+ "y2023_imu.json",
+ "y2023_logger.json"
+ ]
+}
diff --git a/y2023/y2023_imu.json b/y2023/y2023_imu.json
new file mode 100644
index 0000000..6b2ca7a
--- /dev/null
+++ b/y2023/y2023_imu.json
@@ -0,0 +1,380 @@
+{
+ "channels": [
+ {
+ "name": "/imu/aos",
+ "type": "aos.timing.Report",
+ "source_node": "imu",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 4096
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "imu",
+ "frequency": 200,
+ "num_senders": 20
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.starter.Status",
+ "source_node": "imu",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "frequency": 50,
+ "num_senders": 20,
+ "logger_nodes": [
+ "roborio",
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/roborio/imu/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 100,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/logger/imu/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 100,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "imu",
+ "frequency": 10,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio",
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/roborio/imu/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/logger/imu/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "imu",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "imu",
+ "frequency": 20,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "imu",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "imu",
+ "frequency": 15,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio",
+ "logger"
+ ],
+ "max_size": 400,
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 5000000
+ },
+ {
+ "name": "logger",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/roborio/imu/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/logger/imu/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "logger",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.starter.Status",
+ "source_node": "logger",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.Status",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/localizer",
+ "type": "frc971.IMUValuesBatch",
+ "source_node": "imu",
+ "frequency": 2200,
+ "max_size": 1600,
+ "num_senders": 2
+ }
+ ],
+ "applications": [
+ {
+ "name": "message_bridge_client",
+ "executable_name": "message_bridge_client",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "localizer",
+ "executable_name": "localizer_main",
+ /* TODO(james): Remove this once confident in the accelerometer code. */
+ "args": ["--ignore_accelerometer"],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "imu",
+ "executable_name": "imu_main",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "localizer_logger",
+ "executable_name": "logger_main",
+ "args": ["--logging_folder", "", "--snappy_compress"],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "web_proxy",
+ "executable_name": "web_proxy_main",
+ "nodes": [
+ "imu"
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "imu"
+ },
+ "rename": {
+ "name": "/imu/aos"
+ }
+ }
+ ],
+ "nodes": [
+ {
+ "name": "imu",
+ "hostname": "imu",
+ "hostnames": [
+ "pi-971-5",
+ "pi-7971-5",
+ "pi-8971-5",
+ "pi-9971-5"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "logger"
+ },
+ {
+ "name": "roborio"
+ }
+ ]
+}
diff --git a/y2023/y2023_logger.json b/y2023/y2023_logger.json
new file mode 100644
index 0000000..6ddc19f
--- /dev/null
+++ b/y2023/y2023_logger.json
@@ -0,0 +1,425 @@
+{
+ "channels": [
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger" : "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes" : ["roborio"]
+ }
+ ]
+ },
+ {
+ "name": "/pi1/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "pi1",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 1,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/pi2/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "pi2",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 1,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/pi3/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "pi3",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 1,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/pi4/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "pi4",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 1,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.timing.Report",
+ "source_node": "logger",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 4096
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "logger",
+ "frequency": 400,
+ "num_senders": 20
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "logger",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "logger",
+ "frequency": 20,
+ "max_size": 2000,
+ "num_senders": 2
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "logger",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.starter.Status",
+ "source_node": "logger",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 2000,
+ "logger_nodes": [
+ "roborio"
+ ],
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "logger",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio"
+ ],
+ "frequency": 10,
+ "num_senders": 2,
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "logger",
+ "frequency": 15,
+ "num_senders": 2,
+ "max_size": 400,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio",
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "pi1",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "pi2",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "pi3",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "pi4",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "imu",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "roborio",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/roborio/logger/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/imu/logger/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/pi1/logger/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/pi2/logger/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/pi3/logger/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/pi4/logger/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/camera",
+ "type": "frc971.vision.CameraImage",
+ "logger": "NOT_LOGGED",
+ "source_node": "logger",
+ "frequency": 100,
+ "max_size": 2600000,
+ "num_readers": 4,
+ "read_method": "PIN",
+ "num_senders": 1
+ },
+ {
+ "name": "/localizer",
+ "type": "frc971.IMUValuesBatch",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "source_node": "imu",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 3,
+ "time_to_live": 500000000
+ }
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "logger"
+ },
+ "rename": {
+ "name": "/logger/aos"
+ }
+ },
+ {
+ "match": {
+ "name": "/camera*",
+ "source_node": "logger"
+ },
+ "rename": {
+ "name": "/logger/camera"
+ }
+ }
+
+ ],
+ "applications": [
+ {
+ "name": "logger_message_bridge_client",
+ "executable_name": "message_bridge_client",
+ "autostart": false,
+ "args": ["--rmem=8388608", "--rt_priority=16"],
+ "nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "logger_message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "autostart": false,
+ "args": ["--rt_priority=16"],
+ "nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "image_logger",
+ "executable_name": "logger_main",
+ "autostart": false,
+ "args": ["--snappy_compress", "--logging_folder", "", "--snappy_compress", "--rotate_every", "60.0"],
+ "nodes": [
+ "logger"
+ ]
+ },
+ {
+ "name": "image_streamer",
+ "executable_name": "image_streamer_start.sh",
+ "autostart": false,
+ "nodes": [
+ "logger"
+ ]
+ }
+ ],
+ "nodes": [
+ {
+ "name": "logger",
+ "hostname": "pi6",
+ "hostnames": [
+ "pi-971-6",
+ "pi-9971-6",
+ "ASchuh-T480s",
+ "aschuh-3950x"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "pi1"
+ },
+ {
+ "name": "pi2"
+ },
+ {
+ "name": "pi3"
+ },
+ {
+ "name": "roborio"
+ },
+ {
+ "name": "imu"
+ },
+ {
+ "name": "pi4"
+ }
+ ]
+}
diff --git a/y2023/y2023_pi_template.json b/y2023/y2023_pi_template.json
new file mode 100644
index 0000000..2bf45bb
--- /dev/null
+++ b/y2023/y2023_pi_template.json
@@ -0,0 +1,360 @@
+{
+ "channels": [
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.timing.Report",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 4096
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 200,
+ "num_senders": 20
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.starter.Status",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 2000,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio",
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "time_to_live": 5000000
+ },
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 10,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio",
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "time_to_live": 5000000
+ },
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 20,
+ "num_senders": 2
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/pi{{ NUM }}/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 15,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio",
+ "imu"
+ ],
+ "max_size": 200,
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "imu",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/pi{{ NUM }}/aos/remote_timestamps/roborio/pi{{ NUM }}/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "pi{{ NUM }}",
+ "max_size": 208
+ },
+ {
+ "name": "/pi{{ NUM }}/aos/remote_timestamps/imu/pi{{ NUM }}/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "pi{{ NUM }}",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "imu",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "pi{{ NUM }}"
+ ],
+ "destination_nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/pi{{ NUM }}/imu/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/pi{{ NUM }}/camera",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 40,
+ "max_size": 2600000,
+ "num_readers": 4,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "logger",
+ "destination_nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/pi{{ NUM }}/logger/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/logger/aos",
+ "type": "aos.starter.Status",
+ "source_node": "logger",
+ "destination_nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "logger"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/logger/aos/remote_timestamps/pi{{ NUM }}/logger/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "logger",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "roborio",
+ "destination_nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/pi{{ NUM }}/roborio/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.Status",
+ "source_node": "roborio",
+ "destination_nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/pi{{ NUM }}/roborio/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ }
+ ],
+ "applications": [
+ {
+ "name": "message_bridge_client",
+ "executable_name": "message_bridge_client",
+ "args": ["--rt_priority=16"],
+ "user": "pi",
+ "nodes": [
+ "pi{{ NUM }}"
+ ]
+ },
+ {
+ "name": "irq_affinity",
+ "executable_name": "irq_affinity",
+ "user": "root",
+ "args": ["--user=pi"],
+ "nodes": [
+ "pi{{ NUM }}"
+ ]
+ },
+ {
+ "name": "message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "user": "pi",
+ "nodes": [
+ "pi{{ NUM }}"
+ ]
+ },
+ {
+ "name": "web_proxy",
+ "executable_name": "web_proxy_main",
+ "user": "pi",
+ "nodes": [
+ "pi{{ NUM }}"
+ ]
+ },
+ {
+ "name": "camera_reader",
+ "executable_name": "camera_reader",
+ "args": ["--enable_ftrace"],
+ "user": "pi",
+ "nodes": [
+ "pi{{ NUM }}"
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "pi{{ NUM }}"
+ },
+ "rename": {
+ "name": "/pi{{ NUM }}/aos"
+ }
+ },
+ {
+ "match": {
+ "name": "/camera*",
+ "source_node": "pi{{ NUM }}"
+ },
+ "rename": {
+ "name": "/pi{{ NUM }}/camera"
+ }
+ }
+ ],
+ "nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "hostname": "pi{{ NUM }}",
+ "hostnames": [
+ "pi-971-{{ NUM }}",
+ "pi-7971-{{ NUM }}",
+ "pi-8971-{{ NUM }}",
+ "pi-9971-{{ NUM }}"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "logger"
+ },
+ {
+ "name": "imu"
+ },
+ {
+ "name": "roborio"
+ }
+ ]
+}
diff --git a/y2023/y2023_roborio.json b/y2023/y2023_roborio.json
new file mode 100644
index 0000000..f10d901
--- /dev/null
+++ b/y2023/y2023_roborio.json
@@ -0,0 +1,522 @@
+{
+ "channels": [
+ {
+ "name": "/roborio/aos",
+ "type": "aos.JoystickState",
+ "source_node": "roborio",
+ "frequency": 100,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes" : [
+ "imu",
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 200,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 200,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.RobotState",
+ "source_node": "roborio",
+ "frequency": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.timing.Report",
+ "source_node": "roborio",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 4096
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "roborio",
+ "frequency": 500,
+ "max_size": 344,
+ "num_senders": 20
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.Status",
+ "source_node": "roborio",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 2000,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-starter-Status",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "roborio",
+ "frequency": 10,
+ "max_size": 400,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "roborio",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "roborio",
+ "frequency": 20,
+ "max_size": 2000,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "roborio",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/logger/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 200,
+ "source_node": "roborio"
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/pi1/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "roborio",
+ "max_size": 208
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/pi2/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "roborio",
+ "max_size": 208
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/pi3/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "roborio"
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/pi4/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "roborio"
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "roborio",
+ "max_size": 208
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "roborio",
+ "frequency": 15,
+ "num_senders": 2,
+ "max_size": 512,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "pi1",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ },
+ {
+ "name": "pi2",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ },
+ {
+ "name": "pi3",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ },
+ {
+ "name": "pi4",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ },
+ {
+ "name": "imu",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.sensors.GyroReading",
+ "source_node": "roborio",
+ "frequency": 200,
+ "num_senders": 2
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.sensors.Uid",
+ "source_node": "roborio",
+ "frequency": 200,
+ "num_senders": 2
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.fb.Trajectory",
+ "source_node": "roborio",
+ "max_size": 600000,
+ "frequency": 10,
+ "logger": "NOT_LOGGED",
+ "num_senders": 2,
+ "read_method": "PIN",
+ "num_readers": 10
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.SplineGoal",
+ "source_node": "roborio",
+ "frequency": 10
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Goal",
+ "source_node": "roborio",
+ "max_size": 224,
+ "frequency": 200
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Position",
+ "source_node": "roborio",
+ "frequency": 400,
+ "max_size": 112,
+ "num_senders": 2
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Output",
+ "source_node": "roborio",
+ "frequency": 400,
+ "max_size": 80,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/drivetrain/frc971-control_loops-drivetrain-Output",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 400,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Status",
+ "source_node": "roborio",
+ "frequency": 400,
+ "max_size": 1616,
+ "num_senders": 2
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.LocalizerControl",
+ "source_node": "roborio",
+ "frequency": 200,
+ "max_size": 96,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 0
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/drivetrain/frc971-control_loops-drivetrain-LocalizerControl",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 400,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/drivetrain",
+ "type": "y2019.control_loops.drivetrain.TargetSelectorHint",
+ "source_node": "roborio"
+ },
+ {
+ "name": "/autonomous",
+ "type": "aos.common.actions.Status",
+ "source_node": "roborio"
+ },
+ {
+ "name": "/autonomous",
+ "type": "frc971.autonomous.Goal",
+ "source_node": "roborio"
+ },
+ {
+ "name": "/autonomous",
+ "type": "frc971.autonomous.AutonomousMode",
+ "source_node": "roborio",
+ "frequency": 200
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "frc971.PDPValues",
+ "source_node": "roborio",
+ "frequency": 55,
+ "max_size": 368
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "frc971.wpilib.PneumaticsToLog",
+ "source_node": "roborio",
+ "frequency": 50
+ }
+ ],
+ "applications": [
+ {
+ "name": "drivetrain",
+ "executable_name": "drivetrain",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "trajectory_generator",
+ "executable_name": "trajectory_generator",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "joystick_reader",
+ "executable_name": "joystick_reader",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "wpilib_interface",
+ "executable_name": "wpilib_interface",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "autonomous_action",
+ "executable_name": "autonomous_action",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "web_proxy",
+ "executable_name": "web_proxy_main",
+ "args": ["--min_ice_port=5800", "--max_ice_port=5810"],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "roborio_message_bridge_client",
+ "executable_name": "message_bridge_client",
+ "args": ["--rt_priority=16"],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "args": ["--rt_priority=16"],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "logger",
+ "executable_name": "logger_main",
+ "args": ["--snappy_compress"],
+ "nodes": [
+ "roborio"
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "roborio"
+ },
+ "rename": {
+ "name": "/roborio/aos"
+ }
+ }
+ ],
+ "nodes": [
+ {
+ "name": "roborio",
+ "hostname": "roborio",
+ "hostnames": [
+ "roboRIO-971-FRC",
+ "roboRIO-6971-FRC",
+ "roboRIO-7971-FRC",
+ "roboRIO-8971-FRC",
+ "roboRIO-9971-FRC"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "imu"
+ },
+ {
+ "name": "logger"
+ },
+ {
+ "name": "pi1"
+ },
+ {
+ "name": "pi2"
+ },
+ {
+ "name": "pi3"
+ },
+ {
+ "name": "pi4"
+ }
+ ]
+}