Merge "Scouting: Add docked and engaged to Stats2023"
diff --git a/aos/starter/starterd_lib.cc b/aos/starter/starterd_lib.cc
index 485d1f1..b8b7343 100644
--- a/aos/starter/starterd_lib.cc
+++ b/aos/starter/starterd_lib.cc
@@ -84,7 +84,8 @@
if (aos::configuration::MultiNode(config_msg_)) {
std::string_view current_node = event_loop_.node()->name()->string_view();
for (const aos::Application *application : *applications) {
- CHECK(application->has_nodes());
+ CHECK(application->has_nodes())
+ << ": Missing nodes on " << aos::FlatbufferToJson(application);
for (const flatbuffers::String *node : *application->nodes()) {
if (node->string_view() == current_node) {
AddApplication(application);
diff --git a/frc971/autonomous/base_autonomous_actor.cc b/frc971/autonomous/base_autonomous_actor.cc
index ca6cc89..90c1454 100644
--- a/frc971/autonomous/base_autonomous_actor.cc
+++ b/frc971/autonomous/base_autonomous_actor.cc
@@ -177,6 +177,24 @@
return false;
}
+double BaseAutonomousActor::X() {
+ drivetrain_status_fetcher_.Fetch();
+ CHECK(drivetrain_status_fetcher_.get());
+ return drivetrain_status_fetcher_->x();
+}
+
+double BaseAutonomousActor::Y() {
+ drivetrain_status_fetcher_.Fetch();
+ CHECK(drivetrain_status_fetcher_.get());
+ return drivetrain_status_fetcher_->y();
+}
+
+double BaseAutonomousActor::Theta() {
+ drivetrain_status_fetcher_.Fetch();
+ CHECK(drivetrain_status_fetcher_.get());
+ return drivetrain_status_fetcher_->theta();
+}
+
bool BaseAutonomousActor::WaitForAboveAngle(double angle) {
::aos::time::PhasedLoop phased_loop(frc971::controls::kLoopFrequency,
event_loop()->monotonic_now(),
@@ -412,18 +430,26 @@
// when we reach the end of the spline).
// (b) The spline that we are executing is the correct one.
// (c) There is less than distance distance remaining.
+ if (base_autonomous_actor_->drivetrain_status_fetcher_->trajectory_logging()
+ ->goal_spline_handle() != spline_handle_) {
+ // Never done if we aren't the active spline.
+ return false;
+ }
+
+ if (base_autonomous_actor_->drivetrain_status_fetcher_->trajectory_logging()
+ ->is_executed()) {
+ return true;
+ }
return base_autonomous_actor_->drivetrain_status_fetcher_
->trajectory_logging()
->is_executing() &&
base_autonomous_actor_->drivetrain_status_fetcher_
->trajectory_logging()
- ->goal_spline_handle() == spline_handle_ &&
- base_autonomous_actor_->drivetrain_status_fetcher_
- ->trajectory_logging()
->distance_remaining() < distance;
}
return false;
}
+
bool BaseAutonomousActor::SplineHandle::WaitForSplineDistanceRemaining(
double distance) {
::aos::time::PhasedLoop phased_loop(
diff --git a/frc971/autonomous/base_autonomous_actor.h b/frc971/autonomous/base_autonomous_actor.h
index a70a440..5562dde 100644
--- a/frc971/autonomous/base_autonomous_actor.h
+++ b/frc971/autonomous/base_autonomous_actor.h
@@ -91,6 +91,11 @@
// Returns true if the drive has finished.
bool IsDriveDone();
+ // Returns the current x, y, theta of the robot on the field.
+ double X();
+ double Y();
+ double Theta();
+
void LineFollowAtVelocity(
double velocity,
y2019::control_loops::drivetrain::SelectionHint hint =
diff --git a/scouting/www/match_list/match_list.component.ts b/scouting/www/match_list/match_list.component.ts
index 9d93250..0deeb11 100644
--- a/scouting/www/match_list/match_list.component.ts
+++ b/scouting/www/match_list/match_list.component.ts
@@ -30,19 +30,37 @@
constructor(private readonly matchListRequestor: MatchListRequestor) {}
- // Returns a class for the row to hide it if all teams in this match have
- // already been scouted.
- getRowClass(match: Match): string {
+ // Returns true if the match is fully scouted. Returns false otherwise.
+ matchIsFullyScouted(match: Match): boolean {
const scouted = match.dataScouted();
- if (
- this.hideCompletedMatches &&
+ return (
scouted.r1() &&
scouted.r2() &&
scouted.r3() &&
scouted.b1() &&
scouted.b2() &&
scouted.b3()
- ) {
+ );
+ }
+
+ // Returns true if at least one team in this match has been scouted. Returns
+ // false otherwise.
+ matchIsPartiallyScouted(match: Match): boolean {
+ const scouted = match.dataScouted();
+ return (
+ scouted.r1() ||
+ scouted.r2() ||
+ scouted.r3() ||
+ scouted.b1() ||
+ scouted.b2() ||
+ scouted.b3()
+ );
+ }
+
+ // Returns a class for the row to hide it if all teams in this match have
+ // already been scouted.
+ getRowClass(match: Match): string {
+ if (this.hideCompletedMatches && this.matchIsFullyScouted(match)) {
return 'hidden_row';
}
return '';
@@ -110,7 +128,22 @@
displayMatchNumber(match: Match): string {
// Only display the set number for eliminations matches.
const setNumber = match.compLevel() == 'qm' ? '' : `${match.setNumber()}`;
- return `${this.matchType(match)} ${setNumber} Match ${match.matchNumber()}`;
+ const matchType = this.matchType(match);
+ const mainText = `${matchType} ${setNumber} Match ${match.matchNumber()}`;
+
+ // When showing the full match list (i.e. not hiding completed matches)
+ // it's useful to know if a match has already been scouted or not.
+ const suffix = (() => {
+ if (this.matchIsFullyScouted(match)) {
+ return '(fully scouted)';
+ } else if (this.matchIsPartiallyScouted(match)) {
+ return '(partially scouted)';
+ } else {
+ return '';
+ }
+ })();
+
+ return `${mainText} ${suffix}`;
}
ngOnInit() {
diff --git a/y2023/BUILD b/y2023/BUILD
index e92292b..095b856 100644
--- a/y2023/BUILD
+++ b/y2023/BUILD
@@ -60,6 +60,7 @@
"//y2023/constants:constants_sender",
"//y2023/vision:foxglove_image_converter",
"//aos/network:web_proxy_main",
+ ":joystick_republish",
"//aos/events/logging:log_cat",
"//y2023/rockpi:imu_main",
"//frc971/image_streamer:image_streamer",
@@ -327,6 +328,23 @@
],
)
+cc_binary(
+ name = "joystick_republish",
+ srcs = [
+ "joystick_republish.cc",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos:configuration",
+ "//aos:flatbuffer_merge",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//frc971/input:joystick_state_fbs",
+ "@com_github_google_glog//:glog",
+ ],
+)
+
py_library(
name = "python_init",
srcs = ["__init__.py"],
diff --git a/y2023/constants.cc b/y2023/constants.cc
index c2a09aa..f11c68c 100644
--- a/y2023/constants.cc
+++ b/y2023/constants.cc
@@ -83,19 +83,20 @@
break;
case kCompTeamNumber:
- arm_proximal->zeroing.measured_absolute_position = 0.138453705930275;
+ arm_proximal->zeroing.measured_absolute_position = 0.153241637089465;
arm_proximal->potentiometer_offset =
0.931355973012855 + 8.6743197253382 - 0.101200335326309 -
- 0.0820901660993467 - 0.0703733798337964 - 0.0294645384848748;
+ 0.0820901660993467 - 0.0703733798337964 - 0.0294645384848748 -
+ 0.577156175549626;
- arm_distal->zeroing.measured_absolute_position = 0.562947209110251;
+ arm_distal->zeroing.measured_absolute_position = 0.119544808434349;
arm_distal->potentiometer_offset =
0.436664933370656 + 0.49457213779426 + 6.78213223139724 -
0.0220711555235029 - 0.0162945074111813 + 0.00630344935527365 -
0.0164398318919943 - 0.145833494945215 + 0.234878799868491 +
- 0.125924230298394 + 0.147136306208754;
+ 0.125924230298394 + 0.147136306208754 - 0.69167546169753;
- roll_joint->zeroing.measured_absolute_position = 0.593975883699743;
+ roll_joint->zeroing.measured_absolute_position = 0.62315534539819;
roll_joint->potentiometer_offset =
-(3.87038557084874 - 0.0241774522172967 + 0.0711345168020632 -
0.866186131631967 - 0.0256788357596952 + 0.18101759154572017 -
@@ -105,7 +106,7 @@
0.0201047336425017 - 1.0173426655158 - 0.186085272847293 - 0.0317706563397807;
wrist->subsystem_params.zeroing_constants.measured_absolute_position =
- 0.894159203288852;
+ 1.00731305518279;
break;
@@ -119,10 +120,11 @@
7.673132586937 - 0.0799284644472573 - 0.0323574039310657 +
0.0143810684138064 + 0.00945555248207735;
- roll_joint->zeroing.measured_absolute_position = 1.7490367887908;
+ roll_joint->zeroing.measured_absolute_position = 1.85482286175059;
roll_joint->potentiometer_offset =
0.624713611895747 + 3.10458504917251 - 0.0966407797407789 +
- 0.0257708772364788 - 0.0395076737853459 - 6.87914956118006;
+ 0.0257708772364788 - 0.0395076737853459 - 6.87914956118006 -
+ 0.097581301615046;
wrist->subsystem_params.zeroing_constants.measured_absolute_position =
6.04062267812154;
diff --git a/y2023/constants.h b/y2023/constants.h
index 8996597..595a694 100644
--- a/y2023/constants.h
+++ b/y2023/constants.h
@@ -168,7 +168,7 @@
// Game object is spit from end effector for at least this time
static constexpr std::chrono::milliseconds kExtraSpittingTime() {
- return std::chrono::seconds(2);
+ return std::chrono::seconds(1);
}
// if true, tune down all the arm constants for testing.
diff --git a/y2023/control_loops/drivetrain/drivetrain_main.cc b/y2023/control_loops/drivetrain/drivetrain_main.cc
index b13e76f..eebae91 100644
--- a/y2023/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2023/control_loops/drivetrain/drivetrain_main.cc
@@ -15,6 +15,8 @@
aos::FlatbufferDetachedBuffer<aos::Configuration> config =
aos::configuration::ReadConfig("aos_config.json");
+ frc971::constants::WaitForConstants<y2023::Constants>(&config.message());
+
aos::ShmEventLoop event_loop(&config.message());
std::unique_ptr<::frc971::control_loops::drivetrain::PuppetLocalizer>
localizer = std::make_unique<
diff --git a/y2023/control_loops/python/drivetrain.py b/y2023/control_loops/python/drivetrain.py
index 05739fc..9d2b006 100644
--- a/y2023/control_loops/python/drivetrain.py
+++ b/y2023/control_loops/python/drivetrain.py
@@ -14,17 +14,17 @@
kDrivetrain = drivetrain.DrivetrainParams(
J=6.5,
- mass=58.0,
+ mass=68.0,
# TODO(austin): Measure radius a bit better.
robot_radius=0.39,
wheel_radius=2.5 * 0.0254,
motor_type=control_loop.Falcon(),
num_motors=3,
- G=(14.0 / 54.0) * (22.0 / 56.0),
+ G=(14.0 / 52.0) * (26.0 / 58.0),
q_pos=0.24,
q_vel=2.5,
- efficiency=0.75,
- has_imu=True,
+ efficiency=0.92,
+ has_imu=False,
force=True,
kf_q_voltage=1.0,
controller_poles=[0.82, 0.82])
diff --git a/y2023/control_loops/superstructure/end_effector.cc b/y2023/control_loops/superstructure/end_effector.cc
index 8ab2f27..444be0d 100644
--- a/y2023/control_loops/superstructure/end_effector.cc
+++ b/y2023/control_loops/superstructure/end_effector.cc
@@ -18,9 +18,9 @@
beambreak_(false) {}
void EndEffector::RunIteration(
- const ::aos::monotonic_clock::time_point timestamp, RollerGoal roller_goal,
- double falcon_current, double cone_position, bool beambreak,
- double *roller_voltage, bool preloaded_with_cone) {
+ const ::aos::monotonic_clock::time_point timestamp,
+ RollerGoal roller_goal, double falcon_current, double cone_position,
+ bool beambreak, double *roller_voltage, bool preloaded_with_cone) {
*roller_voltage = 0.0;
constexpr double kMinCurrent = 40.0;
@@ -32,6 +32,7 @@
switch (state_) {
case EndEffectorState::IDLE:
case EndEffectorState::INTAKING:
+ game_piece_ = vision::Class::CONE_UP;
state_ = EndEffectorState::LOADED;
break;
case EndEffectorState::LOADED:
@@ -124,6 +125,12 @@
// Finished spitting
state_ = EndEffectorState::IDLE;
game_piece_ = vision::Class::NONE;
+ } else if (roller_goal == RollerGoal::INTAKE_CONE_UP ||
+ roller_goal == RollerGoal::INTAKE_CONE_DOWN ||
+ roller_goal == RollerGoal::INTAKE_CUBE ||
+ roller_goal == RollerGoal::INTAKE_LAST) {
+ state_ = EndEffectorState::INTAKING;
+ timer_ = timestamp;
}
break;
diff --git a/y2023/joystick_reader.cc b/y2023/joystick_reader.cc
index 8d04056..efd7537 100644
--- a/y2023/joystick_reader.cc
+++ b/y2023/joystick_reader.cc
@@ -382,6 +382,8 @@
GamePiece current_game_piece_ = GamePiece::CONE_UP;
+ bool has_scored_ = false;
+
void HandleTeleop(
const ::frc971::input::driver_station::Data &data) override {
superstructure_status_fetcher_.Fetch();
@@ -445,6 +447,7 @@
// Ok, no active setpoint. Search for the right one.
if (current_setpoint_ == nullptr) {
+ has_scored_ = false;
const Side current_side =
data.IsPressed(kBack) ? Side::BACK : Side::FRONT;
// Search for the active setpoint.
@@ -485,13 +488,16 @@
// spit.
if (std::abs(score_wrist_goal.value() -
superstructure_status_fetcher_->wrist()->goal_position()) <
- 0.1) {
+ 0.1 ||
+ has_scored_) {
if (place_index.has_value()) {
arm_goal_position_ = place_index.value();
- if (arm_goal_position_ ==
- superstructure_status_fetcher_->arm()->current_node() &&
- superstructure_status_fetcher_->arm()->path_distance_to_go() <
- 0.01) {
+ if ((arm_goal_position_ ==
+ superstructure_status_fetcher_->arm()->current_node() &&
+ superstructure_status_fetcher_->arm()->path_distance_to_go() <
+ 0.01) ||
+ has_scored_) {
+ has_scored_ = true;
roller_goal = RollerGoal::SPIT;
}
} else {
diff --git a/y2023/joystick_republish.cc b/y2023/joystick_republish.cc
new file mode 100644
index 0000000..9542001
--- /dev/null
+++ b/y2023/joystick_republish.cc
@@ -0,0 +1,34 @@
+#include <sys/resource.h>
+#include <sys/time.h>
+
+#include "aos/configuration.h"
+#include "aos/init.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/init.h"
+#include "frc971/input/joystick_state_generated.h"
+#include "glog/logging.h"
+
+DEFINE_string(config, "aos_config.json", "Config file to use.");
+
+int main(int argc, char *argv[]) {
+ aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(FLAGS_config);
+ aos::ShmEventLoop event_loop(&config.message());
+
+ aos::Sender<aos::JoystickState> sender(
+ event_loop.MakeSender<aos::JoystickState>("/imu/aos"));
+
+ event_loop.MakeWatcher(
+ "/roborio/aos", [&](const aos::JoystickState &joystick_state) {
+ auto builder = sender.MakeBuilder();
+ flatbuffers::Offset<aos::JoystickState> state_fbs =
+ aos::CopyFlatBuffer(&joystick_state, builder.fbb());
+ builder.CheckOk(builder.Send(state_fbs));
+ });
+
+ event_loop.Run();
+ return 0;
+}
diff --git a/y2023/vision/camera_reader.cc b/y2023/vision/camera_reader.cc
index 7de3eb5..b526086 100644
--- a/y2023/vision/camera_reader.cc
+++ b/y2023/vision/camera_reader.cc
@@ -12,6 +12,7 @@
DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
DEFINE_bool(lowlight_camera, true, "Switch to use imx462 image sensor.");
+DEFINE_int32(gain, 200, "analogue_gain");
DEFINE_double(red, 1.252, "Red gain");
DEFINE_double(green, 1, "Green gain");
@@ -117,7 +118,7 @@
rkisp1_selfpath->device(),
camera->device());
if (FLAGS_lowlight_camera) {
- v4l2_reader_selfpath.SetGainExt(100);
+ v4l2_reader_selfpath.SetGainExt(FLAGS_gain);
v4l2_reader_selfpath.SetVerticalBlanking(1000);
v4l2_reader_selfpath.SetExposure(FLAGS_exposure);
} else {
diff --git a/y2023/vision/image_logger.cc b/y2023/vision/image_logger.cc
index b87cec0..d90f9c2 100644
--- a/y2023/vision/image_logger.cc
+++ b/y2023/vision/image_logger.cc
@@ -62,7 +62,7 @@
});
event_loop.MakeWatcher(
- "/roborio/aos", [&](const aos::JoystickState &joystick_state) {
+ "/imu/aos", [&](const aos::JoystickState &joystick_state) {
const auto timestamp = event_loop.context().monotonic_event_time;
// Store the last time we got disabled
if (enabled && !joystick_state.enabled()) {
diff --git a/y2023/y2023_imu.json b/y2023/y2023_imu.json
index e802795..416552b 100644
--- a/y2023/y2023_imu.json
+++ b/y2023/y2023_imu.json
@@ -2,6 +2,108 @@
"channels": [
{
"name": "/imu/aos",
+ "type": "aos.JoystickState",
+ "source_node": "imu",
+ "frequency": 100,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "pi1",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "pi2",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "pi3",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "pi4",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/logger/imu/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 300,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/pi1/imu/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 300,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/pi2/imu/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 300,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/pi3/imu/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 300,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/pi4/imu/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 300,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/aos",
"type": "aos.timing.Report",
"source_node": "imu",
"frequency": 50,
@@ -373,6 +475,14 @@
]
},
{
+ "name": "joystick_republish",
+ "executable_name": "joystick_republish",
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
"name": "message_bridge_server",
"executable_name": "message_bridge_server",
"user": "pi",
@@ -383,7 +493,12 @@
{
"name": "localizer_logger",
"executable_name": "logger_main",
- "args": ["--logging_folder", "", "--snappy_compress"],
+ "args": [
+ "--logging_folder",
+ "",
+ "--snappy_compress",
+ "--rotate_every", "30.0"
+ ],
"user": "pi",
"nodes": [
"imu"
@@ -392,6 +507,10 @@
{
"name": "web_proxy",
"executable_name": "web_proxy_main",
+ "args": [
+ "--min_ice_port=5800",
+ "--max_ice_port=5810"
+ ],
"user": "pi",
"nodes": [
"imu"
@@ -450,6 +569,18 @@
},
{
"name": "roborio"
+ },
+ {
+ "name": "pi1"
+ },
+ {
+ "name": "pi2"
+ },
+ {
+ "name": "pi3"
+ },
+ {
+ "name": "pi4"
}
]
}
diff --git a/y2023/y2023_pi_template.json b/y2023/y2023_pi_template.json
index 113e48f..8d9fdaa 100644
--- a/y2023/y2023_pi_template.json
+++ b/y2023/y2023_pi_template.json
@@ -377,6 +377,10 @@
"name": "web_proxy",
"executable_name": "web_proxy_main",
"user": "pi",
+ "args": [
+ "--min_ice_port=5800",
+ "--max_ice_port=5810"
+ ],
"nodes": [
"pi{{ NUM }}"
]
@@ -397,7 +401,7 @@
"--logging_folder",
"",
"--rotate_every",
- "60.0",
+ "30.0",
"--direct",
"--flush_size=4194304"
],
diff --git a/y2023/y2023_roborio.json b/y2023/y2023_roborio.json
index f3697ac..3114ac9 100644
--- a/y2023/y2023_roborio.json
+++ b/y2023/y2023_roborio.json
@@ -6,7 +6,7 @@
"source_node": "roborio",
"frequency": 100,
"logger": "LOCAL_AND_REMOTE_LOGGER",
- "logger_nodes" : [
+ "logger_nodes": [
"imu",
"logger"
],
@@ -19,51 +19,6 @@
"timestamp_logger_nodes": [
"roborio"
]
- },
- {
- "name": "logger",
- "priority": 5,
- "time_to_live": 50000000,
- "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes": [
- "roborio"
- ]
- },
- {
- "name": "pi1",
- "priority": 5,
- "time_to_live": 50000000,
- "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes": [
- "roborio"
- ]
- },
- {
- "name": "pi2",
- "priority": 5,
- "time_to_live": 50000000,
- "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes": [
- "roborio"
- ]
- },
- {
- "name": "pi3",
- "priority": 5,
- "time_to_live": 50000000,
- "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes": [
- "roborio"
- ]
- },
- {
- "name": "pi4",
- "priority": 5,
- "time_to_live": 50000000,
- "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes": [
- "roborio"
- ]
}
]
},
@@ -77,51 +32,6 @@
"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": 300,
- "num_senders": 2,
- "max_size": 200
- },
- {
- "name": "/roborio/aos/remote_timestamps/pi1/roborio/aos/aos-JoystickState",
- "type": "aos.message_bridge.RemoteMessage",
- "source_node": "roborio",
- "logger": "NOT_LOGGED",
- "frequency": 300,
- "num_senders": 2,
- "max_size": 200
- },
- {
- "name": "/roborio/aos/remote_timestamps/pi2/roborio/aos/aos-JoystickState",
- "type": "aos.message_bridge.RemoteMessage",
- "source_node": "roborio",
- "logger": "NOT_LOGGED",
- "frequency": 300,
- "num_senders": 2,
- "max_size": 200
- },
- {
- "name": "/roborio/aos/remote_timestamps/pi3/roborio/aos/aos-JoystickState",
- "type": "aos.message_bridge.RemoteMessage",
- "source_node": "roborio",
- "logger": "NOT_LOGGED",
- "frequency": 300,
- "num_senders": 2,
- "max_size": 200
- },
- {
- "name": "/roborio/aos/remote_timestamps/pi4/roborio/aos/aos-JoystickState",
- "type": "aos.message_bridge.RemoteMessage",
- "source_node": "roborio",
- "logger": "NOT_LOGGED",
- "frequency": 300,
- "num_senders": 2,
- "max_size": 200
- },
- {
"name": "/roborio/aos",
"type": "aos.RobotState",
"source_node": "roborio",
@@ -608,7 +518,10 @@
{
"name": "roborio_web_proxy",
"executable_name": "web_proxy_main",
- "args": ["--min_ice_port=5800", "--max_ice_port=5810"],
+ "args": [
+ "--min_ice_port=5800",
+ "--max_ice_port=5810"
+ ],
"nodes": [
"roborio"
]
@@ -616,7 +529,9 @@
{
"name": "roborio_message_bridge_client",
"executable_name": "message_bridge_client",
- "args": ["--rt_priority=16"],
+ "args": [
+ "--rt_priority=16"
+ ],
"nodes": [
"roborio"
]
@@ -624,7 +539,9 @@
{
"name": "roborio_message_bridge_server",
"executable_name": "message_bridge_server",
- "args": ["--rt_priority=16"],
+ "args": [
+ "--rt_priority=16"
+ ],
"nodes": [
"roborio"
]
@@ -632,7 +549,11 @@
{
"name": "logger",
"executable_name": "logger_main",
- "args": ["--snappy_compress", "--logging_folder=/home/admin/logs/"],
+ "args": [
+ "--snappy_compress",
+ "--logging_folder=/home/admin/logs/",
+ "--rotate_every", "30.0"
+ ],
"nodes": [
"roborio"
]