Move aos/input and aos/robot_state to frc971/input
Neither folder makes any sense as part of aos/.
Change-Id: I10e0532da4e688c18a9354012b783c43566fd2a1
diff --git a/aos/controls/BUILD b/aos/controls/BUILD
index 14890d4..027b8ca 100644
--- a/aos/controls/BUILD
+++ b/aos/controls/BUILD
@@ -16,8 +16,8 @@
"//aos:flatbuffers",
"//aos:json_to_flatbuffer",
"//aos/events:simulated_event_loop",
- "//aos/robot_state:joystick_state_fbs",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:joystick_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/testing:googletest",
"//aos/testing:test_logging",
"//aos/time",
@@ -77,8 +77,8 @@
"//aos/events:event_loop",
"//aos/events:shm_event_loop",
"//aos/logging",
- "//aos/robot_state:joystick_state_fbs",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:joystick_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/time",
"//aos/util:log_interval",
],
diff --git a/aos/controls/control_loop.h b/aos/controls/control_loop.h
index 6f1b487..efe3493 100644
--- a/aos/controls/control_loop.h
+++ b/aos/controls/control_loop.h
@@ -2,14 +2,15 @@
#define AOS_CONTROL_LOOP_CONTROL_LOOP_H_
#include <string.h>
+
#include <atomic>
#include "aos/events/event_loop.h"
-#include "aos/robot_state/joystick_state_generated.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/time/time.h"
#include "aos/type_traits/type_traits.h"
#include "aos/util/log_interval.h"
+#include "frc971/input/joystick_state_generated.h"
+#include "frc971/input/robot_state_generated.h"
namespace aos {
namespace controls {
diff --git a/aos/controls/control_loop_test.h b/aos/controls/control_loop_test.h
index 536df02..7fbc94a 100644
--- a/aos/controls/control_loop_test.h
+++ b/aos/controls/control_loop_test.h
@@ -7,10 +7,10 @@
#include "aos/events/simulated_event_loop.h"
#include "aos/flatbuffers.h"
#include "aos/json_to_flatbuffer.h"
-#include "aos/robot_state/joystick_state_generated.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/testing/test_logging.h"
#include "aos/time/time.h"
+#include "frc971/input/joystick_state_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "gtest/gtest.h"
namespace aos {
diff --git a/aos/debugging-tips.txt b/aos/debugging-tips.txt
deleted file mode 100644
index 9bbe8d3..0000000
--- a/aos/debugging-tips.txt
+++ /dev/null
@@ -1,45 +0,0 @@
-[General]
-Check the logs! Very few things will fail without putting something in the logs.
- If they do, that is a bug unless our code is never getting run (there are
- innumerable ways that could happen, but it generally doesn't).
- To check the logs, run `log_displayer` if `binary_log_writer` has been started
- or just run `log_streamer` if you want to do simple testing without writing
- logs to a file. See `log_displayer --help` for options.
-All of the binaries get put in the same place. That is
- src/outputs/prime/outputs on the build machine and
- /home/driver/robot_code/bin on linux.
-
-[Startup]
-Low level startup errors often end up in
- /tmp/aos_fatal_error.* under linux. Also helpful are the /tmp/starter*_std*
- files (if the standard start scripts are being used).
- If lots of the /tmp/starter_*std* files (with different numbers) are being
- created, that means that starter_exe is dying constantly.
-
-[Anything Not Running]
-Check starter_exe's log messages. They might mention that it is constantly dying
- on startup and being restarted.
-
-[Control Loop(s) Not Working]
-Are robot_state messages going out? An aos::JoystickInput (often
- joystick_reader) should be sending them.
- Also, kFakeJoysticks in aos/input/joystick_reader.cc has to be set to
- false in order for anything to get output.
-Is it being fed goal messages?
-Is it getting position messages?
-Is something looking at the output and doing something useful with it?
-
-[No Driver Station Packets]
-TODO(brians): This is out of date.
-Check to make sure that JSR (a cRIO-side task) is saying that it's sending
- messages. Also check JoystickReader (or whatever inherits from
- aos::JoystickInput) is running and see if it's receiving anything.
-
-[Attaching a Debugger]
-Attaching GDB to an existing robot code process works like normal (you have to
- su root first because that's what all of the code currently runs as).
-If a process is dying repeatedly, the easiest way to debug it is to kill
- starter_loop.sh and (it has to be after that) starter_exe. After doing that,
- NOTHING will get restarted (including the normal restart after changing a
- binary) so that you can start a process under GDB like usual (shouldn't need
- anything special if done as root).
diff --git a/aos/robot_state/BUILD b/aos/robot_state/BUILD
deleted file mode 100644
index 663c8c6..0000000
--- a/aos/robot_state/BUILD
+++ /dev/null
@@ -1,30 +0,0 @@
-package(default_visibility = ["//visibility:public"])
-
-load("//aos:config.bzl", "aos_config")
-load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
-
-flatbuffer_cc_library(
- name = "robot_state_fbs",
- srcs = ["robot_state.fbs"],
- gen_reflections = 1,
- target_compatible_with = ["@platforms//os:linux"],
-)
-
-flatbuffer_cc_library(
- name = "joystick_state_fbs",
- srcs = ["joystick_state.fbs"],
- gen_reflections = 1,
- target_compatible_with = ["@platforms//os:linux"],
-)
-
-aos_config(
- name = "config",
- src = "robot_state_config.json",
- flatbuffers = [
- "//aos/robot_state:joystick_state_fbs",
- "//aos/robot_state:robot_state_fbs",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- visibility = ["//visibility:public"],
- deps = ["//aos/events:config"],
-)
diff --git a/frc971/codelab/BUILD b/frc971/codelab/BUILD
index c50a2c1..d5c1c59 100644
--- a/frc971/codelab/BUILD
+++ b/frc971/codelab/BUILD
@@ -84,6 +84,6 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
],
)
diff --git a/frc971/codelab/codelab.json b/frc971/codelab/codelab.json
index dedb19f..49e35b3 100644
--- a/frc971/codelab/codelab.json
+++ b/frc971/codelab/codelab.json
@@ -18,6 +18,6 @@
}
],
"imports": [
- "../../aos/robot_state/robot_state_config.json"
+ "../../frc971/input/robot_state_config.json"
]
}
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index f1c54a7..ec480c0 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -152,7 +152,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
],
)
@@ -317,7 +317,7 @@
"//aos:math",
"//aos/controls:control_loop",
"//aos/controls:polytope",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/util:log_interval",
"//aos/util:trapezoid_profile",
"//frc971:shifter_hall_effect",
@@ -355,7 +355,7 @@
":drivetrain_output_fbs",
":drivetrain_position_fbs",
":drivetrain_status_fbs",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/util:log_interval",
],
"@platforms//os:none": [
diff --git a/frc971/control_loops/drivetrain/drivetrain_simulation_config.json b/frc971/control_loops/drivetrain/drivetrain_simulation_config.json
index c113bc0..8523cb1 100644
--- a/frc971/control_loops/drivetrain/drivetrain_simulation_config.json
+++ b/frc971/control_loops/drivetrain/drivetrain_simulation_config.json
@@ -1,6 +1,6 @@
{
"imports": [
- "../../../aos/robot_state/robot_state_config.json",
+ "../../../frc971/input/robot_state_config.json",
"drivetrain_config.json",
"drivetrain_simulation_channels.json"
]
diff --git a/frc971/control_loops/drivetrain/polydrivetrain.h b/frc971/control_loops/drivetrain/polydrivetrain.h
index 17a32b8..fe733bb 100644
--- a/frc971/control_loops/drivetrain/polydrivetrain.h
+++ b/frc971/control_loops/drivetrain/polydrivetrain.h
@@ -7,12 +7,12 @@
#include "frc971/control_loops/drivetrain/gear.h"
#ifdef __linux__
#include "aos/logging/logging.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/input/robot_state_generated.h"
#else
#include "frc971/control_loops/drivetrain/drivetrain_goal_float_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_float_generated.h"
diff --git a/aos/input/BUILD b/frc971/input/BUILD
similarity index 62%
rename from aos/input/BUILD
rename to frc971/input/BUILD
index df00fd5..72be201 100644
--- a/aos/input/BUILD
+++ b/frc971/input/BUILD
@@ -1,5 +1,8 @@
package(default_visibility = ["//visibility:public"])
+load("//aos:config.bzl", "aos_config")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+
cc_library(
name = "joystick_input",
srcs = [
@@ -10,10 +13,10 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
+ ":robot_state_fbs",
"//aos/events:event_loop",
- "//aos/input:driver_station_data",
+ "//frc971/input:driver_station_data",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
],
)
@@ -27,10 +30,10 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
+ ":robot_state_fbs",
"//aos:math",
- "//aos/input:driver_station_data",
+ "//frc971/input:driver_station_data",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
"//frc971/control_loops:control_loops_fbs",
"//frc971/control_loops/drivetrain:drivetrain_config",
"//frc971/control_loops/drivetrain:drivetrain_goal_fbs",
@@ -49,7 +52,7 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
- "//aos/robot_state:joystick_state_fbs",
+ ":joystick_state_fbs",
"@com_github_google_glog//:glog",
],
)
@@ -63,10 +66,36 @@
":drivetrain_input",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:joystick_input",
+ "//frc971/input:joystick_input",
"//aos/logging",
"//frc971/autonomous:auto_fbs",
"//frc971/autonomous:auto_mode_fbs",
"//frc971/autonomous:base_autonomous_actor",
],
)
+
+flatbuffer_cc_library(
+ name = "robot_state_fbs",
+ srcs = ["robot_state.fbs"],
+ gen_reflections = 1,
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+flatbuffer_cc_library(
+ name = "joystick_state_fbs",
+ srcs = ["joystick_state.fbs"],
+ gen_reflections = 1,
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+aos_config(
+ name = "config",
+ src = "robot_state_config.json",
+ flatbuffers = [
+ ":joystick_state_fbs",
+ ":robot_state_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = ["//aos/events:config"],
+)
diff --git a/aos/input/action_joystick_input.cc b/frc971/input/action_joystick_input.cc
similarity index 86%
rename from aos/input/action_joystick_input.cc
rename to frc971/input/action_joystick_input.cc
index 1178818..4f1d655 100644
--- a/aos/input/action_joystick_input.cc
+++ b/frc971/input/action_joystick_input.cc
@@ -1,17 +1,17 @@
-#include "aos/input/action_joystick_input.h"
+#include "frc971/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
#include "frc971/autonomous/auto_generated.h"
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/input/driver_station_data.h"
-using ::aos::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::ControlBit;
-namespace aos {
+namespace frc971 {
namespace input {
void ActionJoystickInput::RunIteration(
- const ::aos::input::driver_station::Data &data) {
+ const ::frc971::input::driver_station::Data &data) {
const bool last_auto_running = auto_running_;
auto_running_ = data.GetControlBit(ControlBit::kAutonomous) &&
data.GetControlBit(ControlBit::kEnabled);
@@ -64,4 +64,4 @@
}
} // namespace input
-} // namespace aos
+} // namespace frc971
diff --git a/aos/input/action_joystick_input.h b/frc971/input/action_joystick_input.h
similarity index 87%
rename from aos/input/action_joystick_input.h
rename to frc971/input/action_joystick_input.h
index 562d41a..cdd0aa6 100644
--- a/aos/input/action_joystick_input.h
+++ b/frc971/input/action_joystick_input.h
@@ -1,21 +1,21 @@
#ifndef AOS_INPUT_ACTION_JOYSTICK_INPUT_H_
#define AOS_INPUT_ACTION_JOYSTICK_INPUT_H_
-#include "aos/input/driver_station_data.h"
-#include "aos/input/drivetrain_input.h"
-#include "aos/input/joystick_input.h"
#include "frc971/autonomous/auto_generated.h"
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
-namespace aos {
+namespace frc971 {
namespace input {
// Class to abstract out managing actions, autonomous mode, and drivetrains.
// Turns out we do the same thing every year, so let's stop copying it.
-class ActionJoystickInput : public ::aos::input::JoystickInput {
+class ActionJoystickInput : public ::frc971::input::JoystickInput {
public:
- // Configuration parameters that don't really belong in the DrivetrainConfig.
+ // Configuration parameters that don't really belong in the DrivetrainConfig.
struct InputConfig {
// If true, we will run teleop during auto mode after auto mode ends. This
// is to support the 2019 sandstorm mode. Auto will run, and then when the
@@ -32,7 +32,7 @@
&dt_config,
DrivetrainInputReader::InputType input_type,
const InputConfig &input_config)
- : ::aos::input::JoystickInput(event_loop),
+ : ::frc971::input::JoystickInput(event_loop),
input_config_(input_config),
drivetrain_input_reader_(
DrivetrainInputReader::Make(event_loop, input_type, dt_config)),
@@ -76,7 +76,7 @@
// no drivetain code is run. If it returns false, the vision align function
// is assumed to be disabled and normal drive code is run.
void set_vision_align_fn(
- ::std::function<bool(const ::aos::input::driver_station::Data &data)>
+ ::std::function<bool(const ::frc971::input::driver_station::Data &data)>
vision_align_fn) {
drivetrain_input_reader_->set_vision_align_fn(vision_align_fn);
}
@@ -85,9 +85,10 @@
// Handles anything that needs to be cleaned up when the auto action exits.
virtual void AutoEnded() {}
// Handles any year specific superstructure code.
- virtual void HandleTeleop(const ::aos::input::driver_station::Data &data) = 0;
+ virtual void HandleTeleop(
+ const ::frc971::input::driver_station::Data &data) = 0;
- void RunIteration(const ::aos::input::driver_station::Data &data) override;
+ void RunIteration(const ::frc971::input::driver_station::Data &data) override;
void StartAuto();
void StopAuto();
@@ -127,6 +128,6 @@
};
} // namespace input
-} // namespace aos
+} // namespace frc971
#endif // AOS_INPUT_ACTION_JOYSTICK_INPUT_H_
diff --git a/aos/input/driver_station_data.cc b/frc971/input/driver_station_data.cc
similarity index 87%
rename from aos/input/driver_station_data.cc
rename to frc971/input/driver_station_data.cc
index 9e3bc52..18d96fd 100644
--- a/aos/input/driver_station_data.cc
+++ b/frc971/input/driver_station_data.cc
@@ -1,21 +1,20 @@
-#include "aos/input/driver_station_data.h"
+#include "frc971/input/driver_station_data.h"
#include "glog/logging.h"
-namespace aos {
+namespace frc971 {
namespace input {
namespace driver_station {
Data::Data() : current_values_(), old_values_() {}
-void Data::Update(const JoystickState *new_values) {
+void Data::Update(const aos::JoystickState *new_values) {
old_values_ = current_values_;
CHECK(new_values->has_joysticks());
CHECK_EQ(new_values->joysticks()->size(), current_values_.joysticks.size());
for (size_t i = 0; i < current_values_.joysticks.size(); ++i) {
- const Joystick *joystick = new_values->joysticks()->Get(i);
- current_values_.joysticks[i].buttons =
- joystick->buttons();
+ const aos::Joystick *joystick = new_values->joysticks()->Get(i);
+ current_values_.joysticks[i].buttons = joystick->buttons();
current_values_.joysticks[i].pov = joystick->pov();
for (size_t j = 0; j < joystick->axis()->size(); ++j) {
current_values_.joysticks[i].axis[j] = joystick->axis()->Get(j);
@@ -72,12 +71,12 @@
bool Data::PosEdge(const ButtonLocation location) const {
return !GetButton(location, old_values_) &&
- GetButton(location, current_values_);
+ GetButton(location, current_values_);
}
bool Data::NegEdge(const ButtonLocation location) const {
return GetButton(location, old_values_) &&
- !GetButton(location, current_values_);
+ !GetButton(location, current_values_);
}
bool Data::IsPressed(const POVLocation location) const {
@@ -108,12 +107,12 @@
bool Data::PosEdge(const ControlBit bit) const {
return !GetControlBitValue(bit, old_values_) &&
- GetControlBitValue(bit, current_values_);
+ GetControlBitValue(bit, current_values_);
}
bool Data::NegEdge(const ControlBit bit) const {
return GetControlBitValue(bit, old_values_) &&
- !GetControlBitValue(bit, current_values_);
+ !GetControlBitValue(bit, current_values_);
}
float Data::GetAxis(JoystickAxis axis) const {
@@ -122,4 +121,4 @@
} // namespace driver_station
} // namespace input
-} // namespace aos
+} // namespace frc971
diff --git a/aos/input/driver_station_data.h b/frc971/input/driver_station_data.h
similarity index 89%
rename from aos/input/driver_station_data.h
rename to frc971/input/driver_station_data.h
index 18eb579..c5c38b4 100644
--- a/aos/input/driver_station_data.h
+++ b/frc971/input/driver_station_data.h
@@ -7,9 +7,9 @@
#include <array>
#include <memory>
-#include "aos/robot_state/joystick_state_generated.h"
+#include "frc971/input/joystick_state_generated.h"
-namespace aos {
+namespace frc971 {
namespace input {
namespace driver_station {
@@ -49,23 +49,19 @@
// Safe for static initialization.
class POVLocation : public JoystickFeature {
public:
- POVLocation(int joystick, int number)
- : JoystickFeature(joystick, number) {}
+ POVLocation(int joystick, int number) : JoystickFeature(joystick, number) {}
};
// Represents various bits of control information that the DS sends.
// Use Data to actually get the value.
-enum class ControlBit {
- kTestMode, kFmsAttached, kAutonomous, kEnabled
-};
+enum class ControlBit { kTestMode, kFmsAttached, kAutonomous, kEnabled };
// Represents a single axis of a joystick.
// Use Data to actually get the value.
// Safe for static initialization.
class JoystickAxis : public JoystickFeature {
public:
- JoystickAxis(int joystick, int number)
- : JoystickFeature(joystick, number) {}
+ JoystickAxis(int joystick, int number) : JoystickFeature(joystick, number) {}
// How many axes there are available on each joystick.
static const int kAxes = 6;
@@ -78,7 +74,7 @@
Data();
// Updates the current information with a new set of values.
- void Update(const JoystickState *new_values);
+ void Update(const aos::JoystickState *new_values);
bool IsPressed(POVLocation location) const;
bool PosEdge(POVLocation location) const;
@@ -132,6 +128,6 @@
} // namespace driver_station
} // namespace input
-} // namespace aos
+} // namespace frc971
#endif // AOS_INPUT_DRIVER_STATION_DATA_H_
diff --git a/aos/input/drivetrain_input.cc b/frc971/input/drivetrain_input.cc
similarity index 90%
rename from aos/input/drivetrain_input.cc
rename to frc971/input/drivetrain_input.cc
index 8860c4d..cefb113 100644
--- a/aos/input/drivetrain_input.cc
+++ b/frc971/input/drivetrain_input.cc
@@ -1,31 +1,32 @@
-#include "aos/input/drivetrain_input.h"
+#include "frc971/input/drivetrain_input.h"
#include <math.h>
#include <stdio.h>
#include <string.h>
+
#include <cmath>
#include "aos/commonmath.h"
-#include "aos/input/driver_station_data.h"
#include "aos/logging/logging.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/input/driver_station_data.h"
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::ControlBit;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::POVLocation;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
+using ::frc971::input::driver_station::POVLocation;
namespace drivetrain = frc971::control_loops::drivetrain;
-namespace aos {
+namespace frc971 {
namespace input {
const ButtonLocation kShiftHigh(2, 3), kShiftHigh2(2, 2), kShiftLow(2, 1);
void DrivetrainInputReader::HandleDrivetrain(
- const ::aos::input::driver_station::Data &data) {
+ const ::frc971::input::driver_station::Data &data) {
const auto wheel_and_throttle = GetWheelAndThrottle(data);
const double wheel = wheel_and_throttle.wheel;
const double wheel_velocity = wheel_and_throttle.wheel_velocity;
@@ -107,10 +108,10 @@
goal_builder.add_highgear(high_gear);
goal_builder.add_quickturn(data.IsPressed(quick_turn_));
goal_builder.add_controller_type(
- is_line_following
- ? drivetrain::ControllerType::LINE_FOLLOWER
- : (is_control_loop_driving ? drivetrain::ControllerType::MOTION_PROFILE
- : drivetrain::ControllerType::POLYDRIVE));
+ is_line_following ? drivetrain::ControllerType::LINE_FOLLOWER
+ : (is_control_loop_driving
+ ? drivetrain::ControllerType::MOTION_PROFILE
+ : drivetrain::ControllerType::POLYDRIVE));
goal_builder.add_left_goal(current_left_goal);
goal_builder.add_right_goal(current_right_goal);
goal_builder.add_linear(linear_offset);
@@ -124,7 +125,7 @@
DrivetrainInputReader::WheelAndThrottle
SteeringWheelDrivetrainInputReader::GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) {
+ const ::frc971::input::driver_station::Data &data) {
const double wheel = -data.GetAxis(wheel_);
const double throttle = -data.GetAxis(throttle_);
@@ -144,7 +145,7 @@
wheel, 0.0, 0.0, throttle, 0.0, 0.0, high_gear_};
}
-double UnwrappedAxis(const ::aos::input::driver_station::Data &data,
+double UnwrappedAxis(const ::frc971::input::driver_station::Data &data,
const JoystickAxis &high_bits,
const JoystickAxis &low_bits) {
const float high_bits_data = data.GetAxis(high_bits);
@@ -173,18 +174,17 @@
DrivetrainInputReader::WheelAndThrottle
PistolDrivetrainInputReader::GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) {
- const double wheel =
- -UnwrappedAxis(data, wheel_, wheel_low_);
+ const ::frc971::input::driver_station::Data &data) {
+ const double wheel = -UnwrappedAxis(data, wheel_, wheel_low_);
const double wheel_velocity =
-UnwrappedAxis(data, wheel_velocity_high_, wheel_velocity_low_) * 50.0;
const double wheel_torque =
-UnwrappedAxis(data, wheel_torque_high_, wheel_torque_low_) / 2.0;
- double throttle =
- UnwrappedAxis(data, throttle_, throttle_low_);
+ double throttle = UnwrappedAxis(data, throttle_, throttle_low_);
const double throttle_velocity =
- UnwrappedAxis(data, throttle_velocity_high_, throttle_velocity_low_) * 50.0;
+ UnwrappedAxis(data, throttle_velocity_high_, throttle_velocity_low_) *
+ 50.0;
const double throttle_torque =
UnwrappedAxis(data, throttle_torque_high_, throttle_torque_low_) / 2.0;
@@ -210,14 +210,14 @@
}
return DrivetrainInputReader::WheelAndThrottle{
- wheel, wheel_velocity, wheel_torque,
- throttle, throttle_velocity, throttle_torque,
+ wheel, wheel_velocity, wheel_torque,
+ throttle, throttle_velocity, throttle_torque,
high_gear_};
}
DrivetrainInputReader::WheelAndThrottle
XboxDrivetrainInputReader::GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) {
+ const ::frc971::input::driver_station::Data &data) {
// xbox
constexpr double kWheelDeadband = 0.05;
constexpr double kThrottleDeadband = 0.05;
@@ -345,4 +345,4 @@
}
} // namespace input
-} // namespace aos
+} // namespace frc971
diff --git a/aos/input/drivetrain_input.h b/frc971/input/drivetrain_input.h
similarity index 93%
rename from aos/input/drivetrain_input.h
rename to frc971/input/drivetrain_input.h
index 0c43d99..9e450d5 100644
--- a/aos/input/drivetrain_input.h
+++ b/frc971/input/drivetrain_input.h
@@ -4,17 +4,18 @@
#include <math.h>
#include <stdio.h>
#include <string.h>
+
#include <cmath>
#include <memory>
-#include "aos/input/driver_station_data.h"
#include "aos/logging/logging.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/input/driver_station_data.h"
-namespace aos {
+namespace frc971 {
namespace input {
// We have a couple different joystick configurations used to drive our skid
@@ -84,7 +85,7 @@
&dt_config);
// Processes new joystick data and publishes drivetrain goal messages.
- void HandleDrivetrain(const ::aos::input::driver_station::Data &data);
+ void HandleDrivetrain(const ::frc971::input::driver_station::Data &data);
// Sets the scalar for the steering wheel for closed loop mode converting
// steering ratio to meters displacement on the two wheels.
@@ -96,7 +97,7 @@
double robot_velocity() const { return robot_velocity_; }
void set_vision_align_fn(
- ::std::function<bool(const ::aos::input::driver_station::Data &data)>
+ ::std::function<bool(const ::frc971::input::driver_station::Data &data)>
vision_align_fn) {
vision_align_fn_ = vision_align_fn;
}
@@ -129,7 +130,7 @@
private:
// Computes the steering and throttle from the provided driverstation data.
virtual WheelAndThrottle GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) = 0;
+ const ::frc971::input::driver_station::Data &data) = 0;
::aos::Fetcher<::frc971::control_loops::drivetrain::Status>
drivetrain_status_fetcher_;
@@ -144,7 +145,7 @@
// joysticks to meters displacement on the two wheels.
double wheel_multiplier_ = 0.5;
- ::std::function<bool(const ::aos::input::driver_station::Data &data)>
+ ::std::function<bool(const ::frc971::input::driver_station::Data &data)>
vision_align_fn_;
};
@@ -166,7 +167,7 @@
private:
WheelAndThrottle GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) override;
+ const ::frc971::input::driver_station::Data &data) override;
bool high_gear_;
bool default_high_gear_;
};
@@ -227,7 +228,7 @@
slow_down_(slow_down) {}
WheelAndThrottle GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) override;
+ const ::frc971::input::driver_station::Data &data) override;
// Sets the default shifter position
void set_default_high_gear(bool default_high_gear) {
@@ -266,10 +267,10 @@
private:
WheelAndThrottle GetWheelAndThrottle(
- const ::aos::input::driver_station::Data &data) override;
+ const ::frc971::input::driver_station::Data &data) override;
};
} // namespace input
-} // namespace aos
+} // namespace frc971
#endif // AOS_INPUT_DRIVETRAIN_INPUT_H_
diff --git a/aos/input/joystick_input.cc b/frc971/input/joystick_input.cc
similarity index 92%
rename from aos/input/joystick_input.cc
rename to frc971/input/joystick_input.cc
index 743e138..c92d567 100644
--- a/aos/input/joystick_input.cc
+++ b/frc971/input/joystick_input.cc
@@ -1,12 +1,13 @@
-#include "aos/input/joystick_input.h"
+#include "frc971/input/joystick_input.h"
#include <string.h>
+
#include <atomic>
#include "aos/logging/logging.h"
-#include "aos/robot_state/robot_state_generated.h"
+#include "frc971/input/robot_state_generated.h"
-namespace aos {
+namespace frc971 {
namespace input {
void JoystickInput::HandleData(const ::aos::JoystickState *joystick_state) {
@@ -16,8 +17,8 @@
(static_cast<int>(joystick_state->scale_left()) << 1);
{
- using driver_station::JoystickFeature;
using driver_station::ButtonLocation;
+ using driver_station::JoystickFeature;
for (int joystick = 1; joystick <= JoystickFeature::kJoysticks;
++joystick) {
for (int button = 1; button <= ButtonLocation::kButtons; ++button) {
@@ -61,4 +62,4 @@
}
} // namespace input
-} // namespace aos
+} // namespace frc971
diff --git a/aos/input/joystick_input.h b/frc971/input/joystick_input.h
similarity index 89%
rename from aos/input/joystick_input.h
rename to frc971/input/joystick_input.h
index aceda52..074908d 100644
--- a/aos/input/joystick_input.h
+++ b/frc971/input/joystick_input.h
@@ -4,9 +4,9 @@
#include <atomic>
#include "aos/events/event_loop.h"
-#include "aos/input/driver_station_data.h"
+#include "frc971/input/driver_station_data.h"
-namespace aos {
+namespace frc971 {
namespace input {
// A class for handling joystick packet values.
@@ -34,13 +34,13 @@
// Subclasses should do whatever they want with data here.
virtual void RunIteration(const driver_station::Data &data) = 0;
- EventLoop *event_loop_;
+ ::aos::EventLoop *event_loop_;
driver_station::Data data_;
int mode_;
};
} // namespace input
-} // namespace aos
+} // namespace frc971
#endif // AOS_INPUT_JOYSTICK_INPUT_H_
diff --git a/aos/robot_state/joystick_state.fbs b/frc971/input/joystick_state.fbs
similarity index 100%
rename from aos/robot_state/joystick_state.fbs
rename to frc971/input/joystick_state.fbs
diff --git a/aos/robot_state/robot_state.fbs b/frc971/input/robot_state.fbs
similarity index 100%
rename from aos/robot_state/robot_state.fbs
rename to frc971/input/robot_state.fbs
diff --git a/aos/robot_state/robot_state_config.json b/frc971/input/robot_state_config.json
similarity index 82%
rename from aos/robot_state/robot_state_config.json
rename to frc971/input/robot_state_config.json
index 37cc160..781dd6c 100644
--- a/aos/robot_state/robot_state_config.json
+++ b/frc971/input/robot_state_config.json
@@ -13,6 +13,6 @@
}
],
"imports": [
- "../events/aos.json"
+ "../../../org_frc971/aos/events/aos.json"
]
}
diff --git a/frc971/wpilib/BUILD b/frc971/wpilib/BUILD
index 00896bb..4f8bca0 100644
--- a/frc971/wpilib/BUILD
+++ b/frc971/wpilib/BUILD
@@ -115,7 +115,7 @@
"//aos/events:event_loop",
"//aos/events:shm_event_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/time",
"//aos/util:phased_loop",
"//frc971/queues:gyro_fbs",
@@ -167,7 +167,7 @@
deps = [
"//aos:init",
"//aos/events:event_loop",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/scoped:scoped_fd",
"//aos/time",
"//aos/util:log_interval",
@@ -204,9 +204,9 @@
deps = [
"//aos:init",
"//aos/events:shm_event_loop",
- "//aos/input:driver_station_data",
+ "//frc971/input:driver_station_data",
"//aos/network:team_number",
- "//aos/robot_state:joystick_state_fbs",
+ "//frc971/input:joystick_state_fbs",
"//third_party:wpilib",
],
)
@@ -222,7 +222,7 @@
target_compatible_with = ["//tools/platforms/hardware:roborio"],
deps = [
"//aos/events:event_loop",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//third_party:wpilib",
],
)
diff --git a/frc971/wpilib/gyro_sender.cc b/frc971/wpilib/gyro_sender.cc
index 2bdcc76..3061c3b 100644
--- a/frc971/wpilib/gyro_sender.cc
+++ b/frc971/wpilib/gyro_sender.cc
@@ -10,9 +10,8 @@
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
#include "aos/logging/logging.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/time/time.h"
-
+#include "frc971/input/robot_state_generated.h"
#include "frc971/queues/gyro_generated.h"
#include "frc971/queues/gyro_uid_generated.h"
#include "frc971/zeroing/averager.h"
@@ -31,9 +30,9 @@
gyro_reading_sender_(
event_loop_->MakeSender<frc971::sensors::GyroReading>(
"/drivetrain")) {
- AOS_PCHECK(
- system("busybox ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | xargs chrt -f -p "
- "33") == 0);
+ AOS_PCHECK(system("busybox ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | "
+ "xargs chrt -f -p "
+ "33") == 0);
event_loop->set_name("Gyro");
event_loop_->SetRuntimeRealtimePriority(33);
diff --git a/frc971/wpilib/gyro_sender.h b/frc971/wpilib/gyro_sender.h
index a0048fb..91257c9 100644
--- a/frc971/wpilib/gyro_sender.h
+++ b/frc971/wpilib/gyro_sender.h
@@ -7,7 +7,7 @@
#include "aos/events/event_loop.h"
#include "aos/events/shm_event_loop.h"
-#include "aos/robot_state/robot_state_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/queues/gyro_generated.h"
#include "frc971/queues/gyro_uid_generated.h"
#include "frc971/wpilib/gyro_interface.h"
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index a4634bf..5661933 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -1,11 +1,10 @@
#include "frc971/wpilib/joystick_sender.h"
-#include "aos/input/driver_station_data.h"
#include "aos/logging/logging.h"
#include "aos/network/team_number.h"
#include "aos/realtime.h"
-#include "aos/robot_state/joystick_state_generated.h"
-
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/joystick_state_generated.h"
#include "frc971/wpilib/ahal/DriverStation.h"
#include "hal/HAL.h"
@@ -35,15 +34,16 @@
auto status = HAL_GetMatchInfo(&match_info);
std::array<flatbuffers::Offset<Joystick>,
- aos::input::driver_station::JoystickFeature::kJoysticks>
+ frc971::input::driver_station::JoystickFeature::kJoysticks>
joysticks;
for (size_t i = 0;
- i < aos::input::driver_station::JoystickFeature::kJoysticks; ++i) {
- std::array<double, aos::input::driver_station::JoystickAxis::kAxes>
+ i < frc971::input::driver_station::JoystickFeature::kJoysticks;
+ ++i) {
+ std::array<double, frc971::input::driver_station::JoystickAxis::kAxes>
axis;
- for (int j = 0; j < aos::input::driver_station::JoystickAxis::kAxes;
- ++j) {
+ for (int j = 0;
+ j < frc971::input::driver_station::JoystickAxis::kAxes; ++j) {
axis[j] = ds->GetStickAxis(i, j);
}
diff --git a/frc971/wpilib/joystick_sender.h b/frc971/wpilib/joystick_sender.h
index 6622d85..c9eb4cd 100644
--- a/frc971/wpilib/joystick_sender.h
+++ b/frc971/wpilib/joystick_sender.h
@@ -4,7 +4,7 @@
#include <atomic>
#include "aos/events/shm_event_loop.h"
-#include "aos/robot_state/joystick_state_generated.h"
+#include "frc971/input/joystick_state_generated.h"
namespace frc971 {
namespace wpilib {
diff --git a/frc971/wpilib/sensor_reader.h b/frc971/wpilib/sensor_reader.h
index 39b83fa..8efdf75 100644
--- a/frc971/wpilib/sensor_reader.h
+++ b/frc971/wpilib/sensor_reader.h
@@ -6,10 +6,10 @@
#include "aos/events/event_loop.h"
#include "aos/events/shm_event_loop.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
#include "frc971/wpilib/ahal/DigitalInput.h"
#include "frc971/wpilib/ahal/DriverStation.h"
diff --git a/frc971/wpilib/wpilib_interface.cc b/frc971/wpilib/wpilib_interface.cc
index 8772af1..2a59019 100644
--- a/frc971/wpilib/wpilib_interface.cc
+++ b/frc971/wpilib/wpilib_interface.cc
@@ -2,8 +2,7 @@
#include "aos/events/event_loop.h"
#include "aos/logging/logging.h"
-#include "aos/robot_state/robot_state_generated.h"
-
+#include "frc971/input/robot_state_generated.h"
#include "hal/HAL.h"
namespace frc971 {
diff --git a/frc971/wpilib/wpilib_interface.h b/frc971/wpilib/wpilib_interface.h
index 104ab84..8ab92ef 100644
--- a/frc971/wpilib/wpilib_interface.h
+++ b/frc971/wpilib/wpilib_interface.h
@@ -4,7 +4,7 @@
#include <stdint.h>
#include "aos/events/event_loop.h"
-#include "aos/robot_state/robot_state_generated.h"
+#include "frc971/input/robot_state_generated.h"
namespace frc971 {
namespace wpilib {
diff --git a/y2012/BUILD b/y2012/BUILD
index 2784788..ea88af8 100644
--- a/y2012/BUILD
+++ b/y2012/BUILD
@@ -9,7 +9,7 @@
deps = [
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:joystick_input",
+ "//frc971/input:joystick_input",
"//aos/logging",
"//aos/time",
"//aos/util:log_interval",
@@ -44,7 +44,7 @@
"//aos/controls:control_loop_fbs",
"//aos/events:shm_event_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
diff --git a/y2012/joystick_reader.cc b/y2012/joystick_reader.cc
index e723fa4..50052c7 100644
--- a/y2012/joystick_reader.cc
+++ b/y2012/joystick_reader.cc
@@ -1,22 +1,21 @@
+#include <math.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
-#include <math.h>
#include "aos/actions/actions.h"
#include "aos/events/shm_event_loop.h"
#include "aos/init.h"
-#include "aos/input/driver_station_data.h"
-#include "aos/input/joystick_input.h"
#include "aos/logging/logging.h"
#include "aos/time/time.h"
-
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/joystick_input.h"
#include "y2012/control_loops/accessories/accessories_generated.h"
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
#define OLD_DS 0
@@ -76,10 +75,10 @@
const JoystickAxis kAdjustClawGoal(3, 2);
const JoystickAxis kAdjustClawSeparation(3, 1);
-class Reader : public ::aos::input::JoystickInput {
+class Reader : public ::frc971::input::JoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::JoystickInput(event_loop),
+ : ::frc971::input::JoystickInput(event_loop),
drivetrain_goal_sender_(
event_loop->MakeSender<::frc971::control_loops::drivetrain::Goal>(
"/drivetrain")),
@@ -89,14 +88,15 @@
"/accessories")),
is_high_gear_(false) {}
- void RunIteration(const ::aos::input::driver_station::Data &data) override {
+ void RunIteration(
+ const ::frc971::input::driver_station::Data &data) override {
if (!data.GetControlBit(ControlBit::kAutonomous)) {
HandleDrivetrain(data);
HandleTeleop(data);
}
}
- void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+ void HandleDrivetrain(const ::frc971::input::driver_station::Data &data) {
const double wheel = -data.GetAxis(kSteeringWheel);
const double throttle = -data.GetAxis(kDriveThrottle);
if (data.PosEdge(kShiftLow)) {
@@ -118,16 +118,17 @@
}
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+ void HandleTeleop(const ::frc971::input::driver_station::Data &data) {
auto builder = accessories_goal_sender_.MakeBuilder();
flatbuffers::Offset<flatbuffers::Vector<uint8_t>> solenoids_offset =
builder.fbb()->CreateVector<uint8_t>({data.IsPressed(kLongShot),
- data.IsPressed(kCloseShot),
- data.IsPressed(kFenderShot)});
+ data.IsPressed(kCloseShot),
+ data.IsPressed(kFenderShot)});
flatbuffers::Offset<flatbuffers::Vector<double>> sticks_offset =
- builder.fbb()->CreateVector<double>({data.GetAxis(kAdjustClawGoal),
- data.GetAxis(kAdjustClawSeparation)});
+ builder.fbb()->CreateVector<double>(
+ {data.GetAxis(kAdjustClawGoal),
+ data.GetAxis(kAdjustClawSeparation)});
y2012::control_loops::accessories::Message::Builder message_builder =
builder.MakeBuilder<y2012::control_loops::accessories::Message>();
diff --git a/y2012/wpilib_interface.cc b/y2012/wpilib_interface.cc
index 256306a..f611c93 100644
--- a/y2012/wpilib_interface.cc
+++ b/y2012/wpilib_interface.cc
@@ -1,12 +1,12 @@
+#include <inttypes.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
-#include <inttypes.h>
#include <chrono>
-#include <thread>
-#include <mutex>
#include <functional>
+#include <mutex>
+#include <thread>
#include "frc971/wpilib/ahal/AnalogInput.h"
#include "frc971/wpilib/ahal/Compressor.h"
@@ -24,7 +24,6 @@
#include "aos/init.h"
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
@@ -32,6 +31,7 @@
#include "aos/util/wrapping_counter.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
#include "frc971/wpilib/dma.h"
@@ -53,15 +53,12 @@
namespace wpilib {
double drivetrain_translate(int32_t in) {
- return -static_cast<double>(in) /
- (256.0 /*cpr*/ * 4.0 /*4x*/) *
- 1 *
+ return -static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) * 1 *
(3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI) * 2.0 / 2.0;
}
double drivetrain_velocity_translate(double in) {
- return (1.0 / in) / 256.0 /*cpr*/ *
- 1 *
+ return (1.0 / in) / 256.0 /*cpr*/ * 1 *
(3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI) * 2.0 / 2.0;
}
@@ -291,5 +288,4 @@
} // namespace wpilib
} // namespace y2012
-
AOS_ROBOT_CLASS(::y2012::wpilib::WPILibRobot);
diff --git a/y2014/BUILD b/y2014/BUILD
index 458c411..a223253 100644
--- a/y2014/BUILD
+++ b/y2014/BUILD
@@ -32,7 +32,7 @@
":constants",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
+ "//frc971/input:action_joystick_input",
"//aos/logging",
"//aos/time",
"//aos/util:log_interval",
@@ -91,7 +91,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/control_loops/drivetrain:config",
],
)
@@ -108,7 +108,7 @@
"//aos:make_unique",
"//aos/controls:control_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
diff --git a/y2014/joystick_reader.cc b/y2014/joystick_reader.cc
index 136f65a..d2a7ed9 100644
--- a/y2014/joystick_reader.cc
+++ b/y2014/joystick_reader.cc
@@ -1,17 +1,16 @@
+#include <math.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
-#include <math.h>
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
#include "aos/logging/logging.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
-
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
#include "y2014/actors/shoot_actor.h"
#include "y2014/constants.h"
#include "y2014/control_loops/claw/claw_goal_generated.h"
@@ -19,9 +18,9 @@
#include "y2014/control_loops/drivetrain/drivetrain_base.h"
#include "y2014/control_loops/shooter/shooter_goal_generated.h"
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
#define OLD_DS 0
@@ -30,7 +29,7 @@
namespace joysticks {
const ButtonLocation kDriveControlLoopEnable1(1, 7),
- kDriveControlLoopEnable2(1, 11);
+ kDriveControlLoopEnable2(1, 11);
const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
const ButtonLocation kShiftHigh(2, 3), kShiftLow(2, 1);
const ButtonLocation kQuickTurn(1, 5);
@@ -150,12 +149,13 @@
const ClawGoal k254PassGoal = {-1.95, kGrabSeparation};
const ClawGoal kFlipped254PassGoal = {1.96, kGrabSeparation};
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop, control_loops::GetDrivetrainConfig(),
- ::aos::input::DrivetrainInputReader::InputType::kSteeringWheel, {}),
+ ::frc971::input::DrivetrainInputReader::InputType::kSteeringWheel,
+ {}),
claw_status_fetcher_(
event_loop->MakeFetcher<::y2014::control_loops::claw::Status>(
"/claw")),
@@ -194,7 +194,8 @@
intake_power_ = goal.intake_power;
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) override {
+ void HandleTeleop(
+ const ::frc971::input::driver_station::Data &data) override {
if (data.IsPressed(kRollersIn) || data.IsPressed(kRollersOut)) {
intake_power_ = 0.0;
separation_angle_ = kGrabSeparation;
@@ -206,8 +207,8 @@
if (OLD_DS || ::std::abs(claw_goal_adjust) < kAdjustClawGoalDeadband) {
claw_goal_adjust = 0;
} else {
- claw_goal_adjust = (claw_goal_adjust -
- ((claw_goal_adjust < 0) ? -kAdjustClawGoalDeadband
+ claw_goal_adjust = (claw_goal_adjust - ((claw_goal_adjust < 0)
+ ? -kAdjustClawGoalDeadband
: kAdjustClawGoalDeadband)) *
0.035;
}
@@ -217,8 +218,8 @@
claw_separation_adjust = 0;
} else {
claw_separation_adjust =
- (claw_separation_adjust -
- ((claw_separation_adjust < 0) ? -kAdjustClawGoalDeadband
+ (claw_separation_adjust - ((claw_separation_adjust < 0)
+ ? -kAdjustClawGoalDeadband
: kAdjustClawGoalDeadband)) *
-0.035;
}
diff --git a/y2014/wpilib_interface.cc b/y2014/wpilib_interface.cc
index ae2ced0..8f53ee2 100644
--- a/y2014/wpilib_interface.cc
+++ b/y2014/wpilib_interface.cc
@@ -1,12 +1,12 @@
+#include <inttypes.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
-#include <inttypes.h>
-#include <thread>
#include <chrono>
-#include <mutex>
#include <functional>
+#include <mutex>
+#include <thread>
#include "frc971/wpilib/ahal/AnalogInput.h"
#include "frc971/wpilib/ahal/Compressor.h"
@@ -22,7 +22,6 @@
#include "aos/init.h"
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
@@ -30,6 +29,7 @@
#include "aos/util/wrapping_counter.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/shifter_hall_effect.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
@@ -63,8 +63,7 @@
// The low bit is direction.
double drivetrain_translate(int32_t in) {
- return -static_cast<double>(in) /
- (256.0 /*cpr*/ * 4.0 /*4x*/) *
+ return -static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
constants::GetValues().drivetrain_encoder_ratio *
(3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI) * 2.0 / 2.0;
}
@@ -75,16 +74,16 @@
(3.5 /*wheel diameter*/ * 2.54 / 100.0 * M_PI) * 2.0 / 2.0;
}
-float hall_translate(const constants::DualHallShifterHallEffect &k, float in_low,
- float in_high) {
+float hall_translate(const constants::DualHallShifterHallEffect &k,
+ float in_low, float in_high) {
const float low_ratio =
0.5 * (in_low - static_cast<float>(k.shifter_hall_effect.low_gear_low)) /
- static_cast<float>(k.low_gear_middle - k.shifter_hall_effect.low_gear_low);
+ static_cast<float>(k.low_gear_middle -
+ k.shifter_hall_effect.low_gear_low);
const float high_ratio =
- 0.5 +
- 0.5 * (in_high - static_cast<float>(k.high_gear_middle)) /
- static_cast<float>(k.shifter_hall_effect.high_gear_high -
- k.high_gear_middle);
+ 0.5 + 0.5 * (in_high - static_cast<float>(k.high_gear_middle)) /
+ static_cast<float>(k.shifter_hall_effect.high_gear_high -
+ k.high_gear_middle);
// Return low when we are below 1/2, and high when we are above 1/2.
if (low_ratio + high_ratio < 1.0) {
@@ -378,7 +377,6 @@
synchronizer_.RunIteration();
-
::frc971::HallEffectStructT front;
CopyPosition(front_counter_.get(), &front);
flatbuffers::Offset<::frc971::HallEffectStruct> front_offset =
diff --git a/y2014/y2014.json b/y2014/y2014.json
index 38440a0..837529e 100644
--- a/y2014/y2014.json
+++ b/y2014/y2014.json
@@ -48,7 +48,7 @@
}
],
"imports": [
- "../aos/robot_state/robot_state_config.json",
+ "../frc971/input/robot_state_config.json",
"../frc971/control_loops/drivetrain/drivetrain_config.json"
]
}
diff --git a/y2014_bot3/BUILD b/y2014_bot3/BUILD
index c2a1793..4617006 100644
--- a/y2014_bot3/BUILD
+++ b/y2014_bot3/BUILD
@@ -9,8 +9,8 @@
deps = [
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:drivetrain_input",
- "//aos/input:joystick_input",
+ "//frc971/input:drivetrain_input",
+ "//frc971/input:joystick_input",
"//aos/logging",
"//aos/time",
"//aos/util:log_interval",
@@ -42,7 +42,7 @@
"//aos:make_unique",
"//aos/controls:control_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
diff --git a/y2014_bot3/joystick_reader.cc b/y2014_bot3/joystick_reader.cc
index b2fe9dc..92fa1e1 100644
--- a/y2014_bot3/joystick_reader.cc
+++ b/y2014_bot3/joystick_reader.cc
@@ -1,26 +1,25 @@
+#include <math.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
-#include <math.h>
#include "aos/init.h"
-#include "aos/input/joystick_input.h"
-#include "aos/input/driver_station_data.h"
#include "aos/logging/logging.h"
-#include "aos/util/log_interval.h"
#include "aos/time/time.h"
-
-#include "aos/input/drivetrain_input.h"
+#include "aos/util/log_interval.h"
#include "frc971/autonomous/base_autonomous_actor.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
#include "y2014_bot3/control_loops/rollers/rollers_goal_generated.h"
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::POVLocation;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::ControlBit;
-using ::aos::input::DrivetrainInputReader;
+using ::frc971::input::DrivetrainInputReader;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
+using ::frc971::input::driver_station::POVLocation;
namespace y2014_bot3 {
namespace input {
@@ -40,10 +39,10 @@
const ButtonLocation kBackRollersOut(4, 12);
const ButtonLocation kHumanPlayer(4, 11);
-class Reader : public ::aos::input::JoystickInput {
+class Reader : public ::frc971::input::JoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::JoystickInput(event_loop),
+ : ::frc971::input::JoystickInput(event_loop),
rollers_goal_sender_(
event_loop->MakeSender<::y2014_bot3::control_loops::rollers::Goal>(
"/rollers")),
@@ -55,7 +54,7 @@
::y2014_bot3::control_loops::drivetrain::GetDrivetrainConfig());
}
- virtual void RunIteration(const ::aos::input::driver_station::Data &data) {
+ virtual void RunIteration(const ::frc971::input::driver_station::Data &data) {
bool last_auto_running = auto_running_;
auto_running_ = data.GetControlBit(ControlBit::kAutonomous) &&
data.GetControlBit(ControlBit::kEnabled);
@@ -75,11 +74,11 @@
action_queue_.Tick();
}
- void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+ void HandleDrivetrain(const ::frc971::input::driver_station::Data &data) {
drivetrain_input_reader_->HandleDrivetrain(data);
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+ void HandleTeleop(const ::frc971::input::driver_station::Data &data) {
if (!data.GetControlBit(ControlBit::kEnabled)) {
action_queue_.CancelAllActions();
AOS_LOG(DEBUG, "Canceling\n");
diff --git a/y2014_bot3/wpilib_interface.cc b/y2014_bot3/wpilib_interface.cc
index ee5fc16..dedeab7 100644
--- a/y2014_bot3/wpilib_interface.cc
+++ b/y2014_bot3/wpilib_interface.cc
@@ -22,7 +22,6 @@
#include "aos/init.h"
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
@@ -30,6 +29,7 @@
#include "aos/util/wrapping_counter.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
#include "frc971/wpilib/dma.h"
@@ -49,13 +49,13 @@
#define M_PI 3.14159265358979323846
#endif
+using aos::make_unique;
using ::aos::util::SimpleLogInterval;
using ::frc971::wpilib::BufferedPcm;
using ::frc971::wpilib::BufferedSolenoid;
-using ::frc971::wpilib::LoopOutputHandler;
-using ::frc971::wpilib::JoystickSender;
using ::frc971::wpilib::GyroSender;
-using aos::make_unique;
+using ::frc971::wpilib::JoystickSender;
+using ::frc971::wpilib::LoopOutputHandler;
namespace y2014_bot3 {
namespace wpilib {
@@ -231,8 +231,8 @@
};
// Writes out rollers voltages.
-class RollersWriter : public LoopOutputHandler<
- ::y2014_bot3::control_loops::rollers::Output> {
+class RollersWriter
+ : public LoopOutputHandler<::y2014_bot3::control_loops::rollers::Output> {
public:
RollersWriter(::aos::EventLoop *event_loop)
: ::frc971::wpilib::LoopOutputHandler<
@@ -256,8 +256,8 @@
}
private:
- virtual void Write(const ::y2014_bot3::control_loops::rollers::Output
- &output) override {
+ virtual void Write(
+ const ::y2014_bot3::control_loops::rollers::Output &output) override {
rollers_front_left_intake_talon_->SetSpeed(output.front_intake_voltage() /
12.0);
rollers_front_right_intake_talon_->SetSpeed(
diff --git a/y2016/BUILD b/y2016/BUILD
index ae12689..9fcab25 100644
--- a/y2016/BUILD
+++ b/y2016/BUILD
@@ -33,7 +33,7 @@
":constants",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
+ "//frc971/input:action_joystick_input",
"//aos/logging",
"//aos/time",
"//aos/util:log_interval",
@@ -96,7 +96,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/autonomous:config",
"//frc971/control_loops/drivetrain:config",
"//frc971/wpilib:config",
@@ -116,7 +116,7 @@
"//aos:math",
"//aos/controls:control_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
diff --git a/y2016/joystick_reader.cc b/y2016/joystick_reader.cc
index 09ff112..7a2ce81 100644
--- a/y2016/joystick_reader.cc
+++ b/y2016/joystick_reader.cc
@@ -1,19 +1,18 @@
+#include <math.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
-#include <math.h>
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
#include "aos/logging/logging.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
-
#include "frc971/autonomous/auto_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
#include "y2016/actors/autonomous_actor.h"
#include "y2016/actors/superstructure_actor.h"
#include "y2016/actors/vision_align_actor.h"
@@ -26,10 +25,10 @@
#include "y2016/queues/ball_detector_generated.h"
#include "y2016/vision/vision_generated.h"
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::ControlBit;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::POVLocation;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
+using ::frc971::input::driver_station::POVLocation;
namespace y2016 {
namespace input {
@@ -66,15 +65,15 @@
const ButtonLocation kExpand(3, 6);
const ButtonLocation kWinch(3, 5);
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop, control_loops::drivetrain::GetDrivetrainConfig(),
- ::aos::input::DrivetrainInputReader::InputType::kSteeringWheel, {}),
+ ::frc971::input::DrivetrainInputReader::InputType::kSteeringWheel,
+ {}),
vision_status_fetcher_(
- event_loop->MakeFetcher<::y2016::vision::VisionStatus>(
- "/vision")),
+ event_loop->MakeFetcher<::y2016::vision::VisionStatus>("/vision")),
ball_detector_fetcher_(
event_loop->MakeFetcher<::y2016::sensors::BallDetector>(
"/superstructure")),
@@ -103,13 +102,14 @@
actors::VisionAlignActor::MakeFactory(event_loop)),
superstructure_action_factory_(
actors::SuperstructureActor::MakeFactory(event_loop)) {
- set_vision_align_fn([this](const ::aos::input::driver_station::Data &data) {
- return VisionAlign(data);
- });
+ set_vision_align_fn(
+ [this](const ::frc971::input::driver_station::Data &data) {
+ return VisionAlign(data);
+ });
}
// Returns true when we are vision aligning
- bool VisionAlign(const ::aos::input::driver_station::Data &data) {
+ bool VisionAlign(const ::frc971::input::driver_station::Data &data) {
vision_valid_ = false;
vision_status_fetcher_.Fetch();
@@ -143,7 +143,7 @@
return vision_action_running_;
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+ void HandleTeleop(const ::frc971::input::driver_station::Data &data) {
if (!data.GetControlBit(ControlBit::kEnabled)) {
// If we are not enabled, reset the waiting for zero bit.
AOS_LOG(DEBUG, "Waiting for zero.\n");
@@ -408,8 +408,7 @@
private:
::aos::Fetcher<::y2016::vision::VisionStatus> vision_status_fetcher_;
::aos::Fetcher<::y2016::sensors::BallDetector> ball_detector_fetcher_;
- ::aos::Sender<::y2016::control_loops::shooter::Goal>
- shooter_goal_sender_;
+ ::aos::Sender<::y2016::control_loops::shooter::Goal> shooter_goal_sender_;
::aos::Fetcher<::y2016::control_loops::superstructure::Status>
superstructure_status_fetcher_;
::aos::Sender<::y2016::control_loops::superstructure::Goal>
diff --git a/y2016/wpilib_interface.cc b/y2016/wpilib_interface.cc
index 5c2fcd6..8ff345d 100644
--- a/y2016/wpilib_interface.cc
+++ b/y2016/wpilib_interface.cc
@@ -23,7 +23,6 @@
#include "aos/events/shm_event_loop.h"
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
@@ -32,6 +31,7 @@
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ADIS16448.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
diff --git a/y2016/y2016.json b/y2016/y2016.json
index 9ad4f20..a880370 100644
--- a/y2016/y2016.json
+++ b/y2016/y2016.json
@@ -81,7 +81,7 @@
}
],
"imports": [
- "../aos/robot_state/robot_state_config.json",
+ "../frc971/input/robot_state_config.json",
"../frc971/control_loops/drivetrain/drivetrain_config.json",
"../frc971/autonomous/autonomous_config.json",
"../frc971/wpilib/wpilib_config.json"
diff --git a/y2017/BUILD b/y2017/BUILD
index a43654d..92779c9 100644
--- a/y2017/BUILD
+++ b/y2017/BUILD
@@ -36,8 +36,8 @@
":constants",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
- "//aos/input:drivetrain_input",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
"//aos/logging",
"//aos/time",
"//aos/util:log_interval",
@@ -61,7 +61,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/control_loops/drivetrain:config",
],
)
@@ -79,7 +79,7 @@
"//aos:math",
"//aos/controls:control_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
diff --git a/y2017/joystick_reader.cc b/y2017/joystick_reader.cc
index 58a3918..628de2a 100644
--- a/y2017/joystick_reader.cc
+++ b/y2017/joystick_reader.cc
@@ -5,23 +5,23 @@
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
-#include "aos/input/drivetrain_input.h"
#include "aos/logging/logging.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
#include "y2017/constants.h"
#include "y2017/control_loops/drivetrain/drivetrain_base.h"
#include "y2017/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2017/control_loops/superstructure/superstructure_status_generated.h"
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::ControlBit;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::POVLocation;
-using ::aos::input::DrivetrainInputReader;
+using ::frc971::input::DrivetrainInputReader;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
+using ::frc971::input::driver_station::POVLocation;
namespace y2017 {
namespace input {
@@ -47,10 +47,10 @@
const ButtonLocation kExtra2(3, 10);
const ButtonLocation kHang(3, 2);
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop,
::y2017::control_loops::drivetrain::GetDrivetrainConfig(),
DrivetrainInputReader::InputType::kSteeringWheel, {}),
@@ -65,7 +65,7 @@
enum class ShotDistance { VISION_SHOT, MIDDLE_SHOT, FAR_SHOT };
- void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+ void HandleTeleop(const ::frc971::input::driver_station::Data &data) {
// Default the intake to in.
intake_goal_ = 0.07;
bool lights_on = false;
@@ -113,9 +113,8 @@
last_shot_distance_ = ShotDistance::FAR_SHOT;
}
- if (data.IsPressed(kVisionAlign) ||
- data.IsPressed(kMiddleShot) || data.IsPressed(kFarShot) ||
- data.IsPressed(kFire)) {
+ if (data.IsPressed(kVisionAlign) || data.IsPressed(kMiddleShot) ||
+ data.IsPressed(kFarShot) || data.IsPressed(kFire)) {
switch (last_shot_distance_) {
case ShotDistance::VISION_SHOT:
hood_goal_ = 0.10;
@@ -135,23 +134,24 @@
break;
}
} else {
- //hood_goal_ = 0.15;
+ // hood_goal_ = 0.15;
shooter_velocity_ = 0.0;
}
if (data.IsPressed(kExtra1)) {
- //turret_goal_ = -M_PI * 3.0 / 4.0;
+ // turret_goal_ = -M_PI * 3.0 / 4.0;
turret_goal_ += 0.150;
}
if (data.IsPressed(kExtra2)) {
- //turret_goal_ = M_PI * 3.0 / 4.0;
+ // turret_goal_ = M_PI * 3.0 / 4.0;
turret_goal_ -= 0.150;
}
turret_goal_ = ::std::max(::std::min(turret_goal_, M_PI), -M_PI);
fire_ = data.IsPressed(kFire) && shooter_velocity_ != 0.0;
if (data.IsPressed(kVisionAlign)) {
- fire_ = fire_ && superstructure_status_fetcher_->turret()->vision_tracking();
+ fire_ =
+ fire_ && superstructure_status_fetcher_->turret()->vision_tracking();
}
auto builder = superstructure_goal_sender_.MakeBuilder();
@@ -206,7 +206,7 @@
indexer_angular_velocity = 1.0;
} else if (fire_) {
indexer_voltage_rollers = 12.0;
- switch (last_shot_distance_) {
+ switch (last_shot_distance_) {
case ShotDistance::VISION_SHOT:
indexer_angular_velocity = -1.25 * M_PI;
break;
@@ -247,7 +247,7 @@
flatbuffers::Offset<frc971::ProfileParameters>
intake_profile_parameters_offset =
- frc971::CreateProfileParameters(*builder.fbb(), 0.5, 3.0);
+ frc971::CreateProfileParameters(*builder.fbb(), 0.5, 3.0);
superstructure::IntakeGoal::Builder intake_goal_builder =
builder.MakeBuilder<superstructure::IntakeGoal>();
diff --git a/y2017/wpilib_interface.cc b/y2017/wpilib_interface.cc
index 84e779d..14029e3 100644
--- a/y2017/wpilib_interface.cc
+++ b/y2017/wpilib_interface.cc
@@ -26,7 +26,6 @@
#include "aos/init.h"
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
#include "aos/util/compiler_memory_barrier.h"
@@ -38,6 +37,7 @@
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ADIS16448.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
@@ -61,8 +61,8 @@
#endif
namespace superstructure = ::y2017::control_loops::superstructure;
-using ::y2017::constants::Values;
using ::aos::monotonic_clock;
+using ::y2017::constants::Values;
namespace chrono = ::std::chrono;
using namespace frc;
using aos::make_unique;
diff --git a/y2017/y2017.json b/y2017/y2017.json
index 90aa77c..cc10744 100644
--- a/y2017/y2017.json
+++ b/y2017/y2017.json
@@ -28,7 +28,7 @@
}
],
"imports": [
- "../aos/robot_state/robot_state_config.json",
+ "../frc971/input/robot_state_config.json",
"../frc971/control_loops/drivetrain/drivetrain_config.json"
]
}
diff --git a/y2018/BUILD b/y2018/BUILD
index 7055f0a..044be19 100644
--- a/y2018/BUILD
+++ b/y2018/BUILD
@@ -25,8 +25,8 @@
":vision_proto",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
- "//aos/input:drivetrain_input",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
"//aos/logging",
"//aos/network:team_number",
"//aos/stl_mutex",
@@ -78,7 +78,7 @@
"//aos:math",
"//aos/controls:control_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/time",
"//aos/util:log_interval",
"//aos/util:phased_loop",
@@ -132,7 +132,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/control_loops/drivetrain:config",
],
)
diff --git a/y2018/joystick_reader.cc b/y2018/joystick_reader.cc
index 1f4a495..b5df79a 100644
--- a/y2018/joystick_reader.cc
+++ b/y2018/joystick_reader.cc
@@ -1,15 +1,13 @@
+#include <google/protobuf/stubs/stringprintf.h>
#include <math.h>
#include <stdio.h>
#include <string.h>
#include <unistd.h>
+
#include <mutex>
-#include <google/protobuf/stubs/stringprintf.h>
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
-#include "aos/input/drivetrain_input.h"
#include "aos/logging/logging.h"
#include "aos/network/team_number.h"
#include "aos/stl_mutex/stl_mutex.h"
@@ -17,6 +15,9 @@
#include "aos/util/log_interval.h"
#include "aos/vision/events/udp.h"
#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
#include "y2018/control_loops/drivetrain/drivetrain_base.h"
#include "y2018/control_loops/superstructure/arm/generated_graph.h"
#include "y2018/control_loops/superstructure/superstructure_goal_generated.h"
@@ -27,14 +28,14 @@
using ::aos::monotonic_clock;
using ::aos::events::ProtoTXUdpSocket;
using ::aos::events::RXUdpSocket;
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::ControlBit;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::POVLocation;
-using ::aos::input::DrivetrainInputReader;
+using ::frc971::input::DrivetrainInputReader;
+using ::frc971::input::driver_station::ButtonLocation;
+using ::frc971::input::driver_station::ControlBit;
+using ::frc971::input::driver_station::JoystickAxis;
+using ::frc971::input::driver_station::POVLocation;
-using ::y2018::control_loops::superstructure::arm::FrontPoints;
using ::y2018::control_loops::superstructure::arm::BackPoints;
+using ::y2018::control_loops::superstructure::arm::FrontPoints;
namespace y2018 {
namespace input {
@@ -83,10 +84,10 @@
const ButtonLocation kClawOpen(4, 4);
const ButtonLocation kDriverClawOpen(2, 4);
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop,
::y2018::control_loops::drivetrain::GetDrivetrainConfig(),
::aos::network::GetTeamNumber() == 971
@@ -94,13 +95,13 @@
: DrivetrainInputReader::InputType::kSteeringWheel,
{}),
superstructure_position_fetcher_(
- event_loop->MakeFetcher<
- ::y2018::control_loops::superstructure::Position>(
- ".frc971.control_loops.superstructure_queue.position")),
+ event_loop
+ ->MakeFetcher<::y2018::control_loops::superstructure::Position>(
+ ".frc971.control_loops.superstructure_queue.position")),
superstructure_status_fetcher_(
- event_loop->MakeFetcher<
- ::y2018::control_loops::superstructure::Status>(
- ".frc971.control_loops.superstructure_queue.status")),
+ event_loop
+ ->MakeFetcher<::y2018::control_loops::superstructure::Status>(
+ ".frc971.control_loops.superstructure_queue.status")),
superstructure_goal_sender_(
event_loop
->MakeSender<::y2018::control_loops::superstructure::Goal>(
@@ -111,7 +112,8 @@
StringPrintf("10.%d.%d.179", team / 100, team % 100), 5000));
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) override {
+ void HandleTeleop(
+ const ::frc971::input::driver_station::Data &data) override {
superstructure_position_fetcher_.Fetch();
superstructure_status_fetcher_.Fetch();
if (!superstructure_status_fetcher_.get() ||
@@ -182,8 +184,7 @@
intake_goal_ = -3.20;
}
- if (roller_voltage > 0.1 &&
- intake_goal_ > 0.0) {
+ if (roller_voltage > 0.1 && intake_goal_ > 0.0) {
if (superstructure_position_fetcher_->box_distance() < 0.10) {
roller_voltage -= 3.0;
}
diff --git a/y2018/y2018.json b/y2018/y2018.json
index ebb6c75..d8e21d2 100644
--- a/y2018/y2018.json
+++ b/y2018/y2018.json
@@ -38,7 +38,7 @@
}
],
"imports": [
- "../aos/robot_state/robot_state_config.json",
+ "../frc971/input/robot_state_config.json",
"../frc971/control_loops/drivetrain/drivetrain_config.json"
]
}
diff --git a/y2019/BUILD b/y2019/BUILD
index 0954157..64d825e 100644
--- a/y2019/BUILD
+++ b/y2019/BUILD
@@ -68,7 +68,7 @@
"//aos/controls:control_loop",
"//aos/events:shm_event_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
@@ -108,7 +108,7 @@
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
- "//aos/input:drivetrain_input",
+ "//frc971/input:drivetrain_input",
"//frc971/zeroing:wrap",
],
)
@@ -136,9 +136,9 @@
":vision_proto",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
- "//aos/input:drivetrain_input",
- "//aos/input:joystick_input",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
+ "//frc971/input:joystick_input",
"//aos/logging",
"//aos/network:team_number",
"//aos/stl_mutex",
@@ -194,7 +194,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/autonomous:config",
"//frc971/control_loops/drivetrain:config",
"//frc971/wpilib:config",
diff --git a/y2019/joystick_angle.h b/y2019/joystick_angle.h
index 09ab8af..dfd8bb9 100644
--- a/y2019/joystick_angle.h
+++ b/y2019/joystick_angle.h
@@ -1,10 +1,10 @@
#ifndef Y2019_JOYSTICK_ANGLE_H_
#define Y2019_JOYSTICK_ANGLE_H_
-#include "aos/input/driver_station_data.h"
+#include "frc971/input/driver_station_data.h"
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::Data;
+using ::frc971::input::driver_station::Data;
+using ::frc971::input::driver_station::JoystickAxis;
namespace y2019 {
namespace input {
diff --git a/y2019/joystick_angle_test.cc b/y2019/joystick_angle_test.cc
index dc29004..7173b80 100644
--- a/y2019/joystick_angle_test.cc
+++ b/y2019/joystick_angle_test.cc
@@ -1,10 +1,12 @@
#include "y2019/joystick_angle.h"
+
#include <iostream>
-#include "aos/input/driver_station_data.h"
+
+#include "frc971/input/driver_station_data.h"
#include "gtest/gtest.h"
-using y2019::input::joysticks::JoystickAngle;
using y2019::input::joysticks::GetJoystickPosition;
+using y2019::input::joysticks::JoystickAngle;
TEST(JoystickAngleTest, JoystickAngleTest) {
EXPECT_EQ(JoystickAngle::kUpperRight, GetJoystickPosition(0.75, 0.75));
diff --git a/y2019/joystick_reader.cc b/y2019/joystick_reader.cc
index 823507d..7351130 100644
--- a/y2019/joystick_reader.cc
+++ b/y2019/joystick_reader.cc
@@ -2,14 +2,11 @@
#include <stdio.h>
#include <string.h>
#include <unistd.h>
+
#include <chrono>
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
-#include "aos/input/drivetrain_input.h"
-#include "aos/input/joystick_input.h"
#include "aos/logging/logging.h"
#include "aos/network/team_number.h"
#include "aos/util/log_interval.h"
@@ -17,7 +14,10 @@
#include "external/com_google_protobuf/src/google/protobuf/stubs/stringprintf.h"
#include "frc971/autonomous/base_autonomous_actor.h"
#include "frc971/control_loops/drivetrain/localizer_generated.h"
-
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
#include "y2019/camera_log_generated.h"
#include "y2019/control_loops/drivetrain/drivetrain_base.h"
#include "y2019/control_loops/drivetrain/target_selector_generated.h"
@@ -27,16 +27,16 @@
#include "y2019/vision.pb.h"
using aos::events::ProtoTXUdpSocket;
-using aos::input::driver_station::ButtonLocation;
-using aos::input::driver_station::ControlBit;
-using aos::input::driver_station::JoystickAxis;
-using aos::input::driver_station::POVLocation;
using frc971::CreateProfileParameters;
using frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
using frc971::control_loops::drivetrain::LocalizerControl;
-using y2019::control_loops::superstructure::SuctionGoal;
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
using y2019::control_loops::superstructure::CreateSuctionGoal;
+using y2019::control_loops::superstructure::SuctionGoal;
namespace chrono = ::std::chrono;
@@ -138,13 +138,13 @@
const ElevatorWristPosition kBallIntakePos{0.309, 2.13};
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop,
::y2019::control_loops::drivetrain::GetDrivetrainConfig(),
- ::aos::input::DrivetrainInputReader::InputType::kPistol,
+ ::frc971::input::DrivetrainInputReader::InputType::kPistol,
{.run_teleop_in_auto = true,
.cancel_auto_button = kCancelAutoMode}),
target_selector_hint_sender_(
@@ -186,7 +186,8 @@
switch_ball_ = false;
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) override {
+ void HandleTeleop(
+ const ::frc971::input::driver_station::Data &data) override {
::aos::monotonic_clock::time_point monotonic_now =
::aos::monotonic_clock::now();
superstructure_position_fetcher_.Fetch();
@@ -270,16 +271,16 @@
const double cargo_joy_x = data.GetAxis(kCargoSelectorX);
if (cargo_joy_y > 0.5) {
target_selector_hint_builder.add_suggested_target(
- control_loops::drivetrain::SelectionHint::NEAR_SHIP);
+ control_loops::drivetrain::SelectionHint::NEAR_SHIP);
} else if (cargo_joy_y < -0.5) {
target_selector_hint_builder.add_suggested_target(
control_loops::drivetrain::SelectionHint::FAR_SHIP);
} else if (::std::abs(cargo_joy_x) > 0.5) {
target_selector_hint_builder.add_suggested_target(
- control_loops::drivetrain::SelectionHint::MID_SHIP);
+ control_loops::drivetrain::SelectionHint::MID_SHIP);
} else {
target_selector_hint_builder.add_suggested_target(
- control_loops::drivetrain::SelectionHint::NONE);
+ control_loops::drivetrain::SelectionHint::NONE);
}
}
if (!builder.Send(target_selector_hint_builder.Finish())) {
@@ -514,8 +515,10 @@
->mutate_max_acceleration(1.25);
} else if (data.IsPressed(kHalfStilt)) {
was_above_ = false;
- mutable_superstructure_goal->mutable_stilts()->mutate_unsafe_goal ( 0.345);
- mutable_superstructure_goal->mutable_stilts()->mutable_profile_params()->mutate_max_velocity ( 0.65);
+ mutable_superstructure_goal->mutable_stilts()->mutate_unsafe_goal(0.345);
+ mutable_superstructure_goal->mutable_stilts()
+ ->mutable_profile_params()
+ ->mutate_max_velocity(0.65);
} else if (data.IsPressed(kDeployStilt) || was_above_) {
mutable_superstructure_goal->mutable_stilts()->mutate_unsafe_goal(
kDeployStiltPosition);
diff --git a/y2019/wpilib_interface.cc b/y2019/wpilib_interface.cc
index b6d432f..00ec2ab 100644
--- a/y2019/wpilib_interface.cc
+++ b/y2019/wpilib_interface.cc
@@ -10,13 +10,13 @@
#include <mutex>
#include <thread>
+#include "ctre/phoenix/CANifier.h"
#include "frc971/wpilib/ahal/AnalogInput.h"
#include "frc971/wpilib/ahal/Counter.h"
#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
#include "frc971/wpilib/ahal/DriverStation.h"
#include "frc971/wpilib/ahal/Encoder.h"
#include "frc971/wpilib/ahal/VictorSP.h"
-#include "ctre/phoenix/CANifier.h"
#undef ERROR
#include "aos/commonmath.h"
@@ -26,7 +26,6 @@
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
#include "aos/realtime.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
#include "aos/util/phased_loop.h"
@@ -34,6 +33,7 @@
#include "ctre/phoenix/motorcontrol/can/TalonSRX.h"
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ADIS16448.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
@@ -58,8 +58,8 @@
#define M_PI 3.14159265358979323846
#endif
-using ::y2019::constants::Values;
using ::aos::monotonic_clock;
+using ::y2019::constants::Values;
namespace superstructure = ::y2019::control_loops::superstructure;
namespace chrono = ::std::chrono;
using aos::make_unique;
@@ -800,8 +800,8 @@
camera_reader.set_activate_passthrough(make_unique<frc::DigitalInput>(25));
auto imu_trigger = make_unique<frc::DigitalInput>(0);
- ::frc971::wpilib::ADIS16448 imu(&imu_event_loop, frc::SPI::Port::kOnboardCS1,
- imu_trigger.get());
+ ::frc971::wpilib::ADIS16448 imu(
+ &imu_event_loop, frc::SPI::Port::kOnboardCS1, imu_trigger.get());
imu.set_spi_idle_callback(
[&camera_reader]() { camera_reader.DoSpiTransaction(); });
auto imu_reset = make_unique<frc::DigitalOutput>(1);
diff --git a/y2019/y2019.json b/y2019/y2019.json
index cbff0a5..7a30be4 100644
--- a/y2019/y2019.json
+++ b/y2019/y2019.json
@@ -47,7 +47,7 @@
}
],
"imports": [
- "../aos/robot_state/robot_state_config.json",
+ "../frc971/input/robot_state_config.json",
"../frc971/control_loops/drivetrain/drivetrain_config.json",
"../frc971/autonomous/autonomous_config.json",
"../frc971/wpilib/wpilib_config.json"
diff --git a/y2020/BUILD b/y2020/BUILD
index d95b687..da7d68c 100644
--- a/y2020/BUILD
+++ b/y2020/BUILD
@@ -91,7 +91,7 @@
"//aos/controls:control_loop",
"//aos/events:shm_event_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
@@ -129,9 +129,9 @@
":setpoint_fbs",
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
- "//aos/input:drivetrain_input",
- "//aos/input:joystick_input",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
+ "//frc971/input:joystick_input",
"//aos/logging",
"//frc971/autonomous:auto_fbs",
"//frc971/autonomous:base_autonomous_actor",
@@ -185,7 +185,7 @@
visibility = ["//visibility:public"],
deps = [
"//aos/events:config",
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/control_loops/drivetrain:config",
],
)
@@ -214,7 +214,7 @@
visibility = ["//visibility:public"],
deps = [
"//aos/events:config",
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/control_loops/drivetrain:config",
],
)
@@ -237,7 +237,7 @@
target_compatible_with = ["@platforms//os:linux"],
deps = [
"//aos/events:config",
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/autonomous:config",
"//frc971/control_loops/drivetrain:config",
"//frc971/wpilib:config",
diff --git a/y2020/actors/BUILD b/y2020/actors/BUILD
index 6521b85..be0d6dd 100644
--- a/y2020/actors/BUILD
+++ b/y2020/actors/BUILD
@@ -48,7 +48,7 @@
deps = [
"//aos/events:event_loop",
"//aos/logging",
- "//aos/robot_state:joystick_state_fbs",
+ "//frc971/input:joystick_state_fbs",
"//aos/util:math",
"//aos/util:phased_loop",
"//frc971/autonomous:base_autonomous_actor",
diff --git a/y2020/actors/auto_splines.h b/y2020/actors/auto_splines.h
index 891228b..a80345c 100644
--- a/y2020/actors/auto_splines.h
+++ b/y2020/actors/auto_splines.h
@@ -3,9 +3,9 @@
#include "aos/events/event_loop.h"
#include "aos/flatbuffer_merge.h"
-#include "aos/robot_state/joystick_state_generated.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/input/joystick_state_generated.h"
/*
The cooridinate system for the autonomous splines is the same as the spline
diff --git a/y2020/control_loops/superstructure/superstructure.h b/y2020/control_loops/superstructure/superstructure.h
index af15be6..4777aef 100644
--- a/y2020/control_loops/superstructure/superstructure.h
+++ b/y2020/control_loops/superstructure/superstructure.h
@@ -3,8 +3,8 @@
#include "aos/controls/control_loop.h"
#include "aos/events/event_loop.h"
-#include "aos/robot_state/joystick_state_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/input/joystick_state_generated.h"
#include "y2020/constants.h"
#include "y2020/control_loops/superstructure/climber.h"
#include "y2020/control_loops/superstructure/shooter/shooter.h"
diff --git a/y2020/control_loops/superstructure/turret/aiming.h b/y2020/control_loops/superstructure/turret/aiming.h
index 854518c..7f69d48 100644
--- a/y2020/control_loops/superstructure/turret/aiming.h
+++ b/y2020/control_loops/superstructure/turret/aiming.h
@@ -2,10 +2,10 @@
#define y2020_CONTROL_LOOPS_SUPERSTRUCTURE_TURRET_AIMING_H_
#include "aos/flatbuffers.h"
-#include "aos/robot_state/joystick_state_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "frc971/control_loops/pose.h"
#include "frc971/control_loops/profiled_subsystem_generated.h"
+#include "frc971/input/joystick_state_generated.h"
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
namespace y2020 {
@@ -66,7 +66,7 @@
bool aiming_for_inner_port_ = false;
// Distance of the shot to the virtual target, used for calculating hood
// position and shooter speed.
- double shot_distance_ = 0.0; // meters
+ double shot_distance_ = 0.0; // meters
// Real-world distance to the target.
double target_distance_ = 0.0; // meters
};
diff --git a/y2020/joystick_reader.cc b/y2020/joystick_reader.cc
index 8df5a8a..3e828cf 100644
--- a/y2020/joystick_reader.cc
+++ b/y2020/joystick_reader.cc
@@ -5,31 +5,30 @@
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
-#include "aos/input/drivetrain_input.h"
-#include "aos/input/joystick_input.h"
#include "aos/logging/logging.h"
#include "aos/network/team_number.h"
#include "aos/util/log_interval.h"
#include "frc971/autonomous/base_autonomous_actor.h"
#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
#include "y2020/constants.h"
#include "y2020/control_loops/drivetrain/drivetrain_base.h"
#include "y2020/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
#include "y2020/setpoint_generated.h"
-using aos::input::driver_station::ButtonLocation;
-using aos::input::driver_station::ControlBit;
-using aos::input::driver_station::JoystickAxis;
-using aos::input::driver_station::POVLocation;
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
using frc971::CreateProfileParameters;
using frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
-
namespace y2020 {
namespace input {
namespace joysticks {
@@ -50,13 +49,13 @@
const ButtonLocation kWinch(3, 14);
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop,
::y2020::control_loops::drivetrain::GetDrivetrainConfig(),
- ::aos::input::DrivetrainInputReader::InputType::kPistol, {}),
+ ::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
superstructure_goal_sender_(
event_loop->MakeSender<superstructure::Goal>("/superstructure")),
localizer_control_sender_(
@@ -89,7 +88,8 @@
}
}
- void HandleTeleop(const ::aos::input::driver_station::Data &data) override {
+ void HandleTeleop(
+ const ::frc971::input::driver_station::Data &data) override {
superstructure_status_fetcher_.Fetch();
if (!superstructure_status_fetcher_.get()) {
AOS_LOG(ERROR, "Got no superstructure status message.\n");
diff --git a/y2020/wpilib_interface.cc b/y2020/wpilib_interface.cc
index 14f6ac9..e0f6f6b 100644
--- a/y2020/wpilib_interface.cc
+++ b/y2020/wpilib_interface.cc
@@ -27,7 +27,6 @@
#include "aos/make_unique.h"
#include "aos/network/team_number.h"
#include "aos/realtime.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
#include "aos/util/phased_loop.h"
@@ -36,6 +35,7 @@
#include "ctre/phoenix/motorcontrol/can/VictorSPX.h"
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ADIS16470.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
diff --git a/y2021_bot3/BUILD b/y2021_bot3/BUILD
index 4e226c0..9429be4 100644
--- a/y2021_bot3/BUILD
+++ b/y2021_bot3/BUILD
@@ -51,7 +51,7 @@
"//aos/controls:control_loop",
"//aos/events:shm_event_loop",
"//aos/logging",
- "//aos/robot_state:robot_state_fbs",
+ "//frc971/input:robot_state_fbs",
"//aos/stl_mutex",
"//aos/time",
"//aos/util:log_interval",
@@ -87,9 +87,9 @@
deps = [
"//aos:init",
"//aos/actions:action_lib",
- "//aos/input:action_joystick_input",
- "//aos/input:drivetrain_input",
- "//aos/input:joystick_input",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
+ "//frc971/input:joystick_input",
"//aos/logging",
"//frc971/autonomous:auto_fbs",
"//frc971/autonomous:base_autonomous_actor",
@@ -111,7 +111,7 @@
],
visibility = ["//visibility:public"],
deps = [
- "//aos/robot_state:config",
+ "//frc971/input:config",
"//frc971/autonomous:config",
"//frc971/control_loops/drivetrain:config",
"//frc971/wpilib:config",
diff --git a/y2021_bot3/joystick_reader.cc b/y2021_bot3/joystick_reader.cc
index accb031..88d16b2 100644
--- a/y2021_bot3/joystick_reader.cc
+++ b/y2021_bot3/joystick_reader.cc
@@ -5,22 +5,22 @@
#include "aos/actions/actions.h"
#include "aos/init.h"
-#include "aos/input/action_joystick_input.h"
-#include "aos/input/driver_station_data.h"
-#include "aos/input/drivetrain_input.h"
-#include "aos/input/joystick_input.h"
#include "aos/logging/logging.h"
#include "aos/network/team_number.h"
#include "aos/util/log_interval.h"
#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
#include "y2021_bot3/control_loops/drivetrain/drivetrain_base.h"
#include "y2021_bot3/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2021_bot3/control_loops/superstructure/superstructure_status_generated.h"
-using aos::input::driver_station::ButtonLocation;
-using aos::input::driver_station::ControlBit;
-using aos::input::driver_station::JoystickAxis;
-using aos::input::driver_station::POVLocation;
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
namespace y2021_bot3 {
namespace input {
@@ -28,13 +28,13 @@
namespace superstructure = y2021_bot3::control_loops::superstructure;
-class Reader : public ::aos::input::ActionJoystickInput {
+class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
- : ::aos::input::ActionJoystickInput(
+ : ::frc971::input::ActionJoystickInput(
event_loop,
::y2021_bot3::control_loops::drivetrain::GetDrivetrainConfig(),
- ::aos::input::DrivetrainInputReader::InputType::kPistol, {}),
+ ::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
superstructure_goal_sender_(
event_loop->MakeSender<superstructure::Goal>("/superstructure")),
superstructure_status_fetcher_(
@@ -44,7 +44,7 @@
void AutoEnded() override { AOS_LOG(INFO, "Auto ended.\n"); }
void HandleTeleop(
- const ::aos::input::driver_station::Data & /*data*/) override {
+ const ::frc971::input::driver_station::Data & /*data*/) override {
superstructure_status_fetcher_.Fetch();
if (!superstructure_status_fetcher_.get()) {
AOS_LOG(ERROR, "Got no superstructure status message.\n");
diff --git a/y2021_bot3/wpilib_interface.cc b/y2021_bot3/wpilib_interface.cc
index 3dfcfb7..4e07842 100644
--- a/y2021_bot3/wpilib_interface.cc
+++ b/y2021_bot3/wpilib_interface.cc
@@ -27,7 +27,6 @@
#include "aos/logging/logging.h"
#include "aos/make_unique.h"
#include "aos/realtime.h"
-#include "aos/robot_state/robot_state_generated.h"
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
#include "aos/util/phased_loop.h"
@@ -35,6 +34,7 @@
#include "ctre/phoenix/motorcontrol/can/TalonSRX.h"
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ADIS16448.h"
#include "frc971/wpilib/buffered_pcm.h"
#include "frc971/wpilib/buffered_solenoid.h"
diff --git a/y2021_bot3/y2021_bot3.json b/y2021_bot3/y2021_bot3.json
index d96ca09..e9b7faf 100644
--- a/y2021_bot3/y2021_bot3.json
+++ b/y2021_bot3/y2021_bot3.json
@@ -31,7 +31,7 @@
}
],
"imports": [
- "../aos/robot_state/robot_state_config.json",
+ "../frc971/input/robot_state_config.json",
"../frc971/control_loops/drivetrain/drivetrain_config.json",
"../frc971/autonomous/autonomous_config.json",
"../frc971/wpilib/wpilib_config.json"