Merge "Actually add directions to enable sandboxing"
diff --git a/NO_BUILD_AMD64 b/NO_BUILD_AMD64
index faa75a9..e80b47c 100644
--- a/NO_BUILD_AMD64
+++ b/NO_BUILD_AMD64
@@ -14,3 +14,6 @@
-//y2016/wpilib/...
-//y2016:download
-//y2016:download_stripped
+-//y2016_bot3/wpilib/...
+-//y2016_bot3:download
+-//y2016_bot3:download_stripped
diff --git a/NO_BUILD_ROBORIO b/NO_BUILD_ROBORIO
index 5b9c693..839238a 100644
--- a/NO_BUILD_ROBORIO
+++ b/NO_BUILD_ROBORIO
@@ -1,9 +1,11 @@
-@slycot_repo//...
-//frc971/control_loops/python/...
-//y2012/control_loops/python/...
+-//y2014_bot3/control_loops/python/...
-//y2014/control_loops/python/...
-//y2014_bot3/control_loops/python/...
-//y2015/control_loops/python/...
-//y2015_bot3/control_loops/python/...
-//y2016/control_loops/python/...
+-//y2016_bot3/control_loops/python/...
-//third_party/protobuf/...
diff --git a/aos/common/event.cc b/aos/common/event.cc
index ae32d39..af9c9c5 100644
--- a/aos/common/event.cc
+++ b/aos/common/event.cc
@@ -11,25 +11,28 @@
}
void Event::Wait() {
- int ret;
- do {
- ret = futex_wait(&impl_);
- } while (ret == 1);
- if (ret == 0) return;
- CHECK_EQ(-1, ret);
- PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+ while (__atomic_load_n(&impl_, __ATOMIC_SEQ_CST) == 0) {
+ const int ret = futex_wait(&impl_);
+ if (ret != 0) {
+ CHECK_EQ(-1, ret);
+ PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+ }
+ }
}
bool Event::WaitTimeout(const ::aos::time::Time &timeout) {
const auto timeout_timespec = timeout.ToTimespec();
- int ret;
- do {
- ret = futex_wait_timeout(&impl_, &timeout_timespec);
- } while (ret == 1);
- if (ret == 0) return true;
- if (ret == 2) return false;
- CHECK_EQ(-1, ret);
- PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+ while (true) {
+ if (__atomic_load_n(&impl_, __ATOMIC_SEQ_CST) != 0) {
+ return true;
+ }
+ const int ret = futex_wait_timeout(&impl_, &timeout_timespec);
+ if (ret != 0) {
+ if (ret == 2) return false;
+ CHECK_EQ(-1, ret);
+ PLOG(FATAL, "futex_wait(%p) failed", &impl_);
+ }
+ }
}
// We're not going to expose the number woken because that's not easily portable
diff --git a/aos/common/time.h b/aos/common/time.h
index 40b72b0..ba795a9 100644
--- a/aos/common/time.h
+++ b/aos/common/time.h
@@ -28,8 +28,10 @@
// Returns the epoch (0).
static constexpr monotonic_clock::time_point epoch() {
- return time_point(duration(0));
+ return time_point(zero());
}
+
+ static constexpr monotonic_clock::duration zero() { return duration(0); }
};
namespace time {
@@ -146,8 +148,10 @@
}
// Construct a time representing the period of hertz.
- static constexpr Time FromRate(int hertz) {
- return Time(0, kNSecInSec / hertz);
+ static constexpr ::std::chrono::nanoseconds FromRate(int hertz) {
+ return ::std::chrono::duration_cast<::std::chrono::nanoseconds>(
+ ::std::chrono::seconds(1)) /
+ hertz;
}
// Checks whether or not this time is within amount nanoseconds of other.
diff --git a/aos/common/time_test.cc b/aos/common/time_test.cc
index 3ae82ab..e1811db 100644
--- a/aos/common/time_test.cc
+++ b/aos/common/time_test.cc
@@ -255,7 +255,7 @@
}
TEST(TimeTest, FromRate) {
- EXPECT_EQ(MACRO_DARG(Time(0, Time::kNSecInSec / 100)), Time::FromRate(100));
+ EXPECT_EQ(::std::chrono::milliseconds(10), Time::FromRate(100));
}
// Test the monotonic_clock and sleep_until functions.
diff --git a/aos/common/type_traits.h b/aos/common/type_traits.h
index 4b5fa8c..53fae23 100644
--- a/aos/common/type_traits.h
+++ b/aos/common/type_traits.h
@@ -12,7 +12,7 @@
struct has_trivial_copy_assign : public std::integral_constant<bool,
// This changed between 4.4.5 and 4.6.3. Unless somebody discovers otherwise,
// 4.6 seems like a reasonable place to switch.
-#if ((__GNUC__ < 4) || (__GNUC_MINOR__ < 6)) && !defined(__clang__)
+#if ((__GNUC__ < 4) || (__GNUC__ == 4 && __GNUC_MINOR__ < 6)) && !defined(__clang__)
::std::has_trivial_assign<Tp>::value> {};
#else
::std::has_trivial_copy_assign<Tp>::value> {};
diff --git a/aos/common/util/phased_loop.cc b/aos/common/util/phased_loop.cc
index b5804c8..9c81ffb 100644
--- a/aos/common/util/phased_loop.cc
+++ b/aos/common/util/phased_loop.cc
@@ -10,15 +10,21 @@
frequency + Time::InUS(offset));
}
-int PhasedLoop::Iterate(const Time &now) {
- const Time next_time = Time::InNS(((now - offset_).ToNSec() + 1) /
- interval_.ToNSec() * interval_.ToNSec()) +
- ((now < offset_) ? Time::kZero : interval_) + offset_;
+int PhasedLoop::Iterate(const monotonic_clock::time_point now) {
+ const monotonic_clock::time_point next_time =
+ monotonic_clock::time_point(
+ (((now - offset_).time_since_epoch() + monotonic_clock::duration(1)) /
+ interval_) *
+ interval_) +
+ ((now.time_since_epoch() < offset_) ? monotonic_clock::zero()
+ : interval_) +
+ offset_;
- const Time difference = next_time - last_time_;
- const int result = difference.ToNSec() / interval_.ToNSec();
+ const monotonic_clock::duration difference = next_time - last_time_;
+ const int result = difference / interval_;
CHECK_EQ(difference, interval_ * result);
- CHECK_EQ(0, (next_time - offset_).ToNSec() % interval_.ToNSec());
+ CHECK_EQ(
+ 0, (next_time - offset_).time_since_epoch().count() % interval_.count());
CHECK_GE(next_time, now);
CHECK_LE(next_time - now, interval_);
last_time_ = next_time;
diff --git a/aos/common/util/phased_loop.h b/aos/common/util/phased_loop.h
index fc0f247..7614ed2 100644
--- a/aos/common/util/phased_loop.h
+++ b/aos/common/util/phased_loop.h
@@ -22,40 +22,47 @@
// ...
// 10000.1s
// offset must be >= Time::kZero and < interval.
- PhasedLoop(const Time &interval, const Time &offset = Time::kZero)
+ PhasedLoop(
+ const monotonic_clock::duration interval,
+ const monotonic_clock::duration offset = monotonic_clock::duration(0))
: interval_(interval), offset_(offset), last_time_(offset) {
- CHECK_GE(offset, Time::kZero);
- CHECK_GT(interval, Time::kZero);
+ CHECK_GE(offset, monotonic_clock::duration(0));
+ CHECK_GT(interval, monotonic_clock::duration(0));
CHECK_LT(offset, interval);
Reset();
}
// Resets the count of skipped iterations.
- // Iterate(now) will return 1 and set sleep_time() to something within
- // interval of now.
- void Reset(const Time &now = Time::Now()) { Iterate(now - interval_); }
+ // Iterate(monotonic_now) will return 1 and set sleep_time() to something
+ // within interval of monotonic_now.
+ void Reset(const monotonic_clock::time_point monotonic_now =
+ monotonic_clock::now()) {
+ Iterate(monotonic_now - interval_);
+ }
- // Calculates the next time to run after now.
+ // Calculates the next time to run after monotonic_now.
// The result can be retrieved with sleep_time().
// Returns the number of iterations which have passed (1 if this is called
- // often enough). This can be < 1 iff now goes backwards between calls.
- int Iterate(const Time &now = Time::Now());
+ // often enough). This can be < 1 iff monotonic_now goes backwards between
+ // calls.
+ int Iterate(const monotonic_clock::time_point monotonic_now =
+ monotonic_clock::now());
// Sleeps until the next time and returns the number of iterations which have
// passed.
int SleepUntilNext() {
- const int r = Iterate(Time::Now());
- SleepUntil(sleep_time());
+ const int r = Iterate(monotonic_clock::now());
+ ::std::this_thread::sleep_until(sleep_time());
return r;
}
- const Time &sleep_time() const { return last_time_; }
+ monotonic_clock::time_point sleep_time() const { return last_time_; }
private:
- const Time interval_, offset_;
+ const monotonic_clock::duration interval_, offset_;
// The time we most recently slept until.
- Time last_time_ = Time::kZero;
+ monotonic_clock::time_point last_time_ = monotonic_clock::epoch();
};
} // namespace time
diff --git a/aos/common/util/phased_loop_test.cc b/aos/common/util/phased_loop_test.cc
index 1641a92..b013c2e 100644
--- a/aos/common/util/phased_loop_test.cc
+++ b/aos/common/util/phased_loop_test.cc
@@ -8,111 +8,115 @@
namespace time {
namespace testing {
+using ::std::chrono::milliseconds;
+
class PhasedLoopTest : public ::testing::Test {
protected:
- PhasedLoopTest() {
- ::aos::testing::EnableTestLogging();
- }
+ PhasedLoopTest() { ::aos::testing::EnableTestLogging(); }
};
typedef PhasedLoopTest PhasedLoopDeathTest;
+monotonic_clock::time_point InMs(int ms) {
+ return monotonic_clock::time_point(::std::chrono::milliseconds(ms));
+}
+
TEST_F(PhasedLoopTest, Reset) {
{
- PhasedLoop loop(Time::InMS(100), Time::kZero);
+ PhasedLoop loop(milliseconds(100), milliseconds(0));
- loop.Reset(Time::kZero);
- EXPECT_EQ(Time::InMS(0), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::kZero));
- EXPECT_EQ(Time::InMS(100), loop.sleep_time());
+ loop.Reset(monotonic_clock::epoch());
+ EXPECT_EQ(InMs(0), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+ EXPECT_EQ(InMs(100), loop.sleep_time());
- loop.Reset(Time::InMS(99));
- EXPECT_EQ(Time::InMS(0), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(99)));
- EXPECT_EQ(Time::InMS(100), loop.sleep_time());
+ loop.Reset(InMs(99));
+ EXPECT_EQ(InMs(0), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(99)));
+ EXPECT_EQ(InMs(100), loop.sleep_time());
- loop.Reset(Time::InMS(100));
- EXPECT_EQ(Time::InMS(100), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(199)));
- EXPECT_EQ(Time::InMS(200), loop.sleep_time());
+ loop.Reset(InMs(100));
+ EXPECT_EQ(InMs(100), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(199)));
+ EXPECT_EQ(InMs(200), loop.sleep_time());
- loop.Reset(Time::InMS(101));
- EXPECT_EQ(Time::InMS(100), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(101)));
- EXPECT_EQ(Time::InMS(200), loop.sleep_time());
+ loop.Reset(InMs(101));
+ EXPECT_EQ(InMs(100), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(101)));
+ EXPECT_EQ(InMs(200), loop.sleep_time());
}
{
- PhasedLoop loop(Time::InMS(100), Time::InMS(1));
- loop.Reset(Time::kZero);
- EXPECT_EQ(Time::InMS(-99), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::kZero));
- EXPECT_EQ(Time::InMS(1), loop.sleep_time());
+ PhasedLoop loop(milliseconds(100), milliseconds(1));
+ loop.Reset(monotonic_clock::epoch());
+ EXPECT_EQ(InMs(-99), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+ EXPECT_EQ(InMs(1), loop.sleep_time());
}
{
- PhasedLoop loop(Time::InMS(100), Time::InMS(99));
+ PhasedLoop loop(milliseconds(100), milliseconds(99));
- loop.Reset(Time::kZero);
- EXPECT_EQ(Time::InMS(-1), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::kZero));
- EXPECT_EQ(Time::InMS(99), loop.sleep_time());
+ loop.Reset(monotonic_clock::epoch());
+ EXPECT_EQ(InMs(-1), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+ EXPECT_EQ(InMs(99), loop.sleep_time());
- loop.Reset(Time::InMS(98));
- EXPECT_EQ(Time::InMS(-1), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(98)));
- EXPECT_EQ(Time::InMS(99), loop.sleep_time());
+ loop.Reset(InMs(98));
+ EXPECT_EQ(InMs(-1), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(98)));
+ EXPECT_EQ(InMs(99), loop.sleep_time());
- loop.Reset(Time::InMS(99));
- EXPECT_EQ(Time::InMS(99), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(99)));
- EXPECT_EQ(Time::InMS(199), loop.sleep_time());
+ loop.Reset(InMs(99));
+ EXPECT_EQ(InMs(99), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(99)));
+ EXPECT_EQ(InMs(199), loop.sleep_time());
- loop.Reset(Time::InMS(100));
- EXPECT_EQ(Time::InMS(99), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(100)));
- EXPECT_EQ(Time::InMS(199), loop.sleep_time());
+ loop.Reset(InMs(100));
+ EXPECT_EQ(InMs(99), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(100)));
+ EXPECT_EQ(InMs(199), loop.sleep_time());
}
}
TEST_F(PhasedLoopTest, Iterate) {
{
- PhasedLoop loop(Time::InMS(100), Time::InMS(99));
- loop.Reset(Time::kZero);
- EXPECT_EQ(1, loop.Iterate(Time::kZero));
- EXPECT_EQ(Time::InMS(99), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(100)));
- EXPECT_EQ(Time::InMS(199), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(100)));
- EXPECT_EQ(Time::InMS(199), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(101)));
- EXPECT_EQ(Time::InMS(199), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(198)));
- EXPECT_EQ(Time::InMS(199), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(199)));
- EXPECT_EQ(Time::InMS(299), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(300)));
- EXPECT_EQ(Time::InMS(399), loop.sleep_time());
- EXPECT_EQ(3, loop.Iterate(Time::InMS(600)));
- EXPECT_EQ(Time::InMS(699), loop.sleep_time());
+ PhasedLoop loop(milliseconds(100), milliseconds(99));
+ loop.Reset(monotonic_clock::epoch());
+ EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+ EXPECT_EQ(InMs(99), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(100)));
+ EXPECT_EQ(InMs(199), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(100)));
+ EXPECT_EQ(InMs(199), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(101)));
+ EXPECT_EQ(InMs(199), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(198)));
+ EXPECT_EQ(InMs(199), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(199)));
+ EXPECT_EQ(InMs(299), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(300)));
+ EXPECT_EQ(InMs(399), loop.sleep_time());
+ EXPECT_EQ(3, loop.Iterate(InMs(600)));
+ EXPECT_EQ(InMs(699), loop.sleep_time());
}
{
- PhasedLoop loop(Time::InMS(100), Time::InMS(1));
- loop.Reset(Time::kZero);
- EXPECT_EQ(1, loop.Iterate(Time::kZero));
- EXPECT_EQ(Time::InMS(1), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(100)));
- EXPECT_EQ(Time::InMS(101), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(100)));
- EXPECT_EQ(Time::InMS(101), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(103)));
- EXPECT_EQ(Time::InMS(201), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(198)));
- EXPECT_EQ(Time::InMS(201), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(200)));
- EXPECT_EQ(Time::InMS(201), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(201)));
- EXPECT_EQ(Time::InMS(301), loop.sleep_time());
- EXPECT_EQ(3, loop.Iterate(Time::InMS(600)));
- EXPECT_EQ(Time::InMS(601), loop.sleep_time());
+ PhasedLoop loop(milliseconds(100), milliseconds(1));
+ loop.Reset(monotonic_clock::epoch());
+ EXPECT_EQ(1, loop.Iterate(monotonic_clock::epoch()));
+ EXPECT_EQ(InMs(1), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(100)));
+ EXPECT_EQ(InMs(101), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(100)));
+ EXPECT_EQ(InMs(101), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(103)));
+ EXPECT_EQ(InMs(201), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(198)));
+ EXPECT_EQ(InMs(201), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(200)));
+ EXPECT_EQ(InMs(201), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(201)));
+ EXPECT_EQ(InMs(301), loop.sleep_time());
+ EXPECT_EQ(3, loop.Iterate(InMs(600)));
+ EXPECT_EQ(InMs(601), loop.sleep_time());
}
}
@@ -120,40 +124,42 @@
// This seems like a rare case at first, but starting from zero needs to
// work, which means negatives should too.
TEST_F(PhasedLoopTest, CrossingZero) {
- PhasedLoop loop(Time::InMS(100), Time::InMS(1));
- loop.Reset(Time::InMS(-1000));
- EXPECT_EQ(Time::InMS(-1099), loop.sleep_time());
- EXPECT_EQ(9, loop.Iterate(Time::InMS(-250)));
- EXPECT_EQ(Time::InMS(-199), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(-199)));
- EXPECT_EQ(Time::InMS(-99), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(-90)));
- EXPECT_EQ(Time::InMS(1), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(0)));
- EXPECT_EQ(Time::InMS(1), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(1)));
- EXPECT_EQ(Time::InMS(101), loop.sleep_time());
+ PhasedLoop loop(milliseconds(100), milliseconds(1));
+ loop.Reset(InMs(-1000));
+ EXPECT_EQ(InMs(-1099), loop.sleep_time());
+ EXPECT_EQ(9, loop.Iterate(InMs(-250)));
+ EXPECT_EQ(InMs(-199), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(-199)));
+ EXPECT_EQ(InMs(-99), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(-90)));
+ EXPECT_EQ(InMs(1), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(0)));
+ EXPECT_EQ(InMs(1), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(1)));
+ EXPECT_EQ(InMs(101), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(2)));
- EXPECT_EQ(Time::InMS(101), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(2)));
+ EXPECT_EQ(InMs(101), loop.sleep_time());
- EXPECT_EQ(-2, loop.Iterate(Time::InMS(-101)));
- EXPECT_EQ(Time::InMS(-99), loop.sleep_time());
- EXPECT_EQ(1, loop.Iterate(Time::InMS(-99)));
- EXPECT_EQ(Time::InMS(1), loop.sleep_time());
+ EXPECT_EQ(-2, loop.Iterate(InMs(-101)));
+ EXPECT_EQ(InMs(-99), loop.sleep_time());
+ EXPECT_EQ(1, loop.Iterate(InMs(-99)));
+ EXPECT_EQ(InMs(1), loop.sleep_time());
- EXPECT_EQ(0, loop.Iterate(Time::InMS(-99)));
- EXPECT_EQ(Time::InMS(1), loop.sleep_time());
+ EXPECT_EQ(0, loop.Iterate(InMs(-99)));
+ EXPECT_EQ(InMs(1), loop.sleep_time());
}
// Tests that passing invalid values to the constructor dies correctly.
TEST_F(PhasedLoopDeathTest, InvalidValues) {
- EXPECT_DEATH(PhasedLoop(Time::InMS(1), Time::InMS(2)), ".*offset<interval.*");
- EXPECT_DEATH(PhasedLoop(Time::InMS(1), Time::InMS(1)), ".*offset<interval.*");
- EXPECT_DEATH(PhasedLoop(Time::InMS(1), Time::InMS(-1)),
- ".*offset>=Time::kZero.*");
- EXPECT_DEATH(PhasedLoop(Time::InMS(0), Time::InMS(0)),
- ".*interval>Time::kZero.*");
+ EXPECT_DEATH(PhasedLoop(milliseconds(1), milliseconds(2)),
+ ".*offset<interval.*");
+ EXPECT_DEATH(PhasedLoop(milliseconds(1), milliseconds(1)),
+ ".*offset<interval.*");
+ EXPECT_DEATH(PhasedLoop(milliseconds(1), milliseconds(-1)),
+ ".*offset>=monotonic_clock::duration\\(0\\).*");
+ EXPECT_DEATH(PhasedLoop(milliseconds(0), milliseconds(0)),
+ ".*interval>monotonic_clock::duration\\(0\\).*");
}
} // namespace testing
diff --git a/aos/linux_code/ipc_lib/aos_sync.cc b/aos/linux_code/ipc_lib/aos_sync.cc
index 92eb1a1..b0b560e 100644
--- a/aos/linux_code/ipc_lib/aos_sync.cc
+++ b/aos/linux_code/ipc_lib/aos_sync.cc
@@ -954,9 +954,6 @@
int futex_wait_timeout(aos_futex *m, const struct timespec *timeout) {
RunObservers run_observers(m, false);
- if (__atomic_load_n(m, __ATOMIC_SEQ_CST) != 0) {
- return 0;
- }
const int ret = sys_futex_wait(FUTEX_WAIT, m, 0, timeout);
if (ret != 0) {
if (ret == -EINTR) {
diff --git a/aos/linux_code/ipc_lib/aos_sync.h b/aos/linux_code/ipc_lib/aos_sync.h
index 3495e73..5b7a865 100644
--- a/aos/linux_code/ipc_lib/aos_sync.h
+++ b/aos/linux_code/ipc_lib/aos_sync.h
@@ -111,9 +111,10 @@
// example messages are available to read on a queue), use the condition_
// functions or there will be race conditions.
-// Wait for the futex to be set. Will return immediately if it's already set.
+// Wait for the futex to be set. Will return immediately if it's already set
+// (after a syscall).
// Returns 0 if successful or it was already set, 1 if interrupted by a signal,
-// or -1 with an error in errno.
+// or -1 with an error in errno. Can return 0 spuriously.
int futex_wait(aos_futex *m) __attribute__((warn_unused_result));
// The same as futex_wait except returns 2 if it times out.
int futex_wait_timeout(aos_futex *m, const struct timespec *timeout)
diff --git a/aos/linux_code/ipc_lib/ipc_comparison.cc b/aos/linux_code/ipc_lib/ipc_comparison.cc
index 0a57ded..f375a17 100644
--- a/aos/linux_code/ipc_lib/ipc_comparison.cc
+++ b/aos/linux_code/ipc_lib/ipc_comparison.cc
@@ -17,6 +17,7 @@
#include <thread>
#include <memory>
#include <string>
+#include <atomic>
#include "aos/common/logging/logging.h"
#include "aos/common/logging/implementations.h"
@@ -811,7 +812,7 @@
return 1;
}
- bool done = false;
+ ::std::atomic<bool> done{false};
::std::thread server([&ping_ponger, &done]() {
if (FLAGS_server_priority > 0) {
@@ -854,6 +855,11 @@
const time::Time end = time::Time::Now();
+ // Try to make sure the server thread gets past its check of done so our
+ // Ping() down below doesn't hang. Kind of lame, but doing better would
+ // require complicating the interface to each implementation which isn't worth
+ // it here.
+ ::std::this_thread::sleep_for(::std::chrono::milliseconds(200));
done = true;
ping_ponger->PingData();
ping_ponger->Ping();
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index f2b14a9..5757b58 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -107,6 +107,8 @@
right_gear_ = ComputeGear(position->right_shifter_position,
dt_config_.right_drive, right_high_requested_);
break;
+ case ShifterType::NO_SHIFTER:
+ break;
}
kf_.set_controller_index(ControllerIndexFromGears());
diff --git a/frc971/control_loops/drivetrain/drivetrain_config.h b/frc971/control_loops/drivetrain/drivetrain_config.h
index ea76ca9..24cc628 100644
--- a/frc971/control_loops/drivetrain/drivetrain_config.h
+++ b/frc971/control_loops/drivetrain/drivetrain_config.h
@@ -12,11 +12,12 @@
enum class ShifterType : int32_t {
HALL_EFFECT_SHIFTER = 0, // Detect when inbetween gears.
- SIMPLE_SHIFTER = 1, // Switch gears without speedmatch logic.
+ SIMPLE_SHIFTER = 1, // Switch gears without speedmatch logic.
+ NO_SHIFTER = 2, // Only one gear ratio.
};
enum class LoopType : int32_t {
- OPEN_LOOP = 0, // Only use open loop logic.
+ OPEN_LOOP = 0, // Only use open loop logic.
CLOSED_LOOP = 1, // Add in closed loop calculation.
};
@@ -32,10 +33,10 @@
::std::function<StateFeedbackLoop<2, 2, 2>()> make_v_drivetrain_loop;
::std::function<StateFeedbackLoop<7, 2, 3>()> make_kf_drivetrain_loop;
- double dt; // Control loop time step.
+ double dt; // Control loop time step.
double robot_radius; // Robot radius, in meters.
double wheel_radius; // Wheel radius, in meters.
- double v; // Motor velocity constant.
+ double v; // Motor velocity constant.
// Gear ratios, from wheel to motor shaft.
double high_gear_ratio;
diff --git a/frc971/wpilib/pdp_fetcher.cc b/frc971/wpilib/pdp_fetcher.cc
index 4e6be32..846de60 100644
--- a/frc971/wpilib/pdp_fetcher.cc
+++ b/frc971/wpilib/pdp_fetcher.cc
@@ -1,5 +1,7 @@
#include "frc971/wpilib/pdp_fetcher.h"
+#include <chrono>
+
#include "aos/common/logging/queue_logging.h"
#include "aos/linux_code/init.h"
#include "aos/common/util/phased_loop.h"
@@ -12,8 +14,8 @@
::aos::SetCurrentThreadName("PDPFetcher");
::std::unique_ptr<PowerDistributionPanel> pdp(new PowerDistributionPanel());
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(4));
while (true) {
{
diff --git a/y2012/wpilib/wpilib_interface.cc b/y2012/wpilib/wpilib_interface.cc
index 6702dc4..290f067 100644
--- a/y2012/wpilib/wpilib_interface.cc
+++ b/y2012/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
#include <unistd.h>
#include <inttypes.h>
+#include <chrono>
#include <thread>
#include <mutex>
#include <functional>
@@ -104,8 +105,8 @@
&DriverStation::GetInstance();
#endif
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(4));
::aos::SetCurrentThreadRealtimePriority(40);
while (run_) {
@@ -183,8 +184,8 @@
::aos::SetCurrentThreadName("Solenoids");
::aos::SetCurrentThreadRealtimePriority(27);
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(1));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(1));
while (run_) {
{
diff --git a/y2014/control_loops/python/extended_lqr.tex b/y2014/control_loops/python/extended_lqr.tex
new file mode 100644
index 0000000..52d0949
--- /dev/null
+++ b/y2014/control_loops/python/extended_lqr.tex
@@ -0,0 +1,766 @@
+\documentclass[a4paper,12pt]{article}
+\usepackage{amsmath}
+\begin{document}
+
+% From http://www.eecs.tufts.edu/~khan/Courses/Spring2013/EE194/Lecs/Lec9and10.pdf
+% and http://www.cs.unc.edu/~wens/WAFR2014-Sun.pdf
+% (which references http://maeresearch.ucsd.edu/skelton/publications/weiwei_ilqg_CDC43.pdf)
+% and http://arl.cs.utah.edu/pubs/ISRR2013.pdf
+
+\section{Backwards Pass}
+
+Let's start with some definitions for the standard LQR controller.
+$c_t(\boldsymbol{x}, \boldsymbol{u})$ is the cost for the iteration $t$ given that we are at $\boldsymbol{x}$ and are going to apply $\boldsymbol{u}$ for one cycle.
+$v_t(\boldsymbol{x})$ is the optimal cost-to-go for the starting point $\boldsymbol{x}$ at step $t$.
+$v_N(\boldsymbol{x})$ may be defined to be a different final cost from $v_t(\boldsymbol{x})$ if need be, where $N$ is the horizon.
+
+$$\begin{array}{rcl}
+c_t(\boldsymbol{x}, \boldsymbol{u}) &=&
+ \frac{1}{2}
+ \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+ \begin{bmatrix} Q_t & P_t^T \\ P_t & R_t \end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix} +
+ \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+ \begin{bmatrix} \boldsymbol{q}_t \\ \boldsymbol{r}_t \end{bmatrix} +
+ q_t \\
+v_{t + 1}(\boldsymbol{x}) &=&
+ \frac{1}{2} \boldsymbol{x}^T S_{t + 1} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{s}_{t + 1} + s_{t + 1} \\
+
+g_t(\boldsymbol{x}_t, \boldsymbol{u}_t) = \boldsymbol{x}_{t + 1}(\boldsymbol{u}_t) &=&
+ A_{t} \boldsymbol{x}_t + B_t \boldsymbol{u}_t + \boldsymbol{c}_{t} \\
+
+v_{t}(\boldsymbol{x}_t, \boldsymbol{u}_t) &=&
+ v_{t+1}(\boldsymbol{x}_{t+1}) +
+ c_t(\boldsymbol{x}_t, \boldsymbol{u}_t) \\\
+ &=&
+ v_{t+1}(g_t(\boldsymbol{x}_{t}, \boldsymbol{u}_t)) +
+ c_t(\boldsymbol{x}_t, \boldsymbol{u}_t)
+ \\
+\end{array}$$
+
+Now, let's calculate $v_t(\boldsymbol{x})$ given $v_{t+1}(\boldsymbol{x})$ and the step cost from $c_t(\boldsymbol{x})$.
+This tells us the cost of applying $\boldsymbol{u}$ starting from $\boldsymbol{x}$.
+We will then optimize over all $\boldsymbol{u}$ to find the optimal next state and cost for that state.
+This lets us then use dynamic programing methods to work out the optimal $\boldsymbol{x}$ and $\boldsymbol{u}$ at each timestep.
+
+We want to get a quadratic solution of the form
+$$v_{t}(\boldsymbol{x}) =
+ \frac{1}{2} \boldsymbol{x}^T S_{t} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{s}_{t} + s_{t}$$ for each step.
+
+$$\begin{array}{rcl}
+v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=&
+ \frac{1}{2} \left( A_{t}\boldsymbol{x} + B_{t}\boldsymbol{u} + \boldsymbol{c}_{t}\right)^T
+ S_{t + 1}
+ \left( A_{t}\boldsymbol{x} + B_{t}\boldsymbol{u} + \boldsymbol{c}_{t}\right) +
+ \left( A_{t}\boldsymbol{x} + B_{t}\boldsymbol{u} + \boldsymbol{c}_{t}\right)^T \boldsymbol{s}_{t + 1} +
+ s_{t + 1} + \\ &&
+ \frac{1}{2}
+ \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+ \begin{bmatrix} Q_{t} & P_{t}^T \\ P_{t} & R_{t} \end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix} +
+ \begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+ \begin{bmatrix} \boldsymbol{q}_{t} \\ \boldsymbol{r}_{t} \end{bmatrix} +
+ q_{t}
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T A_{t}^T S_{t + 1} A_{t} \boldsymbol{x} +
+ \boldsymbol{u}^T B_{t}^T S_{t + 1} A_{t} \boldsymbol{x} +
+ \boldsymbol{c}_t^T S_{t + 1} A_{t} \boldsymbol{x} + \right. \\ &&
+ \left. \boldsymbol{x}^T A_{t}^T S_{t + 1} B_{t} \boldsymbol{u} +
+ \boldsymbol{u}^T B_{t}^T S_{t + 1} B_{t} \boldsymbol{u} +
+ \boldsymbol{c}_t^T S_{t + 1} B_{t} \boldsymbol{u} + \right. \\ &&
+ \left. \boldsymbol{x}^T A_{t}^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{u}^T B_{t}^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+ \right) + \\ &&
+ \boldsymbol{x}^T A_{t}^T \boldsymbol{s}_{t + 1} +
+ \boldsymbol{u}^T B_{t}^T \boldsymbol{s}_{t + 1} +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} +
+ s_{t + 1} + \\ &&
+ \frac{1}{2} \left(\boldsymbol{x}^T Q_t \boldsymbol{x} + \boldsymbol{u}^T P_t \boldsymbol{x} + \boldsymbol{x}^T P_t^T \boldsymbol{u} + \boldsymbol{u}^T R_t \boldsymbol{u} \right) + \boldsymbol{x}^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t + q_t
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+ \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+ \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} +
+ \boldsymbol{q}_t \right)+
+
+ \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} +
+ \boldsymbol{r}_t \right) +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} +
+ q_t + \\ &&
+ \frac{1}{2} \left( \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{x}^T A_{t}^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{u}^T B_{t}^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T S_{t + 1} B_{t} \boldsymbol{u} +
+ \boldsymbol{c}_t^T S_{t + 1} A_{t} \boldsymbol{x} \right)
+\end{array}$$
+
+Now, let's find the optimal $\boldsymbol{u}$. Do this by evaluating $\frac{\partial}{\partial \boldsymbol{u}} v_t(\boldsymbol{x}, \boldsymbol{u}) = 0$.
+
+$$\begin{array}{rcl}
+\frac{\partial}{\partial \boldsymbol{u}} v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=& \frac{1}{2} \left( 2 \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) + 2 \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) + 2 \boldsymbol{c}_t^T S_{t + 1} B_{t} \right) + \\&&\boldsymbol{s}_{t + 1}^T B_{t} + \boldsymbol{r}_t^T \\
+
+\frac{\partial}{\partial \boldsymbol{u}} v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=& \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) + \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) + \boldsymbol{c}_t^T S_{t + 1} B_{t} + \boldsymbol{s}_{t + 1}^T B_{t} + \boldsymbol{r}_t^T \\
+0 &=& \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) + \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) + \boldsymbol{c}_t^T S_{t + 1} B_{t} + \boldsymbol{s}_{t + 1}^T B_{t} + \boldsymbol{r}_t^T
+\end{array}$$
+$$\begin{array}{rcl}
+\boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) &=& - \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) - \boldsymbol{c}_t^T S_{t + 1} B_{t} - \boldsymbol{s}_{t + 1}^T B_{t} - \boldsymbol{r}_t^T \\
+\left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} &=& - \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} - B_t^T S_{t + 1} \boldsymbol{c}_t - B_{t}^T \boldsymbol{s}_{t + 1}- \boldsymbol{r}_t \\
+\boldsymbol{u} &=& - \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) ^{-1} \left( \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} + B_t^T S_{t + 1} \boldsymbol{c}_t + B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t \right)
+\end{array}$$
+
+This gives us the optimal $\boldsymbol{u}$. There are some substitutions defined here from the 2013 paper which make it easier to read.
+Note: the 2014 paper uses different letters for these same quantities\dots
+\\
+$$\begin{array}{rcl}
+C_t &=& B^T_t S_{t + 1} A_t + P_t \\
+E_t &=& B_{t}^T S_{t + 1} B_{t} + R_t \\
+L_t &=& - E_t ^{-1} C_t \\
+
+\boldsymbol{e}_t &=& B_t^T S_{t + 1} \boldsymbol{c}_t + B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t \\
+\boldsymbol{l}_t &=& - E^{-1}_t \boldsymbol{e}_t \\
+
+D_t &=& A_t^T S_{t + 1} A_t + Q_t \\
+\boldsymbol{d}_t &=& A_t^T S_{t + 1} \boldsymbol{c}_t + A_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{q}_t
+\\
+\boldsymbol{u} &=& L_t \boldsymbol{x} + \boldsymbol{l}_t
+\end{array}$$
+
+With these, we can simplify $\boldsymbol{u}$ a bit and make it look like the 2014 paper has it.
+
+$$\begin{array}{rcl}
+ \boldsymbol{u} &=& -E_t^{-1} \left( C_t \boldsymbol{x} + \boldsymbol{e}_t \right) \\
+ \boldsymbol{u} &=& -E_t^{-1} C_t \boldsymbol{x} - E_t^{-1} \boldsymbol{e}_t
+\end{array}$$
+
+For reference, here are some equivalences between the symbols used in the 2013
+paper (the ones we use) and the 2014 paper.
+TODO(Brian): Figure out where the ones in the 2014 paper are defined instead of
+guessing by pattern-matching.
+\\ \begin{tabular}{ | r | l | }
+ \hline
+ 2013 paper (ours) & 2014 paper \\
+ \hline
+ $C_t$ & $E_t$ \\
+ $D_t$ & $C_t$ \\
+ $\boldsymbol{d}_t$ & $\boldsymbol{c}_t$ \\
+ $E_t$ & $D_t$ \\
+ $\boldsymbol{e}_t$ & $\boldsymbol{d}_t$ \\
+ \hline
+\end{tabular} \\
+
+Now, let's solve for the new cost function.
+
+$$\begin{array}{rcl}
+v_{t}(\boldsymbol{x}, \boldsymbol{u}) &=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+ \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+ \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} +
+ \boldsymbol{q}_t \right)+
+
+ \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} +
+ \boldsymbol{r}_t \right) +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} +
+ q_t + \\ &&
+ \frac{1}{2} \left( \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{x}^T A_{t}^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{u}^T B_{t}^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T S_{t + 1} B_{t} \boldsymbol{u} +
+ \boldsymbol{c}_t^T S_{t + 1} A_{t} \boldsymbol{x} \right)
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+ \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+
+ \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{q}_t +
+ \frac{1}{2} A_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+ \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t +
+ \frac{1}{2} B_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \left( A_t \boldsymbol{x} +
+ B_t \boldsymbol{u} + \boldsymbol{c}_t \right) + \\ &&
+
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} A_{t} + Q_t \right) \boldsymbol{x} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} A_{t} + P_t \right) \boldsymbol{x} \right. + \\ &&
+ \left. \boldsymbol{x}^T \left( A_{t}^T S_{t + 1} B_{t} + P_t^T \right) \boldsymbol{u} +
+ \boldsymbol{u}^T \left( B_{t}^T S_{t + 1} B_{t} + R_t \right) \boldsymbol{u} \right) + \\ &&
+
+ \boldsymbol{x}^T \left(A_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{q}_t +
+ A_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+ \boldsymbol{u}^T \left( B_{t}^T \boldsymbol{s}_{t + 1} + \boldsymbol{r}_t +
+ B_{t}^T S_{t + 1} \boldsymbol{c}_t \right) + \\ &&
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T D_t \boldsymbol{x} +
+ \boldsymbol{u}^T C_t \boldsymbol{x} +
+ \boldsymbol{x}^T C_t^T \boldsymbol{u} +
+ \boldsymbol{u}^T E_t \boldsymbol{u} \right) + \\ &&
+
+ \boldsymbol{x}^T \boldsymbol{d}_t +
+ \boldsymbol{u}^T \boldsymbol{e}_t + \\ &&
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T D_t \boldsymbol{x} +
+ \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right)^T C_t \boldsymbol{x} \right. + \\ &&
+ \left. \boldsymbol{x}^T C_t^T \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right) +
+ \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right)^T E_t \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right) \right) + \\ &&
+
+ \boldsymbol{x}^T \boldsymbol{d}_t +
+ \left( L_t \boldsymbol{x} + \boldsymbol{l}_t \right)^T \boldsymbol{e}_t + \\&&
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+ \frac{1}{2} \left(
+ \boldsymbol{x}^T D_t \boldsymbol{x} + \right.
+ \boldsymbol{x}^T L_t^T C_t \boldsymbol{x} + \boldsymbol{l}_t^T C_t \boldsymbol{x} + \\ &&
+
+ \left. \boldsymbol{x}^T C_t^T L_t \boldsymbol{x} + \boldsymbol{x}^T C_t^T \boldsymbol{l}_t +
+
+ \boldsymbol{x}^T L_t^T E_t L_t \boldsymbol{x} +
+ \boldsymbol{l}_t^T E_t L_t \boldsymbol{x} +
+ \boldsymbol{x}^T L_t^T E_t \boldsymbol{l}_t +
+ \boldsymbol{l}_t^T E_t \boldsymbol{l}_t \right) + \\&&
+
+ \boldsymbol{x}^T \boldsymbol{d}_t +
+ \boldsymbol{x}^T L_t^T \boldsymbol{e}_t + \boldsymbol{l}^T_t \boldsymbol{e}_t + \\&&
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t
+\\
+&=&
+ \frac{1}{2}
+ \boldsymbol{x}^T \left(
+ D_t +
+ L_t^T C_t +
+ C_t^T L_t +
+ L_t^T E_t L_t
+ \right) \boldsymbol{x} + \\ &&
+
+ \boldsymbol{x}^T \left(
+ \frac{1}{2} \left( C_t^T \boldsymbol{l}_t +
+ L_t^T E_t \boldsymbol{l}_t \right) +
+ \boldsymbol{d}_t +
+ L_t^T \boldsymbol{e}_t \right) +
+ \frac{1}{2} \left( \boldsymbol{l}_t^T E_t L_t + \boldsymbol{l}_t^T C_t \right) \boldsymbol{x} + \\ &&
+
+ \frac{1}{2} \boldsymbol{l}_t^T E_t \boldsymbol{l}_t +
+ \boldsymbol{l}^T_t \boldsymbol{e}_t +
+
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\\
+&=&
+ \frac{1}{2}
+ \boldsymbol{x}^T \left(
+ D_t +
+ L_t^T C_t +
+ C_t^T L_t +
+ L_t^T E_t L_t
+ \right) \boldsymbol{x} + \\ &&
+
+ \boldsymbol{x}^T \left(
+ C_t^T \boldsymbol{l}_t +
+ L_t^T E_t \boldsymbol{l}_t +
+ \boldsymbol{d}_t +
+ L_t^T \boldsymbol{e}_t \right) + \\ &&
+
+ \frac{1}{2} \boldsymbol{l}_t^T E_t \boldsymbol{l}_t +
+ \boldsymbol{l}^T_t \boldsymbol{e}_t +
+
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\end{array}$$
+
+Ok, let's now pull out the 3 variables of interest and do further simplification.
+
+$$\begin{array}{rcl}
+v_{t}(\boldsymbol{x}) &=&
+ \frac{1}{2} \boldsymbol{x}^T S_{t} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{s}_{t} + s_{t} \\
+S_t &=&
+ D_t +
+ L_t^T C_t +
+ C_t^T L_t +
+ L_t^T E_t L_t \\
+ &=&
+ D_t -
+ C_t^T E_t^{-1} C_t -
+ C_t^T E_t^{-1} C_t +
+ C_t^T E_t^{-1} C_t \\
+ &=& D_t - C_t^T E_t^{-1} C_t
+\\
+\boldsymbol{s}_t &=&
+ \left( C_t^T + L_t^T E_t \right) \boldsymbol{l}_t +
+ \boldsymbol{d}_t +
+ L_t^T \boldsymbol{e}_t \\
+
+ &=&
+ \left( C_t^T - C_t^T E_t^{-1} E_t \right) \boldsymbol{l}_t +
+ \boldsymbol{d}_t -
+ C_t^T E_t^{-1} \boldsymbol{e}_t \\
+ &=& \boldsymbol{d}_t - C_t^T E_t^{-1} \boldsymbol{e}_t
+\\
+s_t &=&
+ \frac{1}{2} \boldsymbol{l}_t^T E_t \boldsymbol{l}_t +
+ \boldsymbol{l}^T_t \boldsymbol{e}_t +
+
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\\
+&=&
+\frac{1}{2} \boldsymbol{e}_t^T E_t^{-1} E_t E_t^{-1} \boldsymbol{e}_t -
+ \boldsymbol{e}_t^T E_t^{-1} \boldsymbol{e}_t +
+
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1} + q_t +
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t
+\\
+&=&
+q_t - \frac{1}{2} \boldsymbol{e}_t^T E_t^{-1} \boldsymbol{e}_t +
+
+ \frac{1}{2} \boldsymbol{c}_t^T S_{t + 1} \boldsymbol{c}_t +
+ \boldsymbol{c}_t^T \boldsymbol{s}_{t + 1} + s_{t + 1}
+\end{array}$$
+
+For better or worse, everything but the constant term matches both the 2013
+paper (which has no constant term) and the 2014 paper.
+The constant term does not match the 2014 paper, but we're pretty sure it's
+correct (extended\_lqr\_derivation.py verifies what we have).
+The 2014 paper has this for the constant term instead:
+$$\begin{array}{rcl}
+s_t &=&
+ q_t - \frac{1}{2} \boldsymbol{e}_t^T E_t^{-1} \boldsymbol{e}_t
+\end{array}$$
+
+\section{Forwards Pass}
+
+Let's define the forwards pass to build the cost-to-come function.
+We must use the same cycle cost, $c_t(\boldsymbol{x}, \boldsymbol{u})$, as the backwards pass.
+The initial cost $v_0(\boldsymbol{x})$ needs to evaluate to $0$ at $\boldsymbol{x}_0$ since
+there is no cost needed to get from $\boldsymbol{x}_0$ to $\boldsymbol{x}_0$.
+
+$$\begin{array}{rcl}
+\bar v_{t}(\boldsymbol{x}) &=&
+ \frac{1}{2} \boldsymbol{x}^T \bar S_{t} \boldsymbol{x} + \boldsymbol{x}^T \boldsymbol{\bar s}_{t} + \bar s_{t} \\
+
+\bar g_t(\boldsymbol{x}_{t + 1}, \boldsymbol{u}) = \boldsymbol{x}_{t}(\boldsymbol{u}) &=&
+ \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t} \\
+
+\bar c_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u}) &=& c_t(\bar g_{t}(\boldsymbol{x}_{t + 1}, \boldsymbol{u}), \boldsymbol{u}) \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u}) &=&
+ \bar v_{t}(\boldsymbol{x}_{t}) +
+ \bar c_t(\boldsymbol{x}_{t + 1}, \boldsymbol{u}_t)
+ \\
+&=&
+ \bar v_{t}(\bar g_t(\boldsymbol{x}_{t + 1}, \boldsymbol{u})) +
+ c_t(\bar g_{t}(\boldsymbol{x}_{t + 1}, \boldsymbol{u}), \boldsymbol{u}) \\
+ \\
+\end{array}$$
+
+It is important to note that the optimal $\boldsymbol{u}$ used to get from $\boldsymbol{x}_t$ to $\boldsymbol{x}_{t+1}$
+when evaluating $g_t(\boldsymbol{x}, \boldsymbol{u})$ is the same optimal $\boldsymbol{u}$
+used to get from $\boldsymbol{x}_{t+1}$ to $\boldsymbol{x}_t$ when evaluating $\bar g_{t}(\boldsymbol{x}_{t + 1}, \boldsymbol{u})$.
+Conveniently, this means that the $\boldsymbol{u}_t$, $L_t$, and $\boldsymbol{l}_t$ calculated in both the forwards and backwards passes is the same.
+
+Like before, we want to get a quadratic solution of the form
+$$\bar v_{t + 1}(\boldsymbol{x}_{t+1}) =
+ \frac{1}{2} \boldsymbol{x}_{t+1}^T \bar S_{t + 1} \boldsymbol{x}_{t+1} + \boldsymbol{x}_{t+1}^T \boldsymbol{\bar s}_{t + 1} + \bar s_{t + 1}$$ for each step.
+
+$$\begin{array}{rcl}
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u}) &=&
+ \frac{1}{2} \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T
+ \bar S_{t}
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\ &&
+ \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) ^T \boldsymbol{\bar s}_{t} + \bar s_{t} + \\&&
+ \frac{1}{2}
+ \begin{bmatrix} \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \\ \boldsymbol{u} \end{bmatrix}^T
+ \begin{bmatrix} Q_t & P_t^T \\ P_t & R_t \end{bmatrix}
+ \begin{bmatrix} \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \\ \boldsymbol{u} \end{bmatrix} + \\&&
+ \begin{bmatrix} \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \\ \boldsymbol{u} \end{bmatrix}^T
+ \begin{bmatrix} \boldsymbol{q}_t \\ \boldsymbol{r}_t \end{bmatrix} +
+ q_t \\
+
+ &=&
+ \frac{1}{2} \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T
+ \bar S_{t}
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\ &&
+ \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) ^T \boldsymbol{\bar s}_{t} + \bar s_{t} + \\&&
+
+ \frac{1}{2} \left(
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T Q_t \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \right. \\&&
+ \boldsymbol{u}^T P_t \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\&&
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T P_t^T \boldsymbol{u} + \\&&
+ \left. \boldsymbol{u}^T R_t \boldsymbol{u} \right) + \\&&
+
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t + q_t \\
+
+ &=&
+ \frac{1}{2} \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T
+ \left( \bar S_{t} + Q_t \right)
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) + \\ &&
+ \left(\bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) ^T \boldsymbol{\bar s}_{t} + \bar s_{t} + \\&&
+
+ \frac{1}{2} \left(
+ \boldsymbol{u}^T P_t \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right) \right. + \\&&
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T P_t^T \boldsymbol{u} + \\&&
+ \left. \boldsymbol{u}^T R_t \boldsymbol{u} \right) + \\&&
+
+ \left( \bar A_{t} \boldsymbol{x}_{t + 1} + \bar B_t \boldsymbol{u} + \boldsymbol{\bar c}_{t}\right)^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t + q_t \\
+
+ &=& \frac{1}{2} \left(
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \right. \\&&
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \\&&
+ \left. \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+ \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t \right) + \\&&
+
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \boldsymbol{\bar s}_t +
+ \boldsymbol{u}^T \bar B_t^T \boldsymbol{\bar s}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t +
+
+ \bar s_t + \\ &&
+
+ \frac{1}{2} \left( \boldsymbol{u}^T P_t \bar A_{t} \boldsymbol{x}_{t + 1} +
+ \boldsymbol{u}^T P_t \bar B_{t} \boldsymbol{u} +
+ \boldsymbol{u}^T P_t \boldsymbol{\bar c}_{t} \right) + \\&&
+ \frac{1}{2} \left( \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T \boldsymbol{u} +
+ \boldsymbol{u}^T \bar B^T_{t} P_t^T \boldsymbol{u} +
+ \boldsymbol{\bar c}_t^T P^T_t \boldsymbol{u} \right) + \\&&
+
+ \frac{1}{2} \boldsymbol{u}^T R_t \boldsymbol{u} + \\&&
+
+ \boldsymbol{x}^T_{t + 1} \bar A^T_t \boldsymbol{q}_t +
+ \boldsymbol{u}^T \bar B^T_t \boldsymbol{q}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{q}_t +
+
+ \boldsymbol{u}^T \boldsymbol{r}_t + q_t
+\end{array}$$
+
+Now, let's find the optimal $\boldsymbol{u}$.
+Do this by evaluating
+$\frac{\partial}{\partial \boldsymbol{u}} \bar v_t(\boldsymbol{x}, \boldsymbol{u}) = 0$.
+
+$$\begin{array}{rcl}
+\frac{\partial}{\partial \boldsymbol{u}} \bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u})
+ &=& \frac{1}{2} \left(
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+
+ \left(\bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1}\right)^T + \right. \\&&
+
+ 2 \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \left( \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t \right)^T + \\&&
+ \left. \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t \right) + \\&&
+ \boldsymbol{\bar s}_t ^T \bar B_t + \\&&
+
+ \frac{1}{2} \left( P_t \bar A_{t} \boldsymbol{x}_{t + 1}\right) ^T +
+ \frac{1}{2} \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T + \\&&
+
+ \frac{1}{2} \boldsymbol{u}^T \left( P_t \bar B_{t} + \bar B_t^T P_t^T \right) +
+ \frac{1}{2} \boldsymbol{u}^T \left( \bar B^T_{t} P_t^T + P_t \bar B_t \right) + \\&&
+ \frac{1}{2} \left( P_t \boldsymbol{\bar c}_{t} \right)^T +
+ \frac{1}{2} \boldsymbol{\bar c}^T_{t} P_t^T +
+
+ \boldsymbol{u}^T R_t + \\&&
+
+ \left(\bar B^T_t \boldsymbol{q}_t\right)^T +
+
+ \boldsymbol{r}_t^T \\
+
+ &=&
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+
+ \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t + \\&&
+
+ \boldsymbol{\bar s}_t ^T \bar B_t + \\&&
+
+ \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T + \\&&
+
+ \boldsymbol{u}^T \left( \bar B^T_{t} P_t^T + P_t \bar B_t \right) + \\&&
+ \boldsymbol{\bar c}^T_{t} P_t^T +
+
+ \boldsymbol{u}^T R_t + \\&&
+
+ \boldsymbol{q}_t^T \bar B_t +
+ \boldsymbol{r}_t^T \\
+0 &=&
+ \boldsymbol{x}_{t + 1}^T \left( \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t + \bar A^T_t P_t^T \right) + \\&&
+
+ \boldsymbol{u}^T \left(
+ \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \bar B^T_{t} P_t^T + P_t \bar B_t + R_t
+ \right) + \\&&
+
+ \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \boldsymbol{\bar s}_t^T \bar B_t +
+ \boldsymbol{\bar c}^T_{t} P_t^T +
+ \boldsymbol{q}_t^T \bar B_t +
+ \boldsymbol{r}_t^T \\
+\end{array}$$
+
+$$\begin{array}{rcl}
+ \boldsymbol{u}^T \left(
+ \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \bar B^T_{t} P_t^T + P_t \bar B_t + R_t
+ \right)
+ &=&
+ - \boldsymbol{x}_{t + 1}^T \left( \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t + \bar A^T_t P_t^T \right) - \\&&
+
+
+ \left( \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \boldsymbol{\bar s}_t^T \bar B_t +
+ \boldsymbol{\bar c}^T_{t} P_t^T +
+ \boldsymbol{q}_t^T \bar B_t +
+ \boldsymbol{r}_t^T \right) \\
+
+\left(
+ \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \bar B^T_{t} P_t^T + P_t \bar B_t + R_t
+\right) \boldsymbol{u}
+ &=&
+ - \left( \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t + P_t \bar A_t \right) \boldsymbol{x}_{t + 1} - \\&&
+
+ \left( \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \bar B_t^T \boldsymbol{\bar s}_t +
+ P_t \boldsymbol{\bar c}_{t} +
+ \bar B_t^T \boldsymbol{q}_t +
+ \boldsymbol{r}_t \right) \\
+\end{array}$$
+
+Some substitutions to use for simplifying:
+
+$$\begin{array}{rcl}
+\bar C_t &=& \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t + P_t \bar A_t \\
+\bar E_t &=&
+ \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t +
+ \bar B^T_{t} P_t^T + P_t \bar B_t + R_t \\
+\bar L_t &=& - \bar E_t^{-1} \bar C_t \\
+
+\boldsymbol{\bar e}_t &=&
+ \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \bar B_t^T \boldsymbol{\bar s}_t +
+ P_t \boldsymbol{\bar c}_{t} +
+ \bar B_t^T \boldsymbol{q}_t +
+ \boldsymbol{r}_t \\
+\boldsymbol{\bar l}_t &=& - \bar E_t^{-1} \boldsymbol{\bar e}_t \\
+
+\bar D_t &=& \bar A_t^T \left( \bar S_t + Q_t \right) \bar A_t \\
+\boldsymbol{\bar d}_t &=&
+ \bar A_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \bar A_t^T \left( \boldsymbol{\bar s}_t + \boldsymbol{q}_t \right) \\
+
+\boldsymbol{u} &=& - \bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \\
+\boldsymbol{u} &=& \bar L_t \boldsymbol{x}_{t + 1} + \boldsymbol{\bar l}_t \\
+
+\bar E_t \boldsymbol{u} &=& -\bar C_t \boldsymbol{x}_{t + 1} - \boldsymbol{\bar e}_t
+\end{array}$$
+
+Now, let's solve for the new cost function.
+
+$$\begin{array}{rcl}
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u})
+ &=& \frac{1}{2} \left(
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \right. \\&&
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+ \boldsymbol{u}^T \bar B_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t + \\&&
+ \left. \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar A_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \bar B_t \boldsymbol{u} +
+ \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t \right) + \\&&
+
+ \boldsymbol{x}_{t + 1}^T \bar A_t^T \boldsymbol{\bar s}_t +
+ \boldsymbol{u}^T \bar B_t^T \boldsymbol{\bar s}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t +
+
+ \bar s_t + \\ &&
+
+ \frac{1}{2} \left( \boldsymbol{u}^T P_t \bar A_{t} \boldsymbol{x}_{t + 1} +
+ \boldsymbol{u}^T P_t \bar B_{t} \boldsymbol{u} +
+ \boldsymbol{u}^T P_t \boldsymbol{\bar c}_{t} \right) + \\&&
+ \frac{1}{2} \left( \boldsymbol{x}_{t+1}^T \bar A^T_t P_t^T \boldsymbol{u} +
+ \boldsymbol{u}^T \bar B^T_{t} P_t^T \boldsymbol{u} +
+ \boldsymbol{\bar c}_t^T P^T_t \boldsymbol{u} \right) + \\&&
+
+ \frac{1}{2} \boldsymbol{u}^T R_t \boldsymbol{u} + \\&&
+
+ \boldsymbol{x}^T_{t + 1} \bar A^T_t \boldsymbol{q}_t +
+ \boldsymbol{u}^T \bar B^T_t \boldsymbol{q}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{q}_t +
+
+ \boldsymbol{u}^T \boldsymbol{r}_t + q_t \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}, \boldsymbol{u})
+ &=& \frac{1}{2} \left(
+ \boldsymbol{x}_{t + 1}^T \bar D_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{x}_{t + 1}^T \bar C_t^T \boldsymbol{u} +
+ \boldsymbol{u}^T \bar C_t \boldsymbol{x}_{t + 1} +
+ \boldsymbol{u}^T \bar E_t \boldsymbol{u} \right) + \\&&
+
+ \boldsymbol{x}_{t + 1}^T \boldsymbol{\bar d}_t +
+
+ \boldsymbol{u}^T \boldsymbol{\bar e}_t + \\&&
+
+ \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1})
+ &=& \frac{1}{2} \left(
+ \boldsymbol{x}_{t + 1}^T \bar D_t \boldsymbol{x}_{t + 1} + \right. \\ &&
+ \boldsymbol{x}_{t + 1}^T \bar C_t^T \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right) + \\&&
+ \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right)^T \bar C_t \boldsymbol{x}_{t + 1} + \\&&
+ \left. \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right)^T \bar E_t \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right) \right) + \\&&
+
+ \boldsymbol{x}_{t + 1}^T \boldsymbol{\bar d}_t +
+
+ \left( -\bar E_t^{-1} \bar C_t \boldsymbol{x}_{t + 1} - \bar E_t^{-1} \boldsymbol{\bar e}_t \right)^T \boldsymbol{\bar e}_t + \\&&
+
+ \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+
+\bar v_{t + 1}(\boldsymbol{x}_{t+1})
+ &=& \frac{1}{2}
+ \boldsymbol{x}_{t + 1}^T \left(\bar D_t - \bar C_t^T \bar E_t^{-1} \bar C_t \right) \boldsymbol{x}_{t + 1} + \\ &&
+
+ \boldsymbol{x}_{t + 1}^T \left(\boldsymbol{\bar d}_t
+ - \bar C_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t \right)\\&&
+
+ - \frac{1}{2} \boldsymbol{\bar e}_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t +
+ \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+\end{array}$$
+
+Ok, let's now pull out the 3 variables of interest and do further simplification.
+
+$$\begin{array}{rcl}
+\bar v_{t + 1}(\boldsymbol{x}_{t+1}) &=& \frac{1}{2} \boldsymbol{x}_{t + 1}^T \bar S_{t + 1} \boldsymbol{x}_{t + 1} + \boldsymbol{x}_{t + 1}^T \boldsymbol{\bar s}_{t + 1} + \bar s_{t+1} \\
+ \bar S_{t + 1} &=& \bar D_t - \bar C_t^T \bar E_t^{-1} \bar C_t \\
+ \boldsymbol{\bar s}_{t + 1} &=&
+ \left(\boldsymbol{\bar d}_t - \bar C_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t \right)\\
+
+\bar s_{t+1} &=&
+ - \frac{1}{2} \boldsymbol{\bar e}_t^T \bar E_t^{-1} \boldsymbol{\bar e}_t +
+ \frac{1}{2} \boldsymbol{\bar c}_t^T \left( \bar S_t + Q_t \right) \boldsymbol{\bar c}_t +
+ \boldsymbol{\bar c}_t^T \boldsymbol{\bar s}_t + \boldsymbol{\bar c}_t^T \boldsymbol{q}_t + \bar s_t + q_t \\
+\end{array}$$
+
+\newpage
+\section{Detailed work for a few transformations}
+
+$$\begin{array}{l}
+\begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+\begin{bmatrix} Q_{t} & P_{t}^T \\ P_{t} & R_{t} \end{bmatrix}
+\begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix} \\
+
+\begin{bmatrix} \boldsymbol{x}_1 & \boldsymbol{x}_2 & \boldsymbol{u}_1 & \boldsymbol{u}_2 \end{bmatrix}
+\left[\begin{array}{cc|cc}
+ Q_{t11} & Q_{t12} & P_{t11} & P_{t21} \\
+ Q_{t21} & Q_{t22} & P_{t12} & P_{t22} \\
+ \hline
+ P_{t11} & P_{t12} & R_{t11} & R_{t12} \\
+ P_{t21} & P_{t22} & R_{t21} & R_{t22} \\
+\end{array}\right]
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\begin{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} Q_{t11} \\ Q_{t21} \\ P_{t11} \\ P_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} Q_{t12} \\ Q_{t22} \\ P_{t12} \\ P_{t22} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t11} \\ P_{t12} \\ R_{t11} \\ R_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t21} \\ P_{t22} \\ R_{t12} \\ R_{t22} \end{bmatrix} &
+\end{bmatrix}
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\begin{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} Q_{t11} \\ Q_{t21} \end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} Q_{t12} \\ Q_{t22} \end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t11} \\ P_{t12} \end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t21} \\ P_{t22} \end{bmatrix}
+\end{bmatrix}
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} + \\ \quad
+\begin{bmatrix}
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t11} \\ P_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t12} \\ P_{t22} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} R_{t11} \\ R_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} R_{t12} \\ R_{t22} \end{bmatrix} &
+\end{bmatrix}
+\begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \\ \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} Q_{t11} \\ Q_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} Q_{t12} \\ Q_{t22} \end{bmatrix}\end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} +
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t11} \\ P_{t12} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t21} \\ P_{t22} \end{bmatrix}\end{bmatrix}
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} + \\ \quad
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t11} \\ P_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} P_{t12} \\ P_{t22} \end{bmatrix}\end{bmatrix}
+ \begin{bmatrix} \boldsymbol{x}_1 \\ \boldsymbol{x}_2 \end{bmatrix} +
+\begin{bmatrix} \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} R_{t11} \\ R_{t21} \end{bmatrix} &
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix} \cdot
+ \begin{bmatrix} R_{t12} \\ R_{t22} \end{bmatrix}\end{bmatrix}
+ \begin{bmatrix} \boldsymbol{u}_1 \\ \boldsymbol{u}_2 \end{bmatrix}
+\\
+\boldsymbol{x}^T Q_t \boldsymbol{x} + \boldsymbol{u}^T P_t \boldsymbol{x} + \boldsymbol{x}^T P_t^T \boldsymbol{u} + \boldsymbol{u}^T R_t \boldsymbol{u}
+\end{array}$$
+\\ \\
+$$\begin{array}{l}
+\begin{bmatrix} \boldsymbol{x} \\ \boldsymbol{u} \end{bmatrix}^T
+\begin{bmatrix} \boldsymbol{q}_{t} \\ \boldsymbol{r}_{t} \end{bmatrix}
+\\
+\begin{bmatrix} \boldsymbol{x}_1 & \boldsymbol{x}_2 & \boldsymbol{u}_1 & \boldsymbol{u}_2 \end{bmatrix}
+\begin{bmatrix} \boldsymbol{q}_{t1} \\ \boldsymbol{q}_{t2} \\ \boldsymbol{r}_{t1} \\ \boldsymbol{r}_{t1} \end{bmatrix}
+\\
+\boldsymbol{x}^T \boldsymbol{q}_t + \boldsymbol{u}^T \boldsymbol{r}_t
+\end{array}$$
+
+\end{document}
diff --git a/y2014/control_loops/python/extended_lqr_derivation.py b/y2014/control_loops/python/extended_lqr_derivation.py
new file mode 100755
index 0000000..248c6fc
--- /dev/null
+++ b/y2014/control_loops/python/extended_lqr_derivation.py
@@ -0,0 +1,410 @@
+#!/usr/bin/python2
+
+# This file checks our math in extended_lqr.tex.
+
+from __future__ import print_function
+from __future__ import division
+
+import sys
+import random
+
+import sympy
+
+'''
+* `x_t1` means `x_{t + 1}`. Using `'x_t + 1'` as the symbol name makes the non-
+ latex output really confusing, so not doing that.
+* `xb` means `\\boldsymbol{x}`. Written as `'xbold'` in the symbol name because
+ that's what sympy.latex recognizes.
+* `xb_tb` means `\\boldsymbol{\\bar x}_t. Written as `'xboldbar'` in the symbol
+ name so sympy.latex recognizes it.
+'''
+
+# sympy.latex
+
+# n in the 2013 paper
+number_of_states = sympy.Symbol('states', integer=True)
+# m in the 2013 paper
+number_of_inputs = sympy.Symbol('inputs', integer=True)
+number_of_outputs = sympy.Symbol('outputs', integer=True)
+
+DIMENSIONS = set([number_of_states, number_of_inputs, number_of_outputs])
+
+A_t = sympy.MatrixSymbol('A_t', number_of_states, number_of_states)
+B_t = sympy.MatrixSymbol('B_t', number_of_states, number_of_inputs)
+cb_t = sympy.MatrixSymbol('cbold_t', number_of_states, 1)
+A_tb = sympy.MatrixSymbol('Abar_t', number_of_states, number_of_states)
+B_tb = sympy.MatrixSymbol('Bbar_t', number_of_states, number_of_inputs)
+cb_tb = sympy.MatrixSymbol('cboldbar_t', number_of_states, 1)
+
+Q_t = sympy.MatrixSymbol('Q_t', number_of_states, number_of_states)
+P_t = sympy.MatrixSymbol('P_t', number_of_inputs, number_of_states)
+R_t = sympy.MatrixSymbol('R_t', number_of_inputs, number_of_inputs)
+qb_t = sympy.MatrixSymbol('qbold_t', number_of_states, 1)
+rb_t = sympy.MatrixSymbol('rbold_t', number_of_inputs, 1)
+q_t = sympy.MatrixSymbol('q_t', 1, 1)
+
+S_t1 = sympy.MatrixSymbol('S_t1', number_of_states, number_of_states)
+sb_t1 = sympy.MatrixSymbol('sbold_t1', number_of_states, 1)
+s_t1 = sympy.MatrixSymbol('s_t1', 1, 1)
+S_tb = sympy.MatrixSymbol('Sbar_t', number_of_states, number_of_states)
+sb_tb = sympy.MatrixSymbol('sboldbar_t', number_of_states, 1)
+s_tb = sympy.MatrixSymbol('sbar_t', 1, 1)
+
+xb_t = sympy.MatrixSymbol('xbold_t', number_of_states, 1)
+ub_t = sympy.MatrixSymbol('ubold_t', number_of_inputs, 1)
+xb_t1 = sympy.MatrixSymbol('xbold_t1', number_of_states, 1)
+ub_t1 = sympy.MatrixSymbol('ubold_t1', number_of_inputs, 1)
+
+half = sympy.Integer(1) / sympy.Integer(2)
+xb = sympy.MatrixSymbol('xbold', number_of_states, 1)
+ub = sympy.MatrixSymbol('ubold', number_of_inputs, 1)
+
+CONSTANTS = set([
+ A_t, B_t, cb_t,
+ S_t1, sb_t1, s_t1,
+ A_tb, B_tb, cb_tb,
+ S_tb, sb_tb, s_tb,
+ P_t, Q_t, R_t, qb_t, rb_t, q_t,
+ ])
+
+SYMMETRIC_CONSTANTS = set([
+ S_t1, S_tb,
+ Q_t, R_t,
+ ])
+
+def verify_equivalent(a, b, inverses={}):
+ def get_matrices(m):
+ matrices = m.atoms(sympy.MatrixSymbol)
+ new_matrices = set()
+ for matrix in matrices:
+ if matrix in inverses:
+ new_matrices.update(inverses[matrix].atoms(sympy.MatrixSymbol))
+ matrices.update(new_matrices)
+ a_matrices, b_matrices = get_matrices(a), get_matrices(b)
+ if a_matrices != b_matrices:
+ raise RuntimeError('matrices different: %s vs %s' % (a_matrices,
+ b_matrices))
+ a_symbols, b_symbols = a.atoms(sympy.Symbol), b.atoms(sympy.Symbol)
+ if a_symbols != b_symbols:
+ raise RuntimeError('symbols different: %s vs %s' % (a_symbols, b_symbols))
+ if not a_symbols < DIMENSIONS:
+ raise RuntimeError('not sure what to do with %s' % (a_symbols - DIMENSIONS))
+
+ if a.shape != b.shape:
+ raise RuntimeError('Different shapes: %s and %s' % (a.shape, b.shape))
+
+ for _ in range(10):
+ subs_symbols = {s: random.randint(1, 5) for s in a_symbols}
+ for _ in range(10):
+ diff = a - b
+ subs_matrices = {}
+ def get_replacement(*args):
+ try:
+ m = sympy.MatrixSymbol(*args)
+ if m not in subs_matrices:
+ if m in inverses:
+ i = inverses[m].replace(sympy.MatrixSymbol, get_replacement, simultaneous=False)
+ i_evaled = sympy.ImmutableMatrix(i.rows, i.cols,
+ lambda x,y: i[x, y].evalf())
+ subs_matrices[m] = i_evaled.I
+ else:
+ rows = m.rows.subs(subs_symbols)
+ cols = m.cols.subs(subs_symbols)
+ new_m = sympy.ImmutableMatrix(rows, cols,
+ lambda i,j: random.uniform(-5, 5))
+ if m in SYMMETRIC_CONSTANTS:
+ if rows != cols:
+ raise RuntimeError('Non-square symmetric matrix %s' % m)
+ def calculate_cell(i, j):
+ if i > j:
+ return new_m[i, j]
+ else:
+ return new_m[j, i]
+ new_m = sympy.ImmutableMatrix(rows, cols, calculate_cell)
+ subs_matrices[m] = new_m
+ return subs_matrices[m]
+ except AttributeError as e:
+ # Stupid sympy silently eats AttributeErrors and treats them as
+ # "no replacement"...
+ raise RuntimeError(e)
+ # subs fails when it tries doing matrix multiplies between fixed-size ones
+ # and the rest of the equation which still has the symbolic-sized ones.
+ # subs(simultaneous=True) wants to put dummies in for everything first,
+ # and Dummy().transpose() is broken.
+ # replace() has the same issue as subs with simultaneous being True.
+ # lambdify() has no idea what to do with the transposes if you replace all
+ # the matrices with ones of random sizes full of dummies.
+ diff = diff.replace(sympy.MatrixSymbol, get_replacement,
+ simultaneous=False)
+ for row in range(diff.rows):
+ for col in range(diff.cols):
+ result = diff[row, col].evalf()
+ if abs(result) > 1e-7:
+ raise RuntimeError('difference at (%s, %s) is %s' % (row, col,
+ result))
+
+def verify_arguments(f, *args):
+ matrix_atoms = f.atoms(sympy.MatrixSymbol) - CONSTANTS
+ if matrix_atoms != set(args):
+ print('Arguments expected to be %s, but are %s, in:\n%s' % (
+ sorted(args), sorted(list(matrix_atoms)), f), file=sys.stderr)
+ raise RuntimeError
+
+def make_c_t():
+ x_and_u = sympy.BlockMatrix(((xb,), (ub,)))
+ c_t = (half * x_and_u.transpose() *
+ sympy.BlockMatrix(((Q_t, P_t.T), (P_t, R_t))) * x_and_u +
+ x_and_u.transpose() * sympy.BlockMatrix(((qb_t,), (rb_t,))) +
+ q_t)
+ verify_arguments(c_t, xb, ub)
+ return c_t
+
+def check_backwards_cost():
+ g_t = A_t * xb_t + B_t * ub_t + cb_t
+ verify_arguments(g_t, xb_t, ub_t)
+ v_t1 = half * xb.transpose() * S_t1 * xb + xb.transpose() * sb_t1 + s_t1
+ verify_arguments(v_t1, xb)
+ v_t = (v_t1.subs(xb, g_t) + make_c_t()).subs({xb_t: xb, ub_t: ub})
+ verify_arguments(v_t, xb, ub)
+
+ v_t_for_cost = (
+ half * (
+ xb.transpose() * (A_t.transpose() * S_t1 * A_t + Q_t) * xb +
+ ub.transpose() * (B_t.transpose() * S_t1 * A_t + P_t) * xb +
+ xb.transpose() * (A_t.transpose() * S_t1 * B_t + P_t.T) * ub +
+ ub.transpose() * (B_t.transpose() * S_t1 * B_t + R_t) * ub) +
+ xb.transpose() * (A_t.transpose() * sb_t1 + qb_t) +
+ ub.transpose() * (B_t.transpose() * sb_t1 + rb_t) +
+ cb_t.transpose() * sb_t1 +
+ s_t1 + q_t +
+ half * (cb_t.transpose() * S_t1 * cb_t +
+ xb.transpose() * A_t.transpose() * S_t1 * cb_t +
+ ub.transpose() * B_t.transpose() * S_t1 * cb_t +
+ cb_t.transpose() * S_t1 * B_t * ub +
+ cb_t.transpose() * S_t1 * A_t * xb))
+ verify_equivalent(v_t, v_t_for_cost)
+
+ v_t_now = (
+ half * (xb.T * (A_t.T * S_t1 * A_t + Q_t) * xb +
+ ub.T * (B_t.T * S_t1 * A_t + P_t) * xb +
+ xb.T * (A_t.T * S_t1 * B_t + P_t.T) * ub +
+ ub.T * (B_t.T * S_t1 * B_t + R_t) * ub) +
+ xb.T * (A_t.T * sb_t1 + qb_t) +
+ ub.T * (B_t.T * sb_t1 + rb_t) +
+ cb_t.T * sb_t1 + s_t1 + q_t +
+ half * (cb_t.T * S_t1 * cb_t +
+ xb.T * A_t.T * S_t1 * cb_t +
+ ub.T * B_t.T * S_t1 * cb_t +
+ cb_t.T * S_t1 * B_t * ub +
+ cb_t.T * S_t1 * A_t * xb))
+
+ v_t_now = (
+ half * (xb.T * (A_t.T * S_t1 * A_t + Q_t) * xb +
+ ub.T * (B_t.T * S_t1 * A_t + P_t) * xb +
+ xb.T * (A_t.T * S_t1 * B_t + P_t.T) * ub +
+ ub.T * (B_t.T * S_t1 * B_t + R_t) * ub) +
+ xb.T * (A_t.T * sb_t1 + qb_t + half * A_t.T * S_t1 * cb_t) +
+ ub.T * (B_t.T * sb_t1 + rb_t + half * B_t.T * S_t1 * cb_t) +
+ half * cb_t.T * S_t1 * (A_t * xb + B_t * ub + cb_t) +
+ cb_t.T * sb_t1 + s_t1 + q_t)
+
+ v_t_now = (
+ half * (xb.T * (A_t.T * S_t1 * A_t + Q_t) * xb +
+ ub.T * (B_t.T * S_t1 * A_t + P_t) * xb +
+ xb.T * (A_t.T * S_t1 * B_t + P_t.T) * ub +
+ ub.T * (B_t.T * S_t1 * B_t + R_t) * ub) +
+ xb.T * (A_t.T * sb_t1 + qb_t + A_t.T * S_t1 * cb_t) +
+ ub.T * (B_t.T * sb_t1 + rb_t + B_t.T * S_t1 * cb_t) +
+ half * cb_t.T * S_t1 * cb_t +
+ cb_t.T * sb_t1 + s_t1 + q_t)
+
+ C_t = B_t.T * S_t1 * A_t + P_t
+ E_t = B_t.T * S_t1 * B_t + R_t
+ E_t_I = sympy.MatrixSymbol('E_t^-1', E_t.cols, E_t.rows)
+ L_t = -E_t_I * C_t
+ eb_t = B_t.T * S_t1 * cb_t + B_t.T * sb_t1 + rb_t
+ lb_t = -E_t_I * eb_t
+ D_t = A_t.T * S_t1 * A_t + Q_t
+ db_t = A_t.T * S_t1 * cb_t + A_t.T * sb_t1 + qb_t
+
+ v_t_now = (
+ half * (xb.T * D_t * xb + ub.T * C_t * xb +
+ xb.T * C_t.T * ub + ub.T * E_t * ub) +
+ xb.T * db_t + ub.T * eb_t +
+ half * cb_t.T * S_t1 * cb_t +
+ cb_t.T * sb_t1 + s_t1 + q_t)
+
+ v_t_final = (
+ half * xb.T * (D_t + L_t.T * C_t + C_t.T * L_t + L_t.T * E_t * L_t) * xb +
+ xb.T * (C_t.T * lb_t + L_t.T * E_t * lb_t + db_t + L_t.T * eb_t) +
+ half * lb_t.T * E_t * lb_t +
+ lb_t.T * eb_t +
+ cb_t.T * sb_t1 + s_t1 + q_t + half * cb_t.T * S_t1 * cb_t
+ )
+ verify_arguments(v_t_final, xb, E_t_I)
+ verify_equivalent(v_t.subs(ub, L_t * xb + lb_t), v_t_final, {E_t_I: E_t})
+
+ def v_t_from_s(this_S_t, this_sb_t, this_s_t):
+ return half * xb.T * this_S_t * xb + xb.T * this_sb_t + this_s_t
+
+ S_t_new_first = D_t + L_t.T * C_t + C_t.T * L_t + L_t.T * E_t * L_t
+ sb_t_new_first = db_t - C_t.T * E_t_I * eb_t
+ s_t_new_first = (half * lb_t.T * E_t * lb_t +
+ lb_t.T * eb_t +
+ cb_t.T * sb_t1 +
+ s_t1 + q_t +
+ half * cb_t.T * S_t1 * cb_t)
+ verify_equivalent(v_t_from_s(S_t_new_first, sb_t_new_first, s_t_new_first),
+ v_t_final, {E_t_I: E_t})
+
+ S_t_new_end = D_t - C_t.T * E_t_I * C_t
+ sb_t_new_end = db_t - C_t.T * E_t_I * eb_t
+ s_t_new_end = (q_t - half * eb_t.T * E_t_I * eb_t +
+ half * cb_t.T * S_t1 * cb_t + cb_t.T * sb_t1 + s_t1)
+ verify_equivalent(v_t_from_s(S_t_new_end, sb_t_new_end, s_t_new_end),
+ v_t_final, {E_t_I: E_t})
+
+def check_forwards_cost():
+ v_tb = half * xb.T * S_tb * xb + xb.T * sb_tb + s_tb
+ verify_arguments(v_tb, xb)
+ g_tb = A_tb * xb_t1 + B_tb * ub + cb_tb
+ verify_arguments(g_tb, xb_t1, ub)
+ c_t1b = make_c_t().subs(xb, g_tb)
+ verify_arguments(c_t1b, xb_t1, ub)
+ v_t1b = v_tb.subs(xb, g_tb) + c_t1b
+ verify_arguments(v_t1b, xb_t1, ub)
+
+ v_t1b_now = (
+ half * g_tb.T * S_tb * g_tb +
+ g_tb.T * sb_tb + s_tb +
+ half * (g_tb.T * Q_t * g_tb +
+ ub.T * P_t * g_tb +
+ g_tb.T * P_t.T * ub +
+ ub.T * R_t * ub) +
+ g_tb.T * qb_t + ub.T * rb_t + q_t)
+
+ v_t1b_for_cost = (
+ half * (xb_t1.T * A_tb.T * (S_tb + Q_t) * A_tb * xb_t1 +
+ xb_t1.T * A_tb.T * (S_tb + Q_t) * B_tb * ub +
+ xb_t1.T * A_tb.T * (S_tb + Q_t) * cb_tb +
+ ub.T * B_tb.T * (S_tb + Q_t) * A_tb * xb_t1 +
+ ub.T * B_tb.T * (S_tb + Q_t) * B_tb * ub +
+ ub.T * B_tb.T * (S_tb + Q_t) * cb_tb +
+ cb_tb.T * (S_tb + Q_t) * A_tb * xb_t1 +
+ cb_tb.T * (S_tb + Q_t) * B_tb * ub +
+ cb_tb.T * (S_tb + Q_t) * cb_tb) +
+ xb_t1.T * A_tb.T * sb_tb +
+ ub.T * B_tb.T * sb_tb +
+ cb_tb.T * sb_tb +
+ s_tb +
+ half * (ub.T * P_t * A_tb * xb_t1 +
+ ub.T * P_t * B_tb * ub +
+ ub.T * P_t * cb_tb) +
+ half * (xb_t1.T * A_tb.T * P_t.T * ub +
+ ub.T * B_tb.T * P_t.T * ub +
+ cb_tb.T * P_t.T * ub) +
+ half * ub.T * R_t * ub +
+ xb_t1.T * A_tb.T * qb_t + ub.T * B_tb.T * qb_t + cb_tb.T * qb_t +
+ ub.T * rb_t + q_t)
+ verify_equivalent(v_t1b, v_t1b_for_cost)
+
+ S_and_Q = S_tb + Q_t
+
+ v_t1b_now = (
+ half * (xb_t1.T * A_tb.T * S_and_Q * A_tb * xb_t1 +
+ xb_t1.T * A_tb.T * S_and_Q * B_tb * ub +
+ xb_t1.T * A_tb.T * S_and_Q * cb_tb +
+ ub.T * B_tb.T * S_and_Q * A_tb * xb_t1 +
+ ub.T * B_tb.T * S_and_Q * B_tb * ub +
+ ub.T * B_tb.T * S_and_Q * cb_tb +
+ cb_tb.T * S_and_Q * A_tb * xb_t1 +
+ cb_tb.T * S_and_Q * B_tb * ub +
+ cb_tb.T * S_and_Q * cb_tb) +
+ xb_t1.T * A_tb.T * sb_tb +
+ ub.T * B_tb.T * sb_tb +
+ cb_tb.T * sb_tb +
+ s_tb +
+ half * (ub.T * P_t * A_tb * xb_t1 +
+ ub.T * P_t * B_tb * ub +
+ ub.T * P_t * cb_tb) +
+ half * (xb_t1.T * A_tb.T * P_t.T * ub +
+ ub.T * B_tb.T * P_t.T * ub +
+ cb_tb.T * P_t.T * ub) +
+ half * ub.T * R_t * ub +
+ xb_t1.T * A_tb.T * qb_t +
+ ub.T * B_tb.T * qb_t +
+ cb_tb.T * qb_t +
+ ub.T * rb_t +
+ q_t)
+
+ C_tb = B_tb.T * S_and_Q * A_tb + P_t * A_tb
+ E_tb = B_tb.T * S_and_Q * B_tb + B_tb.T * P_t.T + P_t * B_tb + R_t
+ E_tb_I = sympy.MatrixSymbol('Ebar_t^-1', E_tb.cols, E_tb.rows)
+ L_tb = -E_tb_I * C_tb
+ eb_tb = B_tb.T * S_and_Q * cb_tb + B_tb.T * sb_tb + P_t * cb_tb + B_tb.T * qb_t + rb_t
+ lb_tb = -E_tb_I * eb_tb
+ D_tb = A_tb.T * S_and_Q * A_tb
+ db_tb = A_tb.T * S_and_Q * cb_tb + A_tb.T * (sb_tb + qb_t)
+
+ v_t1b_now = (
+ half * (xb_t1.T * D_tb * xb_t1 +
+ xb_t1.T * C_tb.T * ub +
+ ub.T * C_tb * xb_t1 +
+ ub.T * E_tb * ub) +
+ xb_t1.T * db_tb +
+ ub.T * eb_tb +
+ half * cb_tb.T * S_and_Q * cb_tb +
+ cb_tb.T * sb_tb +
+ cb_tb.T * qb_t +
+ s_tb + q_t)
+
+ v_t1b_final = (
+ half * xb_t1.T * (D_tb - C_tb.T * E_tb_I * C_tb) * xb_t1 +
+ xb_t1.T * (db_tb - C_tb.T * E_tb_I * eb_tb) +
+ -half * eb_tb.T * E_tb_I * eb_tb +
+ half * cb_tb.T * S_and_Q * cb_tb +
+ cb_tb.T * sb_tb +
+ cb_tb.T * qb_t +
+ s_tb + q_t)
+ verify_arguments(v_t1b_final, xb_t1, E_tb_I)
+ verify_equivalent(v_t1b.subs(ub, -E_tb_I * C_tb * xb_t1 - E_tb_I * eb_tb),
+ v_t1b_final, {E_tb_I: E_tb})
+
+def check_forwards_u():
+ S_and_Q = S_tb + Q_t
+
+ diff_start = (
+ half * (xb_t1.T * A_tb.T * S_and_Q * B_tb +
+ (B_tb.T * S_and_Q * A_tb * xb_t1).T +
+ 2 * ub.T * B_tb.T * S_and_Q * B_tb +
+ (B_tb.T * S_and_Q * cb_tb).T +
+ cb_tb.T * S_and_Q * B_tb) +
+ sb_tb.T * B_tb +
+ half * (P_t * A_tb * xb_t1).T +
+ half * xb_t1.T * A_tb.T * P_t.T +
+ half * ub.T * (P_t * B_tb + B_tb.T * P_t.T) +
+ half * ub.T * (B_tb.T * P_t.T + P_t * B_tb) +
+ half * (P_t * cb_tb).T +
+ half * cb_tb.T * P_t.T +
+ ub.T * R_t +
+ (B_tb.T * qb_t).T + rb_t.T)
+ verify_arguments(diff_start, xb_t1, ub)
+
+ diff_end = (
+ xb_t1.T * (A_tb.T * S_and_Q * B_tb + A_tb.T * P_t.T) +
+ ub.T * (B_tb.T * S_and_Q * B_tb + B_tb.T * P_t.T + P_t * B_tb + R_t) +
+ cb_tb.T * S_and_Q * B_tb +
+ sb_tb.T * B_tb +
+ cb_tb.T * P_t.T +
+ qb_t.T * B_tb +
+ rb_t.T)
+ verify_equivalent(diff_start, diff_end)
+
+def main():
+ sympy.init_printing(use_unicode=True)
+ check_backwards_cost()
+ check_forwards_cost()
+ check_forwards_u()
+
+if __name__ == '__main__':
+ main()
diff --git a/y2014/wpilib/wpilib_interface.cc b/y2014/wpilib/wpilib_interface.cc
index 5195ab6..a53d54b 100644
--- a/y2014/wpilib/wpilib_interface.cc
+++ b/y2014/wpilib/wpilib_interface.cc
@@ -4,6 +4,7 @@
#include <inttypes.h>
#include <thread>
+#include <chrono>
#include <mutex>
#include <functional>
@@ -260,8 +261,8 @@
bottom_reader_.Start();
dma_synchronizer_->Start();
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(4));
::aos::SetCurrentThreadRealtimePriority(40);
while (run_) {
@@ -504,8 +505,8 @@
::aos::SetCurrentThreadName("Solenoids");
::aos::SetCurrentThreadRealtimePriority(27);
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(1));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(1));
while (run_) {
{
diff --git a/y2014_bot3/BUILD b/y2014_bot3/BUILD
index 3ec0bb5..1c07423 100644
--- a/y2014_bot3/BUILD
+++ b/y2014_bot3/BUILD
@@ -16,21 +16,22 @@
'//frc971/queues:gyro',
'//y2014_bot3/autonomous:auto_queue',
'//y2014_bot3/control_loops/rollers:rollers_queue',
- '//y2014_bot3/control_loops/drivetrain:drivetrain_queue',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
],
)
aos_downloader(
- name = 'download',
+ name = 'download_stripped',
start_srcs = [
- '//aos:prime_start_binaries',
- '//y2014_bot3/control_loops/drivetrain:drivetrain',
- '//y2014_bot3/control_loops/rollers:rollers',
- '//y2014_bot3/autonomous:auto',
- ':joystick_reader',
- '//y2014_bot3/wpilib:wpilib_interface',
+ ':joystick_reader.stripped',
+ '//aos:prime_start_binaries_stripped',
+ '//y2014_bot3/autonomous:auto.stripped',
+ '//y2014_bot3/control_loops/drivetrain:drivetrain.stripped',
+ '//y2014_bot3/control_loops/rollers:rollers.stripped',
+ '//y2014_bot3/wpilib:wpilib_interface.stripped',
+
],
srcs = [
- '//aos:prime_binaries',
+ '//aos:prime_binaries_stripped',
],
)
diff --git a/y2014_bot3/autonomous/BUILD b/y2014_bot3/autonomous/BUILD
index f90ce74..bfd7f34 100644
--- a/y2014_bot3/autonomous/BUILD
+++ b/y2014_bot3/autonomous/BUILD
@@ -20,8 +20,7 @@
deps = [
':auto_queue',
'//aos/common/controls:control_loop',
- '//y2014_bot3/control_loops/drivetrain:drivetrain_queue',
- '//y2014_bot3/control_loops/drivetrain:drivetrain_lib',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
'//y2014_bot3/control_loops/rollers:rollers_queue',
'//aos/common:time',
'//aos/common/util:phased_loop',
diff --git a/y2014_bot3/autonomous/auto.cc b/y2014_bot3/autonomous/auto.cc
index 3724cbe..80f2b09 100644
--- a/y2014_bot3/autonomous/auto.cc
+++ b/y2014_bot3/autonomous/auto.cc
@@ -8,13 +8,12 @@
#include "aos/common/logging/logging.h"
#include "aos/common/logging/queue_logging.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
#include "y2014_bot3/autonomous/auto.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
#include "y2014_bot3/control_loops/rollers/rollers.q.h"
using ::aos::time::Time;
-using ::y2014_bot3::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain_queue;
using ::y2014_bot3::control_loops::rollers_queue;
namespace y2014_bot3 {
@@ -35,7 +34,7 @@
void ResetDrivetrain() {
LOG(INFO, "resetting the drivetrain\n");
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
+ ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
.control_loop_driving(false)
.steering(0.0)
.throttle(0.0)
@@ -47,11 +46,11 @@
}
void InitializeEncoders() {
- control_loops::drivetrain_queue.status.FetchAnother();
+ ::frc971::control_loops::drivetrain_queue.status.FetchAnother();
left_initial_position =
- control_loops::drivetrain_queue.status->estimated_left_position;
+ ::frc971::control_loops::drivetrain_queue.status->estimated_left_position;
right_initial_position =
- control_loops::drivetrain_queue.status->estimated_right_position;
+ ::frc971::control_loops::drivetrain_queue.status->estimated_right_position;
}
void HandleAuto() {
@@ -63,7 +62,7 @@
InitializeEncoders();
LOG(INFO, "Driving\n");
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
+ ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
.control_loop_driving(false)
.highgear(false)
.quickturn(false)
@@ -76,7 +75,7 @@
.Send();
time::SleepFor(time::Time::InSeconds(2.0));
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
+ ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
.control_loop_driving(false)
.highgear(false)
.quickturn(false)
diff --git a/y2014_bot3/control_loops/drivetrain/BUILD b/y2014_bot3/control_loops/drivetrain/BUILD
index 32afd4b..6bd7e33 100644
--- a/y2014_bot3/control_loops/drivetrain/BUILD
+++ b/y2014_bot3/control_loops/drivetrain/BUILD
@@ -2,45 +2,6 @@
load('/aos/build/queues', 'queue_library')
-cc_binary(
- name = 'replay_drivetrain',
- srcs = [
- 'replay_drivetrain.cc',
- ],
- deps = [
- ':drivetrain_queue',
- '//aos/common/controls:replay_control_loop',
- '//aos/linux_code:init',
- ],
-)
-
-queue_library(
- name = 'drivetrain_queue',
- srcs = [
- 'drivetrain.q',
- ],
- deps = [
- '//aos/common/controls:control_loop_queues',
- ],
-)
-
-cc_library(
- name = 'polydrivetrain_plants',
- srcs = [
- 'polydrivetrain_dog_motor_plant.cc',
- 'drivetrain_dog_motor_plant.cc',
- 'polydrivetrain_cim_plant.cc',
- ],
- hdrs = [
- 'polydrivetrain_dog_motor_plant.h',
- 'drivetrain_dog_motor_plant.h',
- 'polydrivetrain_cim_plant.h',
- ],
- deps = [
- '//frc971/control_loops:state_feedback_loop',
- ],
-)
-
genrule(
name = 'genrule_drivetrain',
visibility = ['//visibility:private'],
@@ -51,47 +12,55 @@
outs = [
'drivetrain_dog_motor_plant.h',
'drivetrain_dog_motor_plant.cc',
+ 'kalman_drivetrain_motor_plant.h',
+ 'kalman_drivetrain_motor_plant.cc',
+ ],
+)
+
+genrule(
+ name = 'genrule_polydrivetrain',
+ visibility = ['//visibility:private'],
+ cmd = '$(location //y2014_bot3/control_loops/python:polydrivetrain) $(OUTS)',
+ tools = [
+ '//y2014_bot3/control_loops/python:polydrivetrain',
+ ],
+ outs = [
+ 'polydrivetrain_dog_motor_plant.h',
+ 'polydrivetrain_dog_motor_plant.cc',
+ 'polydrivetrain_cim_plant.h',
+ 'polydrivetrain_cim_plant.cc',
],
)
cc_library(
- name = 'drivetrain_lib',
- hdrs = [
- 'drivetrain.h',
- ],
+ name = 'polydrivetrain_plants',
srcs = [
- 'drivetrain.cc',
+ 'polydrivetrain_dog_motor_plant.cc',
+ 'drivetrain_dog_motor_plant.cc',
+ 'kalman_drivetrain_motor_plant.cc',
+ ],
+ hdrs = [
+ 'polydrivetrain_dog_motor_plant.h',
+ 'drivetrain_dog_motor_plant.h',
+ 'kalman_drivetrain_motor_plant.h',
],
deps = [
- ':polydrivetrain_plants',
- ':drivetrain_queue',
- '//aos/common/controls:control_loop',
- '//aos/common/controls:polytope',
'//frc971/control_loops:state_feedback_loop',
- '//frc971/control_loops:coerce_goal',
- '//frc971/queues:gyro',
- '//aos/common/logging:queue_logging',
- '//aos/common/logging:matrix_logging',
- '//aos/common:math',
- '//aos/common/util:log_interval',
- '//frc971:shifter_hall_effect',
],
)
-cc_test(
- name = 'drivetrain_lib_test',
+cc_library(
+ name = 'drivetrain_base',
srcs = [
- 'drivetrain_lib_test.cc',
+ 'drivetrain_base.cc',
+ ],
+ hdrs = [
+ 'drivetrain_base.h',
],
deps = [
- '//aos/testing:googletest',
- ':drivetrain_queue',
- ':drivetrain_lib',
- '//aos/common/controls:control_loop_test',
- '//frc971/control_loops:state_feedback_loop',
- '//frc971/queues:gyro',
- '//aos/common:queues',
- '//aos/common/network:team_number',
+ ':polydrivetrain_plants',
+ '//frc971/control_loops/drivetrain:drivetrain_config',
+ '//frc971:shifter_hall_effect',
],
)
@@ -101,8 +70,8 @@
'drivetrain_main.cc',
],
deps = [
- ':drivetrain_lib',
- ':drivetrain_queue',
+ ':drivetrain_base',
'//aos/linux_code:init',
+ '//frc971/control_loops/drivetrain:drivetrain_lib',
],
)
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain.cc b/y2014_bot3/control_loops/drivetrain/drivetrain.cc
deleted file mode 100644
index 125dd24..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain.cc
+++ /dev/null
@@ -1,571 +0,0 @@
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
-
-#include <stdio.h>
-#include <sched.h>
-#include <cmath>
-#include <memory>
-#include "Eigen/Dense"
-
-#include "aos/common/logging/logging.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/commonmath.h"
-#include "aos/common/logging/queue_logging.h"
-#include "aos/common/logging/matrix_logging.h"
-
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/coerce_goal.h"
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/queues/gyro.q.h"
-#include "frc971/shifter_hall_effect.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-
-using ::frc971::sensors::gyro_reading;
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-class DrivetrainMotorsSS {
- public:
- class LimitedDrivetrainLoop : public StateFeedbackLoop<4, 2, 2> {
- public:
- LimitedDrivetrainLoop(StateFeedbackLoop<4, 2, 2> &&loop)
- : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
- U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0, -1, 0, 0, 1, 0, -1)
- .finished(),
- (Eigen::Matrix<double, 4, 1>() << 12.0, 12.0, 12.0, 12.0)
- .finished()) {
- ::aos::controls::HPolytope<0>::Init();
- T << 1, -1, 1, 1;
- T_inverse = T.inverse();
- }
-
- bool output_was_capped() const { return output_was_capped_; }
-
- private:
- virtual void CapU() {
- const Eigen::Matrix<double, 4, 1> error = R() - X_hat();
-
- if (::std::abs(U(0, 0)) > 12.0 || ::std::abs(U(1, 0)) > 12.0) {
- mutable_U() =
- U() * 12.0 / ::std::max(::std::abs(U(0, 0)), ::std::abs(U(1, 0)));
- LOG_MATRIX(DEBUG, "U is now", U());
- // TODO(Austin): Figure out why the polytope stuff wasn't working and
- // remove this hack.
- output_was_capped_ = true;
- return;
-
- LOG_MATRIX(DEBUG, "U at start", U());
- LOG_MATRIX(DEBUG, "R at start", R());
- LOG_MATRIX(DEBUG, "Xhat at start", X_hat());
-
- Eigen::Matrix<double, 2, 2> position_K;
- position_K << K(0, 0), K(0, 2), K(1, 0), K(1, 2);
- Eigen::Matrix<double, 2, 2> velocity_K;
- velocity_K << K(0, 1), K(0, 3), K(1, 1), K(1, 3);
-
- Eigen::Matrix<double, 2, 1> position_error;
- position_error << error(0, 0), error(2, 0);
- const auto drive_error = T_inverse * position_error;
- Eigen::Matrix<double, 2, 1> velocity_error;
- velocity_error << error(1, 0), error(3, 0);
- LOG_MATRIX(DEBUG, "error", error);
-
- const auto &poly = U_Poly_;
- const Eigen::Matrix<double, 4, 2> pos_poly_H =
- poly.H() * position_K * T;
- const Eigen::Matrix<double, 4, 1> pos_poly_k =
- poly.k() - poly.H() * velocity_K * velocity_error;
- const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
-
- Eigen::Matrix<double, 2, 1> adjusted_pos_error;
- {
- const auto &P = drive_error;
-
- Eigen::Matrix<double, 1, 2> L45;
- L45 << ::aos::sign(P(1, 0)), -::aos::sign(P(0, 0));
- const double w45 = 0;
-
- Eigen::Matrix<double, 1, 2> LH;
- if (::std::abs(P(0, 0)) > ::std::abs(P(1, 0))) {
- LH << 0, 1;
- } else {
- LH << 1, 0;
- }
- const double wh = LH.dot(P);
-
- Eigen::Matrix<double, 2, 2> standard;
- standard << L45, LH;
- Eigen::Matrix<double, 2, 1> W;
- W << w45, wh;
- const Eigen::Matrix<double, 2, 1> intersection =
- standard.inverse() * W;
-
- bool is_inside_h;
- const auto adjusted_pos_error_h = frc971::control_loops::DoCoerceGoal(
- pos_poly, LH, wh, drive_error, &is_inside_h);
- const auto adjusted_pos_error_45 =
- frc971::control_loops::DoCoerceGoal(pos_poly, L45, w45,
- intersection, nullptr);
- if (pos_poly.IsInside(intersection)) {
- adjusted_pos_error = adjusted_pos_error_h;
- } else {
- if (is_inside_h) {
- if (adjusted_pos_error_h.norm() > adjusted_pos_error_45.norm()) {
- adjusted_pos_error = adjusted_pos_error_h;
- } else {
- adjusted_pos_error = adjusted_pos_error_45;
- }
- } else {
- adjusted_pos_error = adjusted_pos_error_45;
- }
- }
- }
-
- LOG_MATRIX(DEBUG, "adjusted_pos_error", adjusted_pos_error);
- mutable_U() =
- velocity_K * velocity_error + position_K * T * adjusted_pos_error;
- LOG_MATRIX(DEBUG, "U is now", U());
- } else {
- output_was_capped_ = false;
- }
- }
-
- const ::aos::controls::HPolytope<2> U_Poly_;
- Eigen::Matrix<double, 2, 2> T, T_inverse;
- bool output_was_capped_ = false;
- };
-
- DrivetrainMotorsSS()
- : loop_(new LimitedDrivetrainLoop(
- ::y2014_bot3::control_loops::drivetrain::MakeDrivetrainLoop())),
- filtered_offset_(0.0),
- gyro_(0.0),
- left_goal_(0.0),
- right_goal_(0.0),
- raw_left_(0.0),
- raw_right_(0.0) {
- // Low gear on both.
- loop_->set_controller_index(0);
- }
-
- void SetGoal(double left, double left_velocity, double right,
- double right_velocity) {
- left_goal_ = left;
- right_goal_ = right;
- loop_->mutable_R() << left, left_velocity, right, right_velocity;
- }
- void SetRawPosition(double left, double right) {
- raw_right_ = right;
- raw_left_ = left;
- Eigen::Matrix<double, 2, 1> Y;
- Y << left + filtered_offset_, right - filtered_offset_;
- loop_->Correct(Y);
- }
- void SetPosition(double left, double right, double gyro) {
- // Decay the offset quickly because this gyro is great.
- const double offset = (right - left - gyro * kDrivetrainTurnWidth) / 2.0;
- filtered_offset_ = 0.25 * offset + 0.75 * filtered_offset_;
- gyro_ = gyro;
- SetRawPosition(left, right);
- }
-
- void SetExternalMotors(double left_voltage, double right_voltage) {
- loop_->mutable_U() << left_voltage, right_voltage;
- }
-
- void Update(bool stop_motors, bool enable_control_loop) {
- if (enable_control_loop) {
- loop_->Update(stop_motors);
- } else {
- if (stop_motors) {
- loop_->mutable_U().setZero();
- loop_->mutable_U_uncapped().setZero();
- }
- loop_->UpdateObserver(loop_->U());
- }
- ::Eigen::Matrix<double, 4, 1> E = loop_->R() - loop_->X_hat();
- LOG_MATRIX(DEBUG, "E", E);
- }
-
- double GetEstimatedRobotSpeed() const {
- // lets just call the average of left and right velocities close enough
- return (loop_->X_hat(1, 0) + loop_->X_hat(3, 0)) / 2;
- }
-
- double GetEstimatedLeftEncoder() const { return loop_->X_hat(0, 0); }
-
- double GetEstimatedRightEncoder() const { return loop_->X_hat(2, 0); }
-
- bool OutputWasCapped() const { return loop_->output_was_capped(); }
-
- void SendMotors(DrivetrainQueue::Output *output) const {
- if (output) {
- output->left_voltage = loop_->U(0, 0);
- output->right_voltage = loop_->U(1, 0);
- output->left_high = false;
- output->right_high = false;
- }
- }
-
- const LimitedDrivetrainLoop &loop() const { return *loop_; }
-
- private:
- ::std::unique_ptr<LimitedDrivetrainLoop> loop_;
-
- double filtered_offset_;
- double gyro_;
- double left_goal_;
- double right_goal_;
- double raw_left_;
- double raw_right_;
-};
-
-class PolyDrivetrain {
- public:
- enum Gear { HIGH, LOW };
- // Stall Torque in N m
- static constexpr double kStallTorque = 2.42;
- // Stall Current in Amps
- static constexpr double kStallCurrent = 133.0;
- // Free Speed in RPM. Used number from last year.
- static constexpr double kFreeSpeed = 4650.0;
- // Free Current in Amps
- static constexpr double kFreeCurrent = 2.7;
- // Moment of inertia of the drivetrain in kg m^2
- // Just borrowed from last year.
- static constexpr double J = 10;
- // Mass of the robot, in kg.
- static constexpr double m = 68;
- // Radius of the robot, in meters (from last year).
- static constexpr double rb = 0.66675 / 2.0;
- static constexpr double kWheelRadius = 0.04445;
- // Resistance of the motor, divided by the number of motors.
- static constexpr double kR =
- (12.0 / kStallCurrent / 4 + 0.03) / (0.93 * 0.93);
- // Motor velocity constant
- static constexpr double Kv =
- ((kFreeSpeed / 60.0 * 2.0 * M_PI) / (12.0 - kR * kFreeCurrent));
- // Torque constant
- static constexpr double Kt = kStallTorque / kStallCurrent;
-
- PolyDrivetrain()
- : U_Poly_((Eigen::Matrix<double, 4, 2>() << /*[[*/ 1, 0 /*]*/,
- /*[*/ -1, 0 /*]*/,
- /*[*/ 0, 1 /*]*/,
- /*[*/ 0, -1 /*]]*/).finished(),
- (Eigen::Matrix<double, 4, 1>() << /*[[*/ 12 /*]*/,
- /*[*/ 12 /*]*/,
- /*[*/ 12 /*]*/,
- /*[*/ 12 /*]]*/).finished()),
- loop_(new StateFeedbackLoop<2, 2, 2>(
- ::y2014_bot3::control_loops::MakeVelocityDrivetrainLoop())),
- ttrust_(1.1),
- wheel_(0.0),
- throttle_(0.0),
- quickturn_(false),
- stale_count_(0),
- position_time_delta_(0.01),
- left_gear_(LOW),
- right_gear_(LOW),
- counter_(0) {
- last_position_.Zero();
- position_.Zero();
- }
-
- static double MotorSpeed(bool high_gear, double velocity) {
- if (high_gear) {
- return velocity / kDrivetrainHighGearRatio / kWheelRadius;
- } else {
- return velocity / kDrivetrainLowGearRatio / kWheelRadius;
- }
- }
-
- void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
- const double kWheelNonLinearity = 0.5;
- // Apply a sin function that's scaled to make it feel better.
- const double angular_range = M_PI_2 * kWheelNonLinearity;
-
- quickturn_ = quickturn;
- wheel_ = sin(angular_range * wheel) / sin(angular_range);
- wheel_ = sin(angular_range * wheel_) / sin(angular_range);
- if (!quickturn_) {
- wheel_ *= 1.5;
- }
-
- static const double kThrottleDeadband = 0.05;
- if (::std::abs(throttle) < kThrottleDeadband) {
- throttle_ = 0;
- } else {
- throttle_ = copysign((::std::abs(throttle) - kThrottleDeadband) /
- (1.0 - kThrottleDeadband),
- throttle);
- }
-
- Gear requested_gear = highgear ? HIGH : LOW;
- left_gear_ = right_gear_ = requested_gear;
- }
-
- void SetPosition(const DrivetrainQueue::Position *position) {
- if (position == NULL) {
- ++stale_count_;
- } else {
- last_position_ = position_;
- position_ = *position;
- position_time_delta_ = (stale_count_ + 1) * 0.01;
- stale_count_ = 0;
- }
- }
-
- double FilterVelocity(double throttle) {
- const Eigen::Matrix<double, 2, 2> FF =
- loop_->B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
- constexpr int kHighGearController = 3;
- const Eigen::Matrix<double, 2, 2> FF_high =
- loop_->controller(kHighGearController).plant.B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() -
- loop_->controller(kHighGearController).plant.A());
-
- ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
- int min_FF_sum_index;
- const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
- const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
- const double high_min_FF_sum = FF_high.col(0).sum();
-
- const double adjusted_ff_voltage = ::aos::Clip(
- throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
- return (adjusted_ff_voltage +
- ttrust_ * min_K_sum * (loop_->X_hat(0, 0) + loop_->X_hat(1, 0)) /
- 2.0) /
- (ttrust_ * min_K_sum + min_FF_sum);
- }
-
- double MaxVelocity() {
- const Eigen::Matrix<double, 2, 2> FF =
- loop_->B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
- constexpr int kHighGearController = 3;
- const Eigen::Matrix<double, 2, 2> FF_high =
- loop_->controller(kHighGearController).plant.B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() -
- loop_->controller(kHighGearController).plant.A());
-
- ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
- int min_FF_sum_index;
- const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
- // const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
- const double high_min_FF_sum = FF_high.col(0).sum();
-
- const double adjusted_ff_voltage =
- ::aos::Clip(12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
- return adjusted_ff_voltage / min_FF_sum;
- }
-
- void Update() {
- // TODO(austin): Observer for the current velocity instead of difference
- // calculations.
- ++counter_;
-
- const double current_left_velocity =
- (position_.left_encoder - last_position_.left_encoder) /
- position_time_delta_;
- const double current_right_velocity =
- (position_.right_encoder - last_position_.right_encoder) /
- position_time_delta_;
- const double left_motor_speed = MotorSpeed(left_gear_ == HIGH,
- current_left_velocity);
- const double right_motor_speed = MotorSpeed(right_gear_ == HIGH,
- current_right_velocity);
-
- {
- CIMLogging logging;
-
- // Reset the CIM model to the current conditions to be ready for when we
- // shift.
- logging.left_in_gear = true;
- logging.left_motor_speed = left_motor_speed;
- logging.left_velocity = current_left_velocity;
-
- logging.right_in_gear = true;
- logging.right_motor_speed = right_motor_speed;
- logging.right_velocity = current_right_velocity;
-
- LOG_STRUCT(DEBUG, "currently", logging);
- }
-
- {
- // FF * X = U (steady state)
- const Eigen::Matrix<double, 2, 2> FF =
- loop_->B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
- // Invert the plant to figure out how the velocity filter would have to
- // work
- // out in order to filter out the forwards negative inertia.
- // This math assumes that the left and right power and velocity are
- // equals,
- // and that the plant is the same on the left and right.
- const double fvel = FilterVelocity(throttle_);
-
- const double sign_svel = wheel_ * ((fvel > 0.0) ? 1.0 : -1.0);
- double steering_velocity;
- if (quickturn_) {
- steering_velocity = wheel_ * MaxVelocity();
- } else {
- steering_velocity = ::std::abs(fvel) * wheel_;
- }
- const double left_velocity = fvel - steering_velocity;
- const double right_velocity = fvel + steering_velocity;
- LOG(DEBUG, "l=%f r=%f\n", left_velocity, right_velocity);
-
- // Integrate velocity to get the position.
- // This position is used to get integral control.
- loop_->mutable_R() << left_velocity, right_velocity;
-
- if (!quickturn_) {
- // K * R = w
- Eigen::Matrix<double, 1, 2> equality_k;
- equality_k << 1 + sign_svel, -(1 - sign_svel);
- const double equality_w = 0.0;
-
- // Construct a constraint on R by manipulating the constraint on U
- ::aos::controls::HPolytope<2> R_poly = ::aos::controls::HPolytope<2>(
- U_Poly_.H() * (loop_->K() + FF),
- U_Poly_.k() + U_Poly_.H() * loop_->K() * loop_->X_hat());
-
- // Limit R back inside the box.
- loop_->mutable_R() = frc971::control_loops::CoerceGoal(
- R_poly, equality_k, equality_w, loop_->R());
- }
-
- const Eigen::Matrix<double, 2, 1> FF_volts = FF * loop_->R();
- const Eigen::Matrix<double, 2, 1> U_ideal =
- loop_->K() * (loop_->R() - loop_->X_hat()) + FF_volts;
-
- for (int i = 0; i < 2; i++) {
- loop_->mutable_U()[i] = ::aos::Clip(U_ideal[i], -12, 12);
- }
-
- // TODO(austin): Model this better.
- // TODO(austin): Feedback?
- loop_->mutable_X_hat() =
- loop_->A() * loop_->X_hat() + loop_->B() * loop_->U();
- }
- }
-
- void SendMotors(DrivetrainQueue::Output *output) {
- if (output != NULL) {
- output->left_voltage = loop_->U(0, 0);
- output->right_voltage = loop_->U(1, 0);
- output->left_high = left_gear_ == HIGH;
- output->right_high = right_gear_ == HIGH;
- }
- }
-
- private:
- const ::aos::controls::HPolytope<2> U_Poly_;
-
- ::std::unique_ptr<StateFeedbackLoop<2, 2, 2>> loop_;
-
- const double ttrust_;
- double wheel_;
- double throttle_;
- bool quickturn_;
- int stale_count_;
- double position_time_delta_;
- Gear left_gear_;
- Gear right_gear_;
- DrivetrainQueue::Position last_position_;
- DrivetrainQueue::Position position_;
- int counter_;
-};
-
-constexpr double PolyDrivetrain::kStallTorque;
-constexpr double PolyDrivetrain::kStallCurrent;
-constexpr double PolyDrivetrain::kFreeSpeed;
-constexpr double PolyDrivetrain::kFreeCurrent;
-constexpr double PolyDrivetrain::J;
-constexpr double PolyDrivetrain::m;
-constexpr double PolyDrivetrain::rb;
-constexpr double PolyDrivetrain::kWheelRadius;
-constexpr double PolyDrivetrain::kR;
-constexpr double PolyDrivetrain::Kv;
-constexpr double PolyDrivetrain::Kt;
-
-void DrivetrainLoop::RunIteration(const DrivetrainQueue::Goal *goal,
- const DrivetrainQueue::Position *position,
- DrivetrainQueue::Output *output,
- DrivetrainQueue::Status *status) {
- // TODO(aschuh): These should be members of the class.
- static DrivetrainMotorsSS dt_closedloop;
- static PolyDrivetrain dt_openloop;
-
- bool bad_pos = false;
- if (position == nullptr) {
- LOG_INTERVAL(no_position_);
- bad_pos = true;
- }
- no_position_.Print();
-
- bool control_loop_driving = false;
- if (goal) {
- double wheel = goal->steering;
- double throttle = goal->throttle;
- bool quickturn = goal->quickturn;
- bool highgear = goal->highgear;
-
- control_loop_driving = goal->control_loop_driving;
- double left_goal = goal->left_goal;
- double right_goal = goal->right_goal;
-
- dt_closedloop.SetGoal(left_goal, goal->left_velocity_goal, right_goal,
- goal->right_velocity_goal);
- dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
- }
-
- if (!bad_pos) {
- const double left_encoder = position->left_encoder;
- const double right_encoder = position->right_encoder;
- if (gyro_reading.FetchLatest()) {
- LOG_STRUCT(DEBUG, "using", *gyro_reading.get());
- dt_closedloop.SetPosition(left_encoder, right_encoder,
- gyro_reading->angle);
- } else {
- dt_closedloop.SetRawPosition(left_encoder, right_encoder);
- }
- }
- dt_openloop.SetPosition(position);
- dt_openloop.Update();
-
- if (control_loop_driving) {
- dt_closedloop.Update(output == NULL, true);
- dt_closedloop.SendMotors(output);
- } else {
- dt_openloop.SendMotors(output);
- if (output) {
- dt_closedloop.SetExternalMotors(output->left_voltage,
- output->right_voltage);
- }
- dt_closedloop.Update(output == NULL, false);
- }
-
- // set the output status of the control loop state
- if (status) {
- status->robot_speed = dt_closedloop.GetEstimatedRobotSpeed();
- status->estimated_left_position = dt_closedloop.GetEstimatedLeftEncoder();
- status->estimated_right_position = dt_closedloop.GetEstimatedRightEncoder();
-
- status->estimated_left_velocity = dt_closedloop.loop().X_hat(1, 0);
- status->estimated_right_velocity = dt_closedloop.loop().X_hat(3, 0);
- status->output_was_capped = dt_closedloop.OutputWasCapped();
- status->uncapped_left_voltage = dt_closedloop.loop().U_uncapped(0, 0);
- status->uncapped_right_voltage = dt_closedloop.loop().U_uncapped(1, 0);
- }
-}
-
-} // namespace control_loops
-} // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain.h b/y2014_bot3/control_loops/drivetrain/drivetrain.h
deleted file mode 100644
index dfb7269..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain.h
+++ /dev/null
@@ -1,58 +0,0 @@
-#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
-#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
-
-#include "Eigen/Dense"
-
-#include "aos/common/controls/polytope.h"
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/util/log_interval.h"
-
-#include "frc971/shifter_hall_effect.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-// Constants
-// TODO(comran): Get actual constants.
-constexpr double kDrivetrainTurnWidth = 0.63;
-constexpr double kDrivetrainEncoderRatio = 18.0 / 44.0;
-constexpr double kDrivetrainHighGearRatio =
- kDrivetrainEncoderRatio * 18.0 / 60.0;
-constexpr double kDrivetrainLowGearRatio = kDrivetrainHighGearRatio;
-const ::frc971::constants::ShifterHallEffect kDrivetrainRightShifter{
- 555, 657, 660, 560, 0.2, 0.7};
-const ::frc971::constants::ShifterHallEffect kDrivetrainLeftShifter{
- 555, 660, 644, 552, 0.2, 0.7};
-// End constants
-
-class DrivetrainLoop
- : public aos::controls::ControlLoop<control_loops::DrivetrainQueue> {
- public:
- // Constructs a control loop which can take a Drivetrain or defaults to the
- // drivetrain at y2014_bot3::control_loops::drivetrain
- explicit DrivetrainLoop(control_loops::DrivetrainQueue *my_drivetrain =
- &control_loops::drivetrain_queue)
- : aos::controls::ControlLoop<control_loops::DrivetrainQueue>(
- my_drivetrain) {
- ::aos::controls::HPolytope<0>::Init();
- }
-
- protected:
- // Executes one cycle of the control loop.
- virtual void RunIteration(
- const control_loops::DrivetrainQueue::Goal *goal,
- const control_loops::DrivetrainQueue::Position *position,
- control_loops::DrivetrainQueue::Output *output,
- control_loops::DrivetrainQueue::Status *status);
-
- typedef ::aos::util::SimpleLogInterval SimpleLogInterval;
- SimpleLogInterval no_position_ = SimpleLogInterval(
- ::aos::time::Time::InSeconds(0.25), WARNING, "no position");
-};
-
-} // namespace control_loops
-} // namespace y2014_bot3
-
-#endif // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain.q b/y2014_bot3/control_loops/drivetrain/drivetrain.q
deleted file mode 100644
index 1b97f81..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain.q
+++ /dev/null
@@ -1,104 +0,0 @@
-package y2014_bot3.control_loops;
-
-import "aos/common/controls/control_loops.q";
-
-// For logging information about the state of the shifters.
-struct CIMLogging {
- // Whether the code thinks the left side is currently in gear.
- bool left_in_gear;
- // Whether the code thinks the right side is currently in gear.
- bool right_in_gear;
- // The velocity in rad/s (positive forward) the code thinks the left motor
- // is currently spinning at.
- double left_motor_speed;
- // The velocity in rad/s (positive forward) the code thinks the right motor
- // is currently spinning at.
- double right_motor_speed;
- // The velocity estimate for the left side of the robot in m/s (positive
- // forward) used for shifting.
- double left_velocity;
- // The velocity estimate for the right side of the robot in m/s (positive
- // forward) used for shifting.
- double right_velocity;
-};
-
-queue_group DrivetrainQueue {
- implements aos.control_loops.ControlLoop;
-
- message Goal {
- // Position of the steering wheel (positive = turning left when going
- // forwards).
- double steering;
- // Position of the throttle (positive forwards).
- double throttle;
- // True to shift into high, false to shift into low.
- bool highgear;
- // True to activate quickturn.
- bool quickturn;
- // True to have the closed-loop controller take over.
- bool control_loop_driving;
- // Position goal for the left side in meters when the closed-loop controller
- // is active.
- double left_goal;
- // Velocity goal for the left side in m/s when the closed-loop controller
- // is active.
- double left_velocity_goal;
- // Position goal for the right side in meters when the closed-loop
- // controller is active.
- double right_goal;
- // Velocity goal for the right side in m/s when the closed-loop controller
- // is active.
- double right_velocity_goal;
- };
-
- message Position {
- // Relative position of the left side in meters.
- double left_encoder;
- // Relative position of the right side in meters.
- double right_encoder;
- // The speed in m/s of the left side from the most recent encoder pulse,
- // or 0 if there was no edge within the last 5ms.
- double left_speed;
- // The speed in m/s of the right side from the most recent encoder pulse,
- // or 0 if there was no edge within the last 5ms.
- double right_speed;
- };
-
- message Output {
- // Voltage to send to the left motor(s).
- double left_voltage;
- // Voltage to send to the right motor(s).
- double right_voltage;
- // True to set the left shifter piston for high gear.
- bool left_high;
- // True to set the right shifter piston for high gear.
- bool right_high;
- };
-
- message Status {
- // Estimated speed of the center of the robot in m/s (positive forwards).
- double robot_speed;
- // Estimated relative position of the left side in meters.
- double estimated_left_position;
- // Estimated relative position of the right side in meters.
- double estimated_right_position;
- // Estimated velocity of the left side in m/s.
- double estimated_left_velocity;
- // Estimated velocity of the right side in m/s.
- double estimated_right_velocity;
-
- // The voltage we wanted to send to the left side last cycle.
- double uncapped_left_voltage;
- // The voltage we wanted to send to the right side last cycle.
- double uncapped_right_voltage;
- // True if the output voltage was capped last cycle.
- bool output_was_capped;
- };
-
- queue Goal goal;
- queue Position position;
- queue Output output;
- queue Status status;
-};
-
-queue_group DrivetrainQueue drivetrain_queue;
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2014_bot3/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..bca3f24
--- /dev/null
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,47 @@
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+#include "y2014_bot3/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace y2014_bot3 {
+namespace control_loops {
+namespace drivetrain {
+
+using ::frc971::constants::ShifterHallEffect;
+
+const ShifterHallEffect kThreeStateDriveShifter{0.0, 0.0, 0.0, 0.0, 0.25, 0.75};
+
+const DrivetrainConfig &GetDrivetrainConfig() {
+ static DrivetrainConfig kDrivetrainConfig{
+ ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
+ ::frc971::control_loops::drivetrain::LoopType::OPEN_LOOP,
+
+ ::y2014_bot3::control_loops::drivetrain::MakeDrivetrainLoop,
+ ::y2014_bot3::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+ ::y2014_bot3::control_loops::drivetrain::MakeKFDrivetrainLoop,
+
+ drivetrain::kDt,
+ drivetrain::kRobotRadius,
+ drivetrain::kWheelRadius,
+ drivetrain::kV,
+
+ drivetrain::kHighGearRatio,
+ drivetrain::kLowGearRatio,
+
+ // No shifter sensors, so we could put anything for the things below.
+ kThreeStateDriveShifter,
+ kThreeStateDriveShifter,
+ false};
+
+ return kDrivetrainConfig;
+};
+
+} // namespace drivetrain
+} // namespace control_loops
+} // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_base.h b/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..d2e54f9
--- /dev/null
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,20 @@
+#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2014_bot3 {
+namespace control_loops {
+namespace drivetrain {
+
+const double kDrivetrainEncoderRatio =
+ (17.0 / 50.0) /*output reduction*/ * (24.0 / 64.0) /*encoder gears*/;
+
+const ::frc971::control_loops::drivetrain::DrivetrainConfig &
+GetDrivetrainConfig();
+
+} // namespace drivetrain
+} // namespace control_loops
+} // namespace y2014_bot3
+
+#endif // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_constants.h b/y2014_bot3/control_loops/drivetrain/drivetrain_constants.h
deleted file mode 100644
index 28848b0..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_constants.h
+++ /dev/null
@@ -1,26 +0,0 @@
-#ifndef BOT3_CONTROL_LOOPS_DRIVETRAIN_CONSTANTS_H_
-#define BOT3_CONTROL_LOOPS_DRIVETRAIN_CONSTANTS_H_
-
-#include "bot3/shifter_hall_effect.h"
-
-namespace bot3 {
-namespace control_loops {
-
-constexpr constants::ShifterHallEffect kBot3LeftDriveShifter =
- {426, 171, 0.6, 0.47};
-constexpr constants::ShifterHallEffect kBot3RightDriveShifter =
- {424, 172, 0.62, 0.55};
-
-constexpr double kBot3TurnWidth = 0.5;
-constexpr double kBot3DrivetrainDoneDistance = 0.02;
-
-constexpr double kBot3LowGearRatio = 14.0 / 60.0 * 17.0 / 50.0;
-constexpr double kBot3HighGearRatio = 30.0 / 44.0 * 17.0 / 50.0;
-
-// If this is true, we don't use the analog hall effects for shifting.
-constexpr bool kBot3SimpleShifting = true;
-
-} // control_loops
-} // bot3
-
-#endif
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_lib_test.cc b/y2014_bot3/control_loops/drivetrain/drivetrain_lib_test.cc
deleted file mode 100644
index 3953951..0000000
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_lib_test.cc
+++ /dev/null
@@ -1,295 +0,0 @@
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/network/team_number.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/controls/control_loop_test.h"
-
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/coerce_goal.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-#include "frc971/queues/gyro.q.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-namespace testing {
-
-class Environment : public ::testing::Environment {
- public:
- virtual ~Environment() {}
- // how to set up the environment.
- virtual void SetUp() {
- aos::controls::HPolytope<0>::Init();
- }
-};
-::testing::Environment* const holder_env =
- ::testing::AddGlobalTestEnvironment(new Environment);
-
-class TeamNumberEnvironment : public ::testing::Environment {
- public:
- // Override this to define how to set up the environment.
- virtual void SetUp() { aos::network::OverrideTeamNumber(971); }
-};
-
-::testing::Environment* const team_number_env =
- ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
-
-// Class which simulates the drivetrain and sends out queue messages containing
-// the position.
-class DrivetrainSimulation {
- public:
- // Constructs a motor simulation.
- // TODO(aschuh) Do we want to test the clutch one too?
- DrivetrainSimulation()
- : drivetrain_plant_(
- new StateFeedbackPlant<4, 2, 2>(drivetrain::MakeDrivetrainPlant())),
- my_drivetrain_queue_(".y2014_bot3.control_loops.drivetrain",
- 0x8a8dde77, ".y2014_bot3.control_loops.drivetrain.goal",
- ".y2014_bot3.control_loops.drivetrain.position",
- ".y2014_bot3.control_loops.drivetrain.output",
- ".y2014_bot3.control_loops.drivetrain.status") {
- Reinitialize();
- }
-
- // Resets the plant.
- void Reinitialize() {
- drivetrain_plant_->mutable_X(0, 0) = 0.0;
- drivetrain_plant_->mutable_X(1, 0) = 0.0;
- drivetrain_plant_->mutable_Y() =
- drivetrain_plant_->C() * drivetrain_plant_->X();
- last_left_position_ = drivetrain_plant_->Y(0, 0);
- last_right_position_ = drivetrain_plant_->Y(1, 0);
- }
-
- // Returns the position of the drivetrain.
- double GetLeftPosition() const { return drivetrain_plant_->Y(0, 0); }
- double GetRightPosition() const { return drivetrain_plant_->Y(1, 0); }
-
- // Sends out the position queue messages.
- void SendPositionMessage() {
- const double left_encoder = GetLeftPosition();
- const double right_encoder = GetRightPosition();
-
- ::aos::ScopedMessagePtr<control_loops::DrivetrainQueue::Position> position =
- my_drivetrain_queue_.position.MakeMessage();
- position->left_encoder = left_encoder;
- position->right_encoder = right_encoder;
- position.Send();
- }
-
- // Simulates the drivetrain moving for one timestep.
- void Simulate() {
- last_left_position_ = drivetrain_plant_->Y(0, 0);
- last_right_position_ = drivetrain_plant_->Y(1, 0);
- EXPECT_TRUE(my_drivetrain_queue_.output.FetchLatest());
- drivetrain_plant_->mutable_U() << my_drivetrain_queue_.output->left_voltage,
- my_drivetrain_queue_.output->right_voltage;
- drivetrain_plant_->Update();
- }
-
- ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> drivetrain_plant_;
- private:
- DrivetrainQueue my_drivetrain_queue_;
- double last_left_position_;
- double last_right_position_;
-};
-
-class DrivetrainTest : public ::aos::testing::ControlLoopTest {
- protected:
- // Create a new instance of the test queue so that it invalidates the queue
- // that it points to. Otherwise, we will have a pointer to shared memory that
- // is no longer valid.
- DrivetrainQueue my_drivetrain_queue_;
-
- // Create a loop and simulation plant.
- DrivetrainLoop drivetrain_motor_;
- DrivetrainSimulation drivetrain_motor_plant_;
-
- DrivetrainTest() : my_drivetrain_queue_(".y2014_bot3.control_loops.drivetrain",
- 0x8a8dde77,
- ".y2014_bot3.control_loops.drivetrain.goal",
- ".y2014_bot3.control_loops.drivetrain.position",
- ".y2014_bot3.control_loops.drivetrain.output",
- ".y2014_bot3.control_loops.drivetrain.status"),
- drivetrain_motor_(&my_drivetrain_queue_),
- drivetrain_motor_plant_() {
- ::frc971::sensors::gyro_reading.Clear();
- }
-
- void VerifyNearGoal() {
- my_drivetrain_queue_.goal.FetchLatest();
- my_drivetrain_queue_.position.FetchLatest();
- EXPECT_NEAR(my_drivetrain_queue_.goal->left_goal,
- drivetrain_motor_plant_.GetLeftPosition(),
- 1e-2);
- EXPECT_NEAR(my_drivetrain_queue_.goal->right_goal,
- drivetrain_motor_plant_.GetRightPosition(),
- 1e-2);
- }
-
- virtual ~DrivetrainTest() {
- ::frc971::sensors::gyro_reading.Clear();
- }
-};
-
-// Tests that the drivetrain converges on a goal.
-TEST_F(DrivetrainTest, ConvergesCorrectly) {
- my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
- .left_goal(-1.0)
- .right_goal(1.0).Send();
- for (int i = 0; i < 200; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- SimulateTimestep(true);
- }
- VerifyNearGoal();
-}
-
-// Tests that it survives disabling.
-TEST_F(DrivetrainTest, SurvivesDisabling) {
- my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
- .left_goal(-1.0)
- .right_goal(1.0).Send();
- for (int i = 0; i < 500; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- if (i > 20 && i < 200) {
- SimulateTimestep(false);
- } else {
- SimulateTimestep(true);
- }
- }
- VerifyNearGoal();
-}
-
-// Tests that never having a goal doesn't break.
-TEST_F(DrivetrainTest, NoGoalStart) {
- for (int i = 0; i < 20; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- }
-}
-
-// Tests that never having a goal, but having driver's station messages, doesn't
-// break.
-TEST_F(DrivetrainTest, NoGoalWithRobotState) {
- for (int i = 0; i < 20; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- SimulateTimestep(true);
- }
-}
-
-::aos::controls::HPolytope<2> MakeBox(double x1_min, double x1_max,
- double x2_min, double x2_max) {
- Eigen::Matrix<double, 4, 2> box_H;
- box_H << /*[[*/ 1.0, 0.0 /*]*/,
- /*[*/-1.0, 0.0 /*]*/,
- /*[*/ 0.0, 1.0 /*]*/,
- /*[*/ 0.0,-1.0 /*]]*/;
- Eigen::Matrix<double, 4, 1> box_k;
- box_k << /*[[*/ x1_max /*]*/,
- /*[*/-x1_min /*]*/,
- /*[*/ x2_max /*]*/,
- /*[*/-x2_min /*]]*/;
- ::aos::controls::HPolytope<2> t_poly(box_H, box_k);
- return t_poly;
-}
-
-class CoerceGoalTest : public ::testing::Test {
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
-};
-
-// WHOOOHH!
-TEST_F(CoerceGoalTest, Inside) {
- ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << /*[[*/ 1, -1 /*]]*/;
-
- Eigen::Matrix<double, 2, 1> R;
- R << /*[[*/ 1.5, 1.5 /*]]*/;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(R(0, 0), output(0, 0));
- EXPECT_EQ(R(1, 0), output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Outside_Inside_Intersect) {
- ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << 1, -1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(2.0, output(0, 0));
- EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Outside_Inside_no_Intersect) {
- ::aos::controls::HPolytope<2> box = MakeBox(3, 4, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << 1, -1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(3.0, output(0, 0));
- EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Middle_Of_Edge) {
- ::aos::controls::HPolytope<2> box = MakeBox(0, 4, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << -1, 1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(2.0, output(0, 0));
- EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, PerpendicularLine) {
- ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << 1, 1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(1.0, output(0, 0));
- EXPECT_EQ(1.0, output(1, 0));
-}
-
-} // namespace testing
-} // namespace control_loops
-} // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc b/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc
index 588bc89..a0f0a83 100644
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_main.cc
@@ -1,10 +1,14 @@
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
-
#include "aos/linux_code/init.h"
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+
int main() {
::aos::Init();
- y2014_bot3::control_loops::DrivetrainLoop drivetrain;
+ DrivetrainLoop drivetrain(
+ ::y2014_bot3::control_loops::drivetrain::GetDrivetrainConfig());
drivetrain.Run();
::aos::Cleanup();
return 0;
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc
deleted file mode 100644
index 75bae13..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients() {
- Eigen::Matrix<double, 1, 1> A;
- A << 0.783924473544;
- Eigen::Matrix<double, 1, 1> B;
- B << 8.94979586973;
- Eigen::Matrix<double, 1, 1> C;
- C << 1;
- Eigen::Matrix<double, 1, 1> D;
- D << 0;
- Eigen::Matrix<double, 1, 1> U_max;
- U_max << 12.0;
- Eigen::Matrix<double, 1, 1> U_min;
- U_min << -12.0;
- return StateFeedbackPlantCoefficients<1, 1, 1>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<1, 1, 1> MakeCIMController() {
- Eigen::Matrix<double, 1, 1> L;
- L << 0.773924473544;
- Eigen::Matrix<double, 1, 1> K;
- K << 0.086473980503;
- Eigen::Matrix<double, 1, 1> A_inv;
- A_inv << 1.2756330919;
- return StateFeedbackController<1, 1, 1>(L, K, A_inv, MakeCIMPlantCoefficients());
-}
-
-StateFeedbackPlant<1, 1, 1> MakeCIMPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>> plants(1);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>(new StateFeedbackPlantCoefficients<1, 1, 1>(MakeCIMPlantCoefficients()));
- return StateFeedbackPlant<1, 1, 1>(&plants);
-}
-
-StateFeedbackLoop<1, 1, 1> MakeCIMLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<1, 1, 1>>> controllers(1);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<1, 1, 1>>(new StateFeedbackController<1, 1, 1>(MakeCIMController()));
- return StateFeedbackLoop<1, 1, 1>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h b/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h
deleted file mode 100644
index 0def071..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_cim_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
-#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients();
-
-StateFeedbackController<1, 1, 1> MakeCIMController();
-
-StateFeedbackPlant<1, 1, 1> MakeCIMPlant();
-
-StateFeedbackLoop<1, 1, 1> MakeCIMLoop();
-
-} // namespace control_loops
-} // namespace y2014_bot3
-
-#endif // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
deleted file mode 100644
index 8fc4049..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
+++ /dev/null
@@ -1,133 +0,0 @@
-#include "y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.953388055571, 0.0100729449137, 0.0100729449137, 0.953388055571;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0119133285199, -0.00257449680311, -0.00257449680311, 0.0119133285199;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
- Eigen::Matrix<double, 2, 2> K;
- K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowLowPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
- Eigen::Matrix<double, 2, 2> K;
- K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowHighPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
- Eigen::Matrix<double, 2, 2> K;
- K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighLowPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.933388055571, 0.0100729449137, 0.0100729449137, 0.933388055571;
- Eigen::Matrix<double, 2, 2> K;
- K << 31.3080614945, 7.61126069778, 7.61126069778, 31.3080614945;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04900794038, -0.0110832091253, -0.0110832091253, 1.04900794038;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighHighPlantCoefficients());
-}
-
-StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>> plants(4);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowLowPlantCoefficients()));
- plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowHighPlantCoefficients()));
- plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighLowPlantCoefficients()));
- plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighHighPlantCoefficients()));
- return StateFeedbackPlant<2, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 2, 2>>> controllers(4);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowLowController()));
- controllers[1] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowHighController()));
- controllers[2] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighLowController()));
- controllers[3] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighHighController()));
- return StateFeedbackLoop<2, 2, 2>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace y2014_bot3
diff --git a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
deleted file mode 100644
index 4442d35..0000000
--- a/y2014_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
-#define Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace y2014_bot3 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController();
-
-StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant();
-
-StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop();
-
-} // namespace control_loops
-} // namespace y2014_bot3
-
-#endif // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2014_bot3/control_loops/drivetrain/replay_drivetrain.cc b/y2014_bot3/control_loops/drivetrain/replay_drivetrain.cc
deleted file mode 100644
index 4f83c9e..0000000
--- a/y2014_bot3/control_loops/drivetrain/replay_drivetrain.cc
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "aos/common/controls/replay_control_loop.h"
-#include "aos/linux_code/init.h"
-
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
-
-// Reads one or more log files and sends out all the queue messages (in the
-// correct order and at the correct time) to feed a "live" drivetrain process.
-
-int main(int argc, char **argv) {
- if (argc <= 1) {
- fprintf(stderr, "Need at least one file to replay!\n");
- return EXIT_FAILURE;
- }
-
- ::aos::InitNRT();
-
- ::aos::controls::ControlLoopReplayer<::y2014_bot3::control_loops::DrivetrainQueue>
- replayer(&::y2014_bot3::control_loops::drivetrain_queue, "drivetrain");
- for (int i = 1; i < argc; ++i) {
- replayer.ProcessFile(argv[i]);
- }
-
- ::aos::Cleanup();
-}
diff --git a/y2014_bot3/control_loops/python/BUILD b/y2014_bot3/control_loops/python/BUILD
index bb8dc29..756b60e 100644
--- a/y2014_bot3/control_loops/python/BUILD
+++ b/y2014_bot3/control_loops/python/BUILD
@@ -6,7 +6,21 @@
'drivetrain.py',
],
deps = [
+ '//external:python-gflags',
'//external:python-glog',
'//frc971/control_loops/python:controls',
]
)
+
+py_binary(
+ name = 'polydrivetrain',
+ srcs = [
+ 'polydrivetrain.py',
+ 'drivetrain.py',
+ ],
+ deps = [
+ '//external:python-gflags',
+ '//external:python-glog',
+ '//frc971/control_loops/python:controls',
+ ],
+)
diff --git a/y2014_bot3/control_loops/python/drivetrain.py b/y2014_bot3/control_loops/python/drivetrain.py
index 4231887..b0555a0 100755
--- a/y2014_bot3/control_loops/python/drivetrain.py
+++ b/y2014_bot3/control_loops/python/drivetrain.py
@@ -4,10 +4,16 @@
from frc971.control_loops.python import controls
import numpy
import sys
+import argparse
from matplotlib import pylab
+import gflags
import glog
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
class CIM(control_loop.ControlLoop):
def __init__(self):
super(CIM, self).__init__("CIM")
@@ -22,10 +28,10 @@
# Moment of inertia of the CIM in kg m^2
self.J = 0.0001
# Resistance of the motor, divided by 2 to account for the 2 motors
- self.R = 12.0 / self.stall_current
+ self.resistance = 12.0 / self.stall_current
# Motor velocity constant
self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
+ (12.0 - self.resistance * self.free_current))
# Torque constant
self.Kt = self.stall_torque / self.stall_current
# Control loop time step
@@ -33,9 +39,9 @@
# State feedback matrices
self.A_continuous = numpy.matrix(
- [[-self.Kt / self.Kv / (self.J * self.R)]])
+ [[-self.Kt / self.Kv / (self.J * self.resistance)]])
self.B_continuous = numpy.matrix(
- [[self.Kt / (self.J * self.R)]])
+ [[self.Kt / (self.J * self.resistance)]])
self.C = numpy.matrix([[1]])
self.D = numpy.matrix([[0]])
@@ -54,36 +60,34 @@
class Drivetrain(control_loop.ControlLoop):
def __init__(self, name="Drivetrain", left_low=True, right_low=True):
super(Drivetrain, self).__init__(name)
+ # Number of motors per side
+ self.num_motors = 2
# Stall Torque in N m
- self.stall_torque = 2.42
+ self.stall_torque = 2.42 * self.num_motors * 0.60
# Stall Current in Amps
- self.stall_current = 133.0
+ self.stall_current = 133.0 * self.num_motors
# Free Speed in RPM. Used number from last year.
- self.free_speed = 4650.0
+ self.free_speed = 5500.0
# Free Current in Amps
- self.free_current = 2.7
+ self.free_current = 4.7 * self.num_motors
# Moment of inertia of the drivetrain in kg m^2
- # Just borrowed from last year.
- self.J = 10
+ self.J = 1.8
# Mass of the robot, in kg.
- self.m = 68
- # Radius of the robot, in meters (from last year).
- self.rb = 0.9603 / 2.0
+ self.m = 37
+ # Radius of the robot, in meters (requires tuning by hand)
+ self.rb = 0.601 / 2.0
# Radius of the wheels, in meters.
self.r = 0.0508
# Resistance of the motor, divided by the number of motors.
- self.R = 12.0 / self.stall_current / 2
+ self.resistance = 12.0 / self.stall_current
# Motor velocity constant
self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
+ (12.0 - self.resistance * self.free_current))
# Torque constant
self.Kt = self.stall_torque / self.stall_current
# Gear ratios
- self.G_const = 18.0 / 44.0 * 18.0 / 60.0
-
- self.G_low = self.G_const
- self.G_high = self.G_const
-
+ self.G_low = 28.0 / 60.0 * 19.0 / 50.0
+ self.G_high = 28.0 / 48.0 * 19.0 / 50.0
if left_low:
self.Gl = self.G_low
else:
@@ -101,10 +105,10 @@
self.msp = 1.0 / self.m + self.rb * self.rb / self.J
self.msn = 1.0 / self.m - self.rb * self.rb / self.J
# The calculations which we will need for A and B.
- self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.R * self.r * self.r)
- self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.R * self.r * self.r)
- self.mpl = self.Kt / (self.Gl * self.R * self.r)
- self.mpr = self.Kt / (self.Gr * self.R * self.r)
+ self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.resistance * self.r * self.r)
+ self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.resistance * self.r * self.r)
+ self.mpl = self.Kt / (self.Gl * self.resistance * self.r)
+ self.mpr = self.Kt / (self.Gr * self.resistance * self.r)
# State feedback matrices
# X will be of the format
@@ -124,17 +128,16 @@
self.D = numpy.matrix([[0, 0],
[0, 0]])
- #glog.debug('THE NUMBER I WANT %s', str(numpy.linalg.inv(self.A_continuous) * -self.B_continuous * numpy.matrix([[12.0], [12.0]])))
self.A, self.B = self.ContinuousToDiscrete(
self.A_continuous, self.B_continuous, self.dt)
- # Poles from last year.
- self.hp = 0.65
- self.lp = 0.83
- self.PlaceControllerPoles([self.hp, self.lp, self.hp, self.lp])
- glog.info('K %s', str(self.K))
- q_pos = 0.07
- q_vel = 1.0
+ if left_low or right_low:
+ q_pos = 0.12
+ q_vel = 1.0
+ else:
+ q_pos = 0.14
+ q_vel = 0.95
+
self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
[0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
[0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
@@ -143,10 +146,10 @@
self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
[0.0, (1.0 / (12.0 ** 2.0))]])
self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
- glog.info('A %s', str(self.A))
- glog.info('B %s', str(self.B))
- glog.info('K %s', str(self.K))
- glog.info('Poles are %s', str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+
+ glog.debug('DT q_pos %f q_vel %s %s', q_pos, q_vel, name)
+ glog.debug(str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+ glog.debug('K %s', repr(self.K))
self.hlp = 0.3
self.llp = 0.4
@@ -154,11 +157,102 @@
self.U_max = numpy.matrix([[12.0], [12.0]])
self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
self.InitializeState()
+
+class KFDrivetrain(Drivetrain):
+ def __init__(self, name="KFDrivetrain", left_low=True, right_low=True):
+ super(KFDrivetrain, self).__init__(name, left_low, right_low)
+
+ self.unaugmented_A_continuous = self.A_continuous
+ self.unaugmented_B_continuous = self.B_continuous
+
+ # The states are
+ # The practical voltage applied to the wheels is
+ # V_left = U_left + left_voltage_error
+ #
+ # [left position, left velocity, right position, right velocity,
+ # left voltage error, right voltage error, angular_error]
+ #
+ # The left and right positions are filtered encoder positions and are not
+ # adjusted for heading error.
+ # The turn velocity as computed by the left and right velocities is
+ # adjusted by the gyro velocity.
+ # The angular_error is the angular velocity error between the wheel speed
+ # and the gyro speed.
+ self.A_continuous = numpy.matrix(numpy.zeros((7, 7)))
+ self.B_continuous = numpy.matrix(numpy.zeros((7, 2)))
+ self.A_continuous[0:4,0:4] = self.unaugmented_A_continuous
+ self.A_continuous[0:4,4:6] = self.unaugmented_B_continuous
+ self.B_continuous[0:4,0:2] = self.unaugmented_B_continuous
+ self.A_continuous[0,6] = 1
+ self.A_continuous[2,6] = -1
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ self.C = numpy.matrix([[1, 0, 0, 0, 0, 0, 0],
+ [0, 0, 1, 0, 0, 0, 0],
+ [0, -0.5 / self.rb, 0, 0.5 / self.rb, 0, 0, 0]])
+
+ self.D = numpy.matrix([[0, 0],
+ [0, 0],
+ [0, 0]])
+
+ q_pos = 0.05
+ q_vel = 1.00
+ q_voltage = 10.0
+ q_encoder_uncertainty = 2.00
+
+ self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
+ [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0],
+ [0.0, 0.0, (q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0],
+ [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, (q_encoder_uncertainty ** 2.0)]])
+
+ r_pos = 0.0001
+ r_gyro = 0.000001
+ self.R = numpy.matrix([[(r_pos ** 2.0), 0.0, 0.0],
+ [0.0, (r_pos ** 2.0), 0.0],
+ [0.0, 0.0, (r_gyro ** 2.0)]])
+
+ # Solving for kf gains.
+ self.KalmanGain, self.Q_steady = controls.kalman(
+ A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+ self.L = self.A * self.KalmanGain
+
+ unaug_K = self.K
+
+ # Implement a nice closed loop controller for use by the closed loop
+ # controller.
+ self.K = numpy.matrix(numpy.zeros((self.B.shape[1], self.A.shape[0])))
+ self.K[0:2, 0:4] = unaug_K
+ self.K[0, 4] = 1.0
+ self.K[1, 5] = 1.0
+
+ self.Qff = numpy.matrix(numpy.zeros((4, 4)))
+ qff_pos = 0.005
+ qff_vel = 1.00
+ self.Qff[0, 0] = 1.0 / qff_pos ** 2.0
+ self.Qff[1, 1] = 1.0 / qff_vel ** 2.0
+ self.Qff[2, 2] = 1.0 / qff_pos ** 2.0
+ self.Qff[3, 3] = 1.0 / qff_vel ** 2.0
+ self.Kff = numpy.matrix(numpy.zeros((2, 7)))
+ self.Kff[0:2, 0:4] = controls.TwoStateFeedForwards(self.B[0:4,:], self.Qff)
+
+ self.InitializeState()
+
+
def main(argv):
+ argv = FLAGS(argv)
+ glog.init()
+
# Simulate the response of the system to a step input.
- drivetrain = Drivetrain()
+ drivetrain = Drivetrain(left_low=False, right_low=False)
simulated_left = []
simulated_right = []
for _ in xrange(100):
@@ -166,26 +260,37 @@
simulated_left.append(drivetrain.X[0, 0])
simulated_right.append(drivetrain.X[2, 0])
- #pylab.plot(range(100), simulated_left)
- #pylab.plot(range(100), simulated_right)
- #pylab.show()
+ if FLAGS.plot:
+ pylab.plot(range(100), simulated_left)
+ pylab.plot(range(100), simulated_right)
+ pylab.suptitle('Acceleration Test')
+ pylab.show()
# Simulate forwards motion.
- drivetrain = Drivetrain()
+ drivetrain = Drivetrain(left_low=False, right_low=False)
close_loop_left = []
close_loop_right = []
+ left_power = []
+ right_power = []
R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
- for _ in xrange(100):
+ for _ in xrange(300):
U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
drivetrain.U_min, drivetrain.U_max)
drivetrain.UpdateObserver(U)
drivetrain.Update(U)
close_loop_left.append(drivetrain.X[0, 0])
close_loop_right.append(drivetrain.X[2, 0])
+ left_power.append(U[0, 0])
+ right_power.append(U[1, 0])
- #pylab.plot(range(100), close_loop_left)
- #pylab.plot(range(100), close_loop_right)
- #pylab.show()
+ if FLAGS.plot:
+ pylab.plot(range(300), close_loop_left, label='left position')
+ pylab.plot(range(300), close_loop_right, label='right position')
+ pylab.plot(range(300), left_power, label='left power')
+ pylab.plot(range(300), right_power, label='right power')
+ pylab.suptitle('Linear Move')
+ pylab.legend()
+ pylab.show()
# Try turning in place
drivetrain = Drivetrain()
@@ -200,9 +305,11 @@
close_loop_left.append(drivetrain.X[0, 0])
close_loop_right.append(drivetrain.X[2, 0])
- #pylab.plot(range(100), close_loop_left)
- #pylab.plot(range(100), close_loop_right)
- #pylab.show()
+ if FLAGS.plot:
+ pylab.plot(range(100), close_loop_left)
+ pylab.plot(range(100), close_loop_right)
+ pylab.suptitle('Angular Move')
+ pylab.show()
# Try turning just one side.
drivetrain = Drivetrain()
@@ -217,25 +324,75 @@
close_loop_left.append(drivetrain.X[0, 0])
close_loop_right.append(drivetrain.X[2, 0])
- #pylab.plot(range(100), close_loop_left)
- #pylab.plot(range(100), close_loop_right)
- #pylab.show()
+ if FLAGS.plot:
+ pylab.plot(range(100), close_loop_left)
+ pylab.plot(range(100), close_loop_right)
+ pylab.suptitle('Pivot')
+ pylab.show()
# Write the generated constants out to a file.
- glog.info('Output one')
- drivetrain_low_low = Drivetrain(name="DrivetrainLowLow", left_low=True, right_low=True)
- drivetrain_low_high = Drivetrain(name="DrivetrainLowHigh", left_low=True, right_low=False)
- drivetrain_high_low = Drivetrain(name="DrivetrainHighLow", left_low=False, right_low=True)
- drivetrain_high_high = Drivetrain(name="DrivetrainHighHigh", left_low=False, right_low=False)
+ drivetrain_low_low = Drivetrain(
+ name="DrivetrainLowLow", left_low=True, right_low=True)
+ drivetrain_low_high = Drivetrain(
+ name="DrivetrainLowHigh", left_low=True, right_low=False)
+ drivetrain_high_low = Drivetrain(
+ name="DrivetrainHighLow", left_low=False, right_low=True)
+ drivetrain_high_high = Drivetrain(
+ name="DrivetrainHighHigh", left_low=False, right_low=False)
- if len(argv) != 3:
- glog.fatal('Expected .h file name and .cc file name')
+ kf_drivetrain_low_low = KFDrivetrain(
+ name="KFDrivetrainLowLow", left_low=True, right_low=True)
+ kf_drivetrain_low_high = KFDrivetrain(
+ name="KFDrivetrainLowHigh", left_low=True, right_low=False)
+ kf_drivetrain_high_low = KFDrivetrain(
+ name="KFDrivetrainHighLow", left_low=False, right_low=True)
+ kf_drivetrain_high_high = KFDrivetrain(
+ name="KFDrivetrainHighHigh", left_low=False, right_low=False)
+
+ if len(argv) != 5:
+ print "Expected .h file name and .cc file name"
else:
+ namespaces = ['y2014_bot3', 'control_loops', 'drivetrain']
dog_loop_writer = control_loop.ControlLoopWriter(
"Drivetrain", [drivetrain_low_low, drivetrain_low_high,
drivetrain_high_low, drivetrain_high_high],
- namespaces=['y2014_bot3', 'control_loops', 'drivetrain'])
+ namespaces = namespaces)
+ dog_loop_writer.AddConstant(control_loop.Constant("kDt", "%f",
+ drivetrain_low_low.dt))
+ dog_loop_writer.AddConstant(control_loop.Constant("kStallTorque", "%f",
+ drivetrain_low_low.stall_torque))
+ dog_loop_writer.AddConstant(control_loop.Constant("kStallCurrent", "%f",
+ drivetrain_low_low.stall_current))
+ dog_loop_writer.AddConstant(control_loop.Constant("kFreeSpeedRPM", "%f",
+ drivetrain_low_low.free_speed))
+ dog_loop_writer.AddConstant(control_loop.Constant("kFreeCurrent", "%f",
+ drivetrain_low_low.free_current))
+ dog_loop_writer.AddConstant(control_loop.Constant("kJ", "%f",
+ drivetrain_low_low.J))
+ dog_loop_writer.AddConstant(control_loop.Constant("kMass", "%f",
+ drivetrain_low_low.m))
+ dog_loop_writer.AddConstant(control_loop.Constant("kRobotRadius", "%f",
+ drivetrain_low_low.rb))
+ dog_loop_writer.AddConstant(control_loop.Constant("kWheelRadius", "%f",
+ drivetrain_low_low.r))
+ dog_loop_writer.AddConstant(control_loop.Constant("kR", "%f",
+ drivetrain_low_low.resistance))
+ dog_loop_writer.AddConstant(control_loop.Constant("kV", "%f",
+ drivetrain_low_low.Kv))
+ dog_loop_writer.AddConstant(control_loop.Constant("kT", "%f",
+ drivetrain_low_low.Kt))
+ dog_loop_writer.AddConstant(control_loop.Constant("kLowGearRatio", "%f",
+ drivetrain_low_low.G_low))
+ dog_loop_writer.AddConstant(control_loop.Constant("kHighGearRatio", "%f",
+ drivetrain_high_high.G_high))
+
dog_loop_writer.Write(argv[1], argv[2])
+ kf_loop_writer = control_loop.ControlLoopWriter(
+ "KFDrivetrain", [kf_drivetrain_low_low, kf_drivetrain_low_high,
+ kf_drivetrain_high_low, kf_drivetrain_high_high],
+ namespaces = namespaces)
+ kf_loop_writer.Write(argv[3], argv[4])
+
if __name__ == '__main__':
sys.exit(main(sys.argv))
diff --git a/y2014_bot3/control_loops/python/polydrivetrain.py b/y2014_bot3/control_loops/python/polydrivetrain.py
index 2ffbed6..e047c11 100755
--- a/y2014_bot3/control_loops/python/polydrivetrain.py
+++ b/y2014_bot3/control_loops/python/polydrivetrain.py
@@ -2,14 +2,23 @@
import numpy
import sys
-import polytope
-import drivetrain
-import control_loop
-import controls
+from frc971.control_loops.python import polytope
+from y2014_bot3.control_loops.python import drivetrain
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
from matplotlib import pylab
+import gflags
+import glog
+
__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
def CoerceGoal(region, K, w, R):
"""Intersects a line with a region, and finds the closest point to R.
@@ -110,8 +119,8 @@
self.B_continuous = numpy.matrix(
[[self._drivetrain.B_continuous[1, 0], self._drivetrain.B_continuous[1, 1]],
[self._drivetrain.B_continuous[3, 0], self._drivetrain.B_continuous[3, 1]]])
- self.C = numpy.matrix(numpy.eye(2));
- self.D = numpy.matrix(numpy.zeros((2, 2)));
+ self.C = numpy.matrix(numpy.eye(2))
+ self.D = numpy.matrix(numpy.zeros((2, 2)))
self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
self.B_continuous, self.dt)
@@ -119,12 +128,12 @@
# FF * X = U (steady state)
self.FF = self.B.I * (numpy.eye(2) - self.A)
- self.PlaceControllerPoles([0.6, 0.6])
+ self.PlaceControllerPoles([0.67, 0.67])
self.PlaceObserverPoles([0.02, 0.02])
self.G_high = self._drivetrain.G_high
self.G_low = self._drivetrain.G_low
- self.R = self._drivetrain.R
+ self.resistance = self._drivetrain.resistance
self.r = self._drivetrain.r
self.Kv = self._drivetrain.Kv
self.Kt = self._drivetrain.Kt
@@ -174,10 +183,14 @@
[[0.0],
[0.0]])
+ self.U_ideal = numpy.matrix(
+ [[0.0],
+ [0.0]])
+
# ttrust is the comprimise between having full throttle negative inertia,
# and having no throttle negative inertia. A value of 0 is full throttle
# inertia. A value of 1 is no throttle negative inertia.
- self.ttrust = 1.1
+ self.ttrust = 1.0
self.left_gear = VelocityDrivetrain.LOW
self.right_gear = VelocityDrivetrain.LOW
@@ -229,9 +242,9 @@
self.CurrentDrivetrain().r)
#print gear_name, "Motor Energy Difference.", 0.5 * 0.000140032647 * (low_omega * low_omega - high_omega * high_omega), "joules"
high_torque = ((12.0 - high_omega / self.CurrentDrivetrain().Kv) *
- self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+ self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().resistance)
low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
- self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+ self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().resistance)
high_power = high_torque * high_omega
low_power = low_torque * low_omega
#if should_print:
@@ -250,16 +263,16 @@
#goal_gear_is_high = True
if not self.IsInGear(current_gear):
- print gear_name, 'Not in gear.'
+ glog.debug('%s Not in gear.', gear_name)
return current_gear
else:
is_high = current_gear is VelocityDrivetrain.HIGH
if is_high != goal_gear_is_high:
if goal_gear_is_high:
- print gear_name, 'Shifting up.'
+ glog.debug('%s Shifting up.', gear_name)
return VelocityDrivetrain.SHIFTING_UP
else:
- print gear_name, 'Shifting down.'
+ glog.debug('%s Shifting down.', gear_name)
return VelocityDrivetrain.SHIFTING_DOWN
else:
return current_gear
@@ -303,7 +316,7 @@
# wheel.
self.left_gear = self.right_gear = True
- if False:
+ if True:
self.left_gear = self.ComputeGear(self.X[0, 0], should_print=True,
current_gear=self.left_gear,
gear_name="left")
@@ -316,8 +329,7 @@
if self.IsInGear(self.right_gear):
self.right_cim.X[0, 0] = self.MotorRPM(self.right_shifter_position, self.X[0, 0])
- steering *= 2.3
- if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+ if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
# Filter the throttle to provide a nicer response.
fvel = self.FilterVelocity(throttle)
@@ -362,7 +374,7 @@
FF_volts = self.CurrentDrivetrain().FF * self.boxed_R
self.U_ideal = self.CurrentDrivetrain().K * (self.boxed_R - self.X) + FF_volts
else:
- print 'Not all in gear'
+ glog.debug('Not all in gear')
if not self.IsInGear(self.left_gear) and not self.IsInGear(self.right_gear):
# TODO(austin): Use battery volts here.
R_left = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
@@ -383,7 +395,7 @@
# TODO(austin): Model the robot as not accelerating when you shift...
# This hack only works when you shift at the same time.
- if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+ if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
self.X = self.CurrentDrivetrain().A * self.X + self.CurrentDrivetrain().B * self.U
self.left_gear, self.left_shifter_position = self.SimShifter(
@@ -391,37 +403,36 @@
self.right_gear, self.right_shifter_position = self.SimShifter(
self.right_gear, self.right_shifter_position)
- print "U is", self.U[0, 0], self.U[1, 0]
- print "Left shifter", self.left_gear, self.left_shifter_position, "Right shifter", self.right_gear, self.right_shifter_position
+ glog.debug('U is %s %s', str(self.U[0, 0]), str(self.U[1, 0]))
+ glog.debug('Left shifter %s %d Right shifter %s %d',
+ self.left_gear, self.left_shifter_position,
+ self.right_gear, self.right_shifter_position)
def main(argv):
+ argv = FLAGS(argv)
+
vdrivetrain = VelocityDrivetrain()
- if len(argv) != 7:
- print "Expected .h file name and .cc file name"
- else:
- dog_loop_writer = control_loop.ControlLoopWriter(
- "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
- vdrivetrain.drivetrain_low_high,
- vdrivetrain.drivetrain_high_low,
- vdrivetrain.drivetrain_high_high],
- namespaces=['y2014_bot3', 'control_loops'])
-
- if argv[1][-3:] == '.cc':
- dog_loop_writer.Write(argv[2], argv[1])
+ if not FLAGS.plot:
+ if len(argv) != 5:
+ glog.fatal('Expected .h file name and .cc file name')
else:
+ namespaces = ['y2014_bot3', 'control_loops', 'drivetrain']
+ dog_loop_writer = control_loop.ControlLoopWriter(
+ "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
+ vdrivetrain.drivetrain_low_high,
+ vdrivetrain.drivetrain_high_low,
+ vdrivetrain.drivetrain_high_high],
+ namespaces=namespaces)
+
dog_loop_writer.Write(argv[1], argv[2])
- cim_writer = control_loop.ControlLoopWriter(
- "CIM", [drivetrain.CIM()],
- namespaces=['y2014_bot3', 'control_loops'])
+ cim_writer = control_loop.ControlLoopWriter(
+ "CIM", [drivetrain.CIM()])
- if argv[5][-3:] == '.cc':
- cim_writer.Write(argv[6], argv[5])
- else:
- cim_writer.Write(argv[5], argv[6])
- return
+ cim_writer.Write(argv[3], argv[4])
+ return
vl_plot = []
vr_plot = []
@@ -436,16 +447,16 @@
vdrivetrain.left_gear = VelocityDrivetrain.LOW
vdrivetrain.right_gear = VelocityDrivetrain.LOW
- print "K is", vdrivetrain.CurrentDrivetrain().K
+ glog.debug('K is %s', str(vdrivetrain.CurrentDrivetrain().K))
if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
- print "Left is high"
+ glog.debug('Left is high')
else:
- print "Left is low"
+ glog.debug('Left is low')
if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
- print "Right is high"
+ glog.debug('Right is high')
else:
- print "Right is low"
+ glog.debug('Right is low')
for t in numpy.arange(0, 1.7, vdrivetrain.dt):
if t < 0.5:
@@ -469,22 +480,6 @@
else:
radius_plot.append(turn_velocity / fwd_velocity)
- cim_velocity_plot = []
- cim_voltage_plot = []
- cim_time = []
- cim = drivetrain.CIM()
- R = numpy.matrix([[300]])
- for t in numpy.arange(0, 0.5, cim.dt):
- U = numpy.clip(cim.K * (R - cim.X) + R / cim.Kv, cim.U_min, cim.U_max)
- cim.Update(U)
- cim_velocity_plot.append(cim.X[0, 0])
- cim_voltage_plot.append(U[0, 0] * 10)
- cim_time.append(t)
- pylab.plot(cim_time, cim_velocity_plot, label='cim spinup')
- pylab.plot(cim_time, cim_voltage_plot, label='cim voltage')
- pylab.legend()
- pylab.show()
-
# TODO(austin):
# Shifting compensation.
diff --git a/y2014_bot3/joystick_reader.cc b/y2014_bot3/joystick_reader.cc
index 6dfcbb4..86f78dc 100644
--- a/y2014_bot3/joystick_reader.cc
+++ b/y2014_bot3/joystick_reader.cc
@@ -11,11 +11,11 @@
#include "aos/common/time.h"
#include "frc971/queues/gyro.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
#include "y2014_bot3/autonomous/auto.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
#include "y2014_bot3/control_loops/rollers/rollers.q.h"
-using ::y2014_bot3::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain_queue;
using ::y2014_bot3::control_loops::rollers_queue;
using ::frc971::sensors::gyro_reading;
@@ -30,9 +30,12 @@
// Joystick & button addresses.
const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
-const ButtonLocation kShiftHigh(2, 3), kShiftLow(2, 1);
+const ButtonLocation kShiftHigh(2, 3), kShiftHigh2(2, 2), kShiftLow(2, 1);
const ButtonLocation kQuickTurn(1, 5);
+const ButtonLocation kTurn1(1, 7);
+const ButtonLocation kTurn2(1, 11);
+
const ButtonLocation kFrontRollersIn(3, 8);
const ButtonLocation kBackRollersIn(3, 7);
const ButtonLocation kFrontRollersOut(3, 6);
@@ -62,15 +65,33 @@
}
void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+ bool is_control_loop_driving = false;
+ static double left_goal = 0.0;
+ static double right_goal = 0.0;
const double wheel = -data.GetAxis(kSteeringWheel);
const double throttle = -data.GetAxis(kDriveThrottle);
+ if (data.PosEdge(kTurn1) || data.PosEdge(kTurn2)) {
+ drivetrain_queue.status.FetchLatest();
+ if (drivetrain_queue.status.get()) {
+ left_goal = drivetrain_queue.status->estimated_left_position;
+ right_goal = drivetrain_queue.status->estimated_right_position;
+ }
+ }
+ if (data.IsPressed(kTurn1) || data.IsPressed(kTurn2)) {
+ is_control_loop_driving = true;
+ }
+
if (!drivetrain_queue.goal.MakeWithBuilder()
.steering(wheel)
.throttle(throttle)
- .quickturn(data.IsPressed(kQuickTurn))
- .control_loop_driving(false)
.highgear(is_high_gear_)
+ .quickturn(data.IsPressed(kQuickTurn))
+ .control_loop_driving(is_control_loop_driving)
+ .left_goal(left_goal - wheel * 0.5 + throttle * 0.3)
+ .right_goal(right_goal + wheel * 0.5 + throttle * 0.3)
+ .left_velocity_goal(0)
+ .right_velocity_goal(0)
.Send()) {
LOG(WARNING, "sending stick values failed\n");
}
@@ -79,7 +100,7 @@
is_high_gear_ = false;
}
- if (data.PosEdge(kShiftHigh)) {
+ if (data.PosEdge(kShiftHigh) || data.PosEdge(kShiftHigh2)) {
is_high_gear_ = true;
}
}
diff --git a/y2014_bot3/wpilib/BUILD b/y2014_bot3/wpilib/BUILD
index 5f5319c..8af099f 100644
--- a/y2014_bot3/wpilib/BUILD
+++ b/y2014_bot3/wpilib/BUILD
@@ -10,7 +10,7 @@
'//aos/common:stl_mutex',
'//aos/common/logging',
'//third_party/allwpilib_2016:wpilib',
- '//y2014_bot3/control_loops/drivetrain:drivetrain_queue',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
'//aos/common/controls:control_loop',
'//aos/common/util:log_interval',
'//aos/common:time',
@@ -29,7 +29,7 @@
'//frc971/wpilib:pdp_fetcher',
'//frc971/wpilib:dma',
'//y2014_bot3/autonomous:auto_queue',
- '//y2014_bot3/control_loops/drivetrain:drivetrain_lib',
'//y2014_bot3/control_loops/rollers:rollers_lib',
+ '//y2014_bot3/control_loops/drivetrain:drivetrain_base',
],
)
diff --git a/y2014_bot3/wpilib/wpilib_interface.cc b/y2014_bot3/wpilib/wpilib_interface.cc
index e1e07a0..4abbfce 100644
--- a/y2014_bot3/wpilib/wpilib_interface.cc
+++ b/y2014_bot3/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
#include <unistd.h>
#include <inttypes.h>
+#include <chrono>
#include <thread>
#include <mutex>
#include <functional>
@@ -27,10 +28,10 @@
#include "aos/linux_code/init.h"
#include "aos/common/messages/robot_state.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2014_bot3/control_loops/drivetrain/drivetrain_base.h"
#include "y2014_bot3/control_loops/rollers/rollers.q.h"
#include "y2014_bot3/autonomous/auto.q.h"
-#include "y2014_bot3/control_loops/drivetrain/drivetrain.h"
#include "y2014_bot3/control_loops/rollers/rollers.h"
#include "frc971/wpilib/joystick_sender.h"
@@ -48,7 +49,7 @@
#endif
using ::aos::util::SimpleLogInterval;
-using ::y2014_bot3::control_loops::drivetrain_queue;
+using ::frc971::control_loops::drivetrain_queue;
using ::y2014_bot3::control_loops::rollers_queue;
using ::frc971::wpilib::BufferedPcm;
using ::frc971::wpilib::BufferedSolenoid;
@@ -61,13 +62,13 @@
double drivetrain_translate(int32_t in) {
return static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
- ::y2014_bot3::control_loops::kDrivetrainEncoderRatio *
+ ::y2014_bot3::control_loops::drivetrain::kDrivetrainEncoderRatio *
(4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
}
double drivetrain_velocity_translate(double in) {
return (1.0 / in) / 256.0 /*cpr*/ *
- ::y2014_bot3::control_loops::kDrivetrainEncoderRatio *
+ ::y2014_bot3::control_loops::drivetrain::kDrivetrainEncoderRatio *
(4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
}
@@ -97,8 +98,8 @@
&DriverStation::GetInstance();
#endif
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(4));
::aos::SetCurrentThreadRealtimePriority(40);
while (run_) {
@@ -154,7 +155,7 @@
public:
SolenoidWriter(const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm)
: pcm_(pcm),
- drivetrain_(".y2014_bot3.control_loops.drivetrain_queue.output"),
+ drivetrain_(".frc971.control_loops.drivetrain_queue.output"),
rollers_(".y2014_bot3.control_loops.rollers_queue.output") {}
void set_pressure_switch(::std::unique_ptr<DigitalInput> pressure_switch) {
@@ -185,8 +186,8 @@
::aos::SetCurrentThreadName("Solenoids");
::aos::SetCurrentThreadRealtimePriority(27);
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(1));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(1));
while (run_) {
{
@@ -249,7 +250,7 @@
::std::unique_ptr<DigitalInput> pressure_switch_;
::std::unique_ptr<Relay> compressor_relay_;
- ::aos::Queue<::y2014_bot3::control_loops::DrivetrainQueue::Output>
+ ::aos::Queue<::frc971::control_loops::DrivetrainQueue::Output>
drivetrain_;
::aos::Queue<::y2014_bot3::control_loops::RollersQueue::Output> rollers_;
@@ -269,11 +270,11 @@
private:
virtual void Read() override {
- ::y2014_bot3::control_loops::drivetrain_queue.output.FetchAnother();
+ ::frc971::control_loops::drivetrain_queue.output.FetchAnother();
}
virtual void Write() override {
- auto &queue = ::y2014_bot3::control_loops::drivetrain_queue.output;
+ auto &queue = ::frc971::control_loops::drivetrain_queue.output;
LOG_STRUCT(DEBUG, "will output", *queue);
left_drivetrain_talon_->Set(-queue->left_voltage / 12.0);
right_drivetrain_talon_->Set(queue->right_voltage / 12.0);
@@ -373,9 +374,9 @@
// Outputs
DrivetrainWriter drivetrain_writer;
drivetrain_writer.set_left_drivetrain_talon(
- ::std::unique_ptr<Talon>(new Talon(2)));
- drivetrain_writer.set_right_drivetrain_talon(
::std::unique_ptr<Talon>(new Talon(5)));
+ drivetrain_writer.set_right_drivetrain_talon(
+ ::std::unique_ptr<Talon>(new Talon(2)));
::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
RollersWriter rollers_writer;
diff --git a/y2015/wpilib/wpilib_interface.cc b/y2015/wpilib/wpilib_interface.cc
index 3130424..14ca146 100644
--- a/y2015/wpilib/wpilib_interface.cc
+++ b/y2015/wpilib/wpilib_interface.cc
@@ -3,9 +3,10 @@
#include <unistd.h>
#include <inttypes.h>
-#include <thread>
-#include <mutex>
+#include <chrono>
#include <functional>
+#include <mutex>
+#include <thread>
#include "Encoder.h"
#include "Talon.h"
@@ -241,8 +242,8 @@
wrist_encoder_.Start();
dma_synchronizer_->Start();
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(4));
::aos::SetCurrentThreadRealtimePriority(40);
while (run_) {
@@ -418,8 +419,8 @@
::aos::SetCurrentThreadName("Solenoids");
::aos::SetCurrentThreadRealtimePriority(27);
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(1));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(1));
while (run_) {
{
diff --git a/y2015_bot3/wpilib/wpilib_interface.cc b/y2015_bot3/wpilib/wpilib_interface.cc
index cb2acf1..bbfa91e 100644
--- a/y2015_bot3/wpilib/wpilib_interface.cc
+++ b/y2015_bot3/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
#include <unistd.h>
#include <inttypes.h>
+#include <chrono>
#include <thread>
#include <mutex>
#include <functional>
@@ -137,8 +138,8 @@
&DriverStation::GetInstance();
#endif
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(4));
::aos::SetCurrentThreadRealtimePriority(40);
while (run_) {
@@ -242,8 +243,8 @@
::aos::SetCurrentThreadName("Solenoids");
::aos::SetCurrentThreadRealtimePriority(27);
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(1));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(1));
while (run_) {
{
diff --git a/y2016/actors/autonomous_actor.cc b/y2016/actors/autonomous_actor.cc
index 199dda5..7b3fc60 100644
--- a/y2016/actors/autonomous_actor.cc
+++ b/y2016/actors/autonomous_actor.cc
@@ -2,6 +2,7 @@
#include <inttypes.h>
+#include <chrono>
#include <cmath>
#include "aos/common/util/phased_loop.h"
@@ -102,8 +103,8 @@
return;
}
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
// Poll the running bit and see if we should cancel.
phased_loop.SleepUntilNext();
@@ -116,8 +117,8 @@
constexpr double kDoNotTurnCare = 2.0;
bool AutonomousActor::WaitForDriveNear(double distance, double angle) {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
constexpr double kPositionTolerance = 0.02;
constexpr double kProfileTolerance = 0.001;
@@ -164,8 +165,8 @@
}
bool AutonomousActor::WaitForDriveProfileDone() {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
constexpr double kProfileTolerance = 0.001;
while (true) {
@@ -187,8 +188,8 @@
}
bool AutonomousActor::WaitForMaxBy(double angle) {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
double max_angle = -M_PI;
while (true) {
if (ShouldCancel()) {
@@ -211,8 +212,8 @@
}
bool AutonomousActor::WaitForAboveAngle(double angle) {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
if (ShouldCancel()) {
return false;
@@ -231,8 +232,8 @@
}
bool AutonomousActor::WaitForBelowAngle(double angle) {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
if (ShouldCancel()) {
return false;
@@ -276,8 +277,8 @@
}
bool AutonomousActor::WaitForDriveDone() {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
if (ShouldCancel()) {
@@ -397,8 +398,8 @@
LOG(ERROR, "Sending shooter goal failed.\n");
}
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
if (ShouldCancel()) return;
@@ -414,8 +415,8 @@
}
void AutonomousActor::WaitForShooterSpeed() {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
if (ShouldCancel()) return;
@@ -442,8 +443,8 @@
double last_angle = 0.0;
int ready_to_fire = 0;
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
::aos::time::Time end_time =
::aos::time::Time::Now() + align_duration;
while (end_time > ::aos::time::Time::Now()) {
@@ -632,8 +633,10 @@
void AutonomousActor::BackLongShotTwoBallFinish() {
LOG(INFO, "Expanding for back long shot\n");
- MoveSuperstructure(0.00, M_PI / 2.0 - 0.2, -0.625, {7.0, 40.0}, {4.0, 6.0},
- {10.0, 25.0}, false, 0.0);
+ MoveSuperstructure(
+ 0.00, M_PI / 2.0 - 0.2, -0.625 + 0.03, {7.0, 40.0},
+ {4.0, 6.0},
+ {10.0, 25.0}, false, 0.0);
}
void AutonomousActor::BackLongShot() {
@@ -783,8 +786,8 @@
}
void AutonomousActor::WaitForBallOrDriveDone() {
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
if (ShouldCancel()) {
return;
@@ -1164,8 +1167,8 @@
LOG(INFO, "Done %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (!ShouldCancel()) {
phased_loop.SleepUntilNext();
diff --git a/y2016/actors/vision_align_actor.cc b/y2016/actors/vision_align_actor.cc
index 00695f0..9491cd4 100644
--- a/y2016/actors/vision_align_actor.cc
+++ b/y2016/actors/vision_align_actor.cc
@@ -1,5 +1,6 @@
#include "y2016/actors/vision_align_actor.h"
+#include <chrono>
#include <functional>
#include <numeric>
@@ -28,8 +29,8 @@
const actors::VisionAlignActionParams & /*params*/) {
const double robot_radius =
control_loops::drivetrain::GetDrivetrainConfig().robot_radius;
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(5) / 2);
while (true) {
const int iterations = phased_loop.SleepUntilNext();
if (iterations != 1) {
diff --git a/y2016/constants.cc b/y2016/constants.cc
index 974a82d..5353d6e 100644
--- a/y2016/constants.cc
+++ b/y2016/constants.cc
@@ -81,8 +81,7 @@
5.0, // drivetrain max speed
// Intake
- {
- // Value to add to the pot reading for the intake.
+ {// Value to add to the pot reading for the intake.
-4.550531 + 150.40906362 * M_PI / 180.0 + 0.5098 - 0.0178 - 0.0725,
{Values::kZeroingSampleSize, Values::kIntakeEncoderIndexDifference,
// Location of an index pulse.
@@ -90,21 +89,19 @@
},
// Shoulder
- {
- // Value to add to the pot reading for the shoulder.
- -1.0 - 0.0822 + 0.06138835 * M_PI / 180.0 - 0.0323 - 0.1057 +
- 0.0035 + 0.0055 - 0.001 - 0.0103 + 0.0032 - 0.0755,
+ {// Value to add to the pot reading for the shoulder.
+ -2.86275657117,
{Values::kZeroingSampleSize, Values::kShoulderEncoderIndexDifference,
- 0.535359, 2.5},
+ 0.097312, 2.5},
},
// Wrist
- {
- // Value to add to the pot reading for the wrist.
+ {// Value to add to the pot reading for the wrist.
3.2390714288298668 + -0.06138835 * M_PI / 180.0 + 0.0078 - 0.0548 -
- 0.0167 + 0.002 - 0.0026 - 0.1040 - 0.0035 - 0.0012 + 0.0166 - 0.017 + 0.148 + 0.004,
+ 0.0167 + 0.002 - 0.0026 - 0.1040 - 0.0035 - 0.0012 + 0.0166 -
+ 0.017 + 0.148 + 0.004 + 0.024701 - 0.0741,
{Values::kZeroingSampleSize, Values::kWristEncoderIndexDifference,
- -0.354946, 2.5},
+ 0.000820, 2.5},
},
0.0,
@@ -116,10 +113,9 @@
5.0, // drivetrain max speed
// Intake
- {
- // Hard stop is 164.2067247 degrees.
- -4.2193 + (164.2067247 * M_PI / 180.0 + 0.02 - 0.0235) + 0.0549 -
- 0.104 + 0.019 - 0.938 + 0.660 - 0.002,
+ {// Hard stop is 160.0185751389329 degrees.
+ -4.2193 + (160.0185751389329 * M_PI / 180.0 + 0.02 - 0.0235) +
+ 0.0549 - 0.104 + 0.019 - 0.938 + 0.660 - 0.002 - 0.2081,
{Values::kZeroingSampleSize, Values::kIntakeEncoderIndexDifference,
0.332370, 1.3},
},
@@ -135,7 +131,8 @@
// Wrist
{
3.326328571170133 - 0.06138835 * M_PI / 180.0 - 0.177 + 0.0323 -
- 0.023 + 0.0488 + 0.0120 - 0.0005 - 0.0784 - 0.0010 - 0.080 + 0.1245,
+ 0.023 + 0.0488 + 0.0120 - 0.0005 - 0.0784 - 0.0010 - 0.080 +
+ 0.1245,
{Values::kZeroingSampleSize, Values::kWristEncoderIndexDifference,
-0.263227, 1.3},
},
diff --git a/y2016/dashboard/dashboard.cc b/y2016/dashboard/dashboard.cc
index bdfedb8..22a77fa 100644
--- a/y2016/dashboard/dashboard.cc
+++ b/y2016/dashboard/dashboard.cc
@@ -49,7 +49,7 @@
: cur_raw_data_("no data"),
sample_id_(0),
measure_index_(0),
- overflow_id_(20) {}
+ overflow_id_(1) {}
void DataCollector::RunIteration() {
::aos::MutexLocker locker(&mutex_);
@@ -183,26 +183,28 @@
// Note that we are ignoring the from_sample being sent to keep up with the
// live data without worrying about client lag.
- int32_t cur_sample = sample_id_ - 2;
+ int32_t cur_sample = sample_id_;
int32_t adjusted_index = GetIndex(cur_sample);
message << "$"; // Begin data packet.
// Make sure we are not out of range.
- if (static_cast<size_t>(adjusted_index) <
- sample_items_.at(0).datapoints.size()) {
- message << cur_sample << "%"
- << sample_items_.at(0)
- .datapoints.at(adjusted_index)
- .time.ToSeconds() << "%"; // Send time.
- // Add comma-separated list of data points.
- for (size_t cur_measure = 0; cur_measure < sample_items_.size();
- cur_measure++) {
- if (cur_measure > 0) {
- message << ",";
- }
- message << sample_items_.at(cur_measure)
+ if (sample_items_.size() > 0) {
+ if (static_cast<size_t>(adjusted_index) <
+ sample_items_.at(0).datapoints.size()) {
+ message << cur_sample << "%"
+ << sample_items_.at(0)
.datapoints.at(adjusted_index)
- .value;
+ .time.ToSeconds() << "%"; // Send time.
+ // Add comma-separated list of data points.
+ for (size_t cur_measure = 0; cur_measure < sample_items_.size();
+ cur_measure++) {
+ if (cur_measure > 0) {
+ message << ",";
+ }
+ message << sample_items_.at(cur_measure)
+ .datapoints.at(adjusted_index)
+ .value;
+ }
}
}
diff --git a/y2016/dashboard/www/index.html b/y2016/dashboard/www/index.html
index da5512f..3821b48 100644
--- a/y2016/dashboard/www/index.html
+++ b/y2016/dashboard/www/index.html
@@ -7,11 +7,11 @@
var escapable =
/[\x00-\x1f\ud800-\udfff\u200c-\u200f\u2028-\u202f\u2060-\u206f\ufff0-\uffff]/g;
var ws;
-var intervalTime = 50;
+var intervalTime = 100;
var selected = 0;
var reconnecting = false;
var lastSampleID = 0;
-var resetTimeout;
+var reconnectTimeout;
// Filter out junky JSON packets that will otherwise cause nasty decoding
// errors. These errors come as a result of incomplete packets, corrupted data,
@@ -145,12 +145,13 @@
}
function reconnect() {
+ clearTimeout(reconnectTimeout);
$('#message').text('Reconnecting...');
$('#dataTable').empty();
lastSampleID = 0;
reconnecting = true;
- setTimeout(function(){
+ reconnectTimeout = setTimeout(function(){
initSocketLoop()
}, 500);
}
diff --git a/y2016/plotting/responsive_plotter.js b/y2016/plotting/responsive_plotter.js
new file mode 100644
index 0000000..0840e1d
--- /dev/null
+++ b/y2016/plotting/responsive_plotter.js
@@ -0,0 +1,238 @@
+"use strict";
+
+// Create anonymous namespace to avoid leaking these functions.
+(function() {
+// Convenience function that fetches a file and extracts the array buffer.
+function fetch_ArrayBuffer(url) { // returns Promise<ArrayBuffer>
+ return fetch(url).then(function(val) { return val.arrayBuffer(); });
+}
+
+// Two dimensional vector.
+class Point2d {
+ constructor(x, y) {
+ this.x = x;
+ this.y = y;
+ }
+ sub(o) { return new Point2d(this.x - o.x, this.y - o.y); }
+ add(o) { return new Point2d(this.x + o.x, this.y + o.y); }
+};
+
+// Drag event object for updating a Point2d class by reference.
+class PointDrag {
+ constructor(point) { // point : Point2d
+ this.point = point;
+ }
+ doDrag(delta) {
+ this.point.x += delta.x;
+ this.point.y += delta.y;
+ }
+ doMouseUp(e) { return null; }
+}
+
+// Takes in a canvas and adds the ability to click and drag the offset point.
+// scaleX and scaleY are allowed to be locked or not-locked as the scroll events
+// must be handled by the user of this class.
+//
+// offset.x and offset.y are defined in reference to the model-scale, not the viewport.
+// Thus to move the viewport you need to use offset.x * scaleX, etc.
+//
+// scaleX and scaleY aren't automatically applied to the rendering context because
+// differing x and y scales mess up the line width rendering.
+class ClickDrag {
+ constructor(canvas) {
+ canvas.addEventListener('selectstart', function(e) { e.preventDefault(); return false; }, false);
+ canvas.addEventListener('mousemove', this.handleMouseMove.bind(this), true);
+ canvas.addEventListener('mousedown', this.handleMouseDown.bind(this), true);
+ canvas.addEventListener('mouseup', this.handleMouseUp.bind(this), true);
+ this.canvas = canvas;
+ this.dragger = null;
+ this.offset = new Point2d(0, 0);
+ this.scaleX = 1.0;
+ this.scaleY = 1.0;
+ this.old_point = null;
+ this.on_redraw = null;
+ }
+ translateContext(ctx) { // ctx : CanvasRenderingContext2D
+ ctx.translate(this.offset.x * this.scaleX, this.offset.y * this.scaleY);
+ }
+ handleMouseMove(e) { // e : MouseEvent
+ let pos = new Point2d(e.offsetX / this.scaleX, e.offsetY / this.scaleY);
+ if (this.old_point !== null && this.dragger !== null) {
+ this.dragger.doDrag(pos.sub(this.old_point));
+ if (this.on_redraw !== null) { this.on_redraw(); }
+ }
+ this.old_point = pos;
+ }
+ get width() { return this.canvas.width; }
+ handleMouseDown(e) { // e : MouseEvent
+ this.dragger = new PointDrag(this.offset);
+ }
+ handleMouseUp(e) { // e : MouseEvent
+ if (this.dragger === null) { return; }
+ if (this.dragger.doMouseUp !== undefined) {
+ this.dragger = this.dragger.doMouseUp(e);
+ if (this.on_redraw !== null) { this.on_redraw(); }
+ }
+ }
+ multiplyScale(evt, dx, dy) {
+ let x_cur = evt.offsetX / this.scaleX - this.offset.x;
+ let y_cur = evt.offsetY / this.scaleY - this.offset.y;
+ this.scaleX *= dx;
+ this.scaleY *= dy;
+ this.offset.x = evt.offsetX / this.scaleX - x_cur;
+ this.offset.y = evt.offsetY / this.scaleY - y_cur;
+ if (this.on_redraw !== null) { this.on_redraw(); }
+ }
+};
+
+// This represents a particular downsampling of a timeseries dataset.
+// For the base level, data = min = max.
+// This is required
+class MipMapLevel {
+ // All arrays should be the same size.
+ constructor(data, min, max, scale) { // data : Float32Array, min : Float32Array, max : Float32Array, scale : Integer
+ this.data = data;
+ this.min = min;
+ this.max = max;
+ this.scale = scale;
+ }
+ get length() { return this.data.length; }
+ // Uses box filter to downsample. Guassian may be an improvement.
+ downsample() {
+ let new_length = (this.data.length / 2) | 0;
+ let data = new Float32Array(new_length);
+ let min = new Float32Array(new_length);
+ let max = new Float32Array(new_length);
+ for (let i = 0; i < new_length; i++) {
+ let i1 = i * 2;
+ let i2 = i1 + 1
+ data[i] = (this.data[i1] + this.data[i2]) / 2.0;
+ min[i] = Math.min(this.min[i1], this.min[i2]);
+ max[i] = Math.max(this.max[i1], this.max[i2]);
+ }
+ return new MipMapLevel(data, min, max, this.scale * 2);
+ }
+ static makeBaseLevel(data) { // data : Float32Array
+ return new MipMapLevel(data, data, data, 1);
+ }
+ clipv(v) { // v : Numeric
+ return Math.min(Math.max(v|0, 0), this.length - 1);
+ }
+ draw(ctx, clickDrag) { // ctx : CanvasRenderingContext2D, clickDrag : ClickDrag
+ let scalex = clickDrag.scaleX * this.scale;
+ let scaley = clickDrag.scaleY;
+ let stx = -clickDrag.offset.x / this.scale;
+ let edx = stx + clickDrag.width / scalex;
+ let sti = this.clipv(stx - 2);
+ let edi = this.clipv(edx + 2);
+ ctx.beginPath();
+ ctx.fillStyle="#00ff00";
+ ctx.moveTo(sti * scalex, scaley * this.min[sti]);
+ for (let i = sti + 1; i <= edi; i++) {
+ ctx.lineTo(i * scalex, scaley * this.min[i]);
+ }
+ for (let i = edi; i >= sti; --i) {
+ ctx.lineTo(i * scalex, scaley * this.max[i]);
+ }
+ ctx.fill();
+ ctx.closePath();
+
+ ctx.beginPath();
+ ctx.strokeStyle="#008f00";
+ ctx.moveTo(sti * scalex, scaley * this.data[sti]);
+ for (let i = sti + 1; i <= edi; i++) {
+ ctx.lineTo(i * scalex, scaley * this.data[i]);
+ }
+ ctx.stroke();
+ ctx.closePath();
+ }
+};
+
+// This class represents all downsampled data levels.
+// This must only be used for descrite time-series data.
+class MipMapper {
+ constructor(samples) { // samples : Float32Array
+ this.levels = [];
+ let level = MipMapLevel.makeBaseLevel(samples);
+ this.levels.push(level);
+ while (level.length > 2) {
+ level = level.downsample();
+ this.levels.push(level);
+ }
+ }
+ // Find the level such that samples are spaced at most 2 pixels apart
+ getLevel(scale) { // scale : Float
+ let level = this.levels[0];
+ for (let i = 0; i < this.levels.length; ++i) {
+ // Someone who understands nyquist could probably improve this.
+ if (this.levels[i].scale * scale <= 4.0) {
+ level = this.levels[i];
+ }
+ }
+ return level;
+ }
+}
+
+// Custom HTML element for x-responsive-plotter.
+// This should be the main entry-point for this code.
+class ResponsivePlotter extends HTMLElement {
+ createdCallback() {
+ this.data = null;
+ this.canvas = document.createElement("canvas");
+ this.canvas.style["background"] = "inherit";
+ this.canvas.addEventListener("mousewheel", this.doScroll.bind(this), false);
+ this.clickDrag = new ClickDrag(this.canvas);
+ this.clickDrag.on_redraw = this.doRedraw.bind(this);
+ this.clickDrag.offset.y = 160; //320;
+ this.updateInnerData();
+ this.appendChild(this.canvas);
+ }
+ doScroll(e) {
+ let factor = (e.wheelDelta < 0) ? 0.9 : 1.1;
+ this.clickDrag.multiplyScale(e, e.shiftKey ? 1.0 : factor, e.shiftKey ? factor : 1.0);
+ e.preventDefault();
+ }
+ doRedraw() {
+ this.redraw();
+ }
+ updateInnerData() {
+ this.canvas.width = this.getAttribute("width") || 640;
+ this.canvas.height = this.getAttribute("height") || 480;
+ fetch_ArrayBuffer(this.getAttribute("data")).then(this.dataUpdated.bind(this));
+ this.redraw();
+ }
+ attributeChangedCallback(attrName, oldVal, newVal) {
+ if (attrName == "width") {
+ this.canvas.width = this.getAttribute("width") || 640;
+ this.redraw();
+ } else if (attrName == "height") {
+ this.canvas.width = this.getAttribute("height") || 480;
+ this.redraw();
+ } else if (attrName == "data") {
+ // Should this clear out the canvas if a different url is selected?
+ // Well it does.
+ this.data = null;
+ fetch_ArrayBuffer(this.getAttribute("data")).then(this.dataUpdated.bind(this));
+ }
+ }
+ dataUpdated(data) { // data : ArrayBuffer
+ this.data = new MipMapper(new Float32Array(data));
+ this.redraw();
+ }
+ redraw() {
+ let ctx = this.canvas.getContext('2d');
+ ctx.clearRect(0, 0, this.canvas.width, this.canvas.height);
+ ctx.save();
+ this.clickDrag.translateContext(ctx);
+ if (this.data !== null) {
+ let level = this.data.getLevel(this.clickDrag.scaleX);
+ level.draw(ctx, this.clickDrag);
+ }
+ ctx.restore();
+ }
+};
+
+
+// TODO(parker): This is chrome-specific v0 version of this switch to v1 when available.
+document.registerElement('x-responsive-plotter', ResponsivePlotter);
+})();
diff --git a/y2016/plotting/test.html b/y2016/plotting/test.html
new file mode 100644
index 0000000..df278b0
--- /dev/null
+++ b/y2016/plotting/test.html
@@ -0,0 +1,12 @@
+<!DOCTYPE html>
+<html>
+ <head>
+ <meta charset="UTF-8">
+ <script src="/responsive_plotter.js" type="text/javascript"></script>
+ </head>
+
+ <body style=>
+ <x-responsive-plotter width=800 data="/test_data" style="background: lightblue;">
+ </x-responsive-plotter>
+ </body>
+</html>
diff --git a/y2016/plotting/test.rb b/y2016/plotting/test.rb
new file mode 100644
index 0000000..9f2f58a
--- /dev/null
+++ b/y2016/plotting/test.rb
@@ -0,0 +1,29 @@
+require "sinatra"
+
+# Must use sinatra server for this because fetch() in javascript
+# cannot load from the filesystem.
+get '/test.html' do
+ File.read("./test.html")
+end
+
+get '/responsive_plotter.js' do
+ content_type 'text/javascript'
+ File.read("./responsive_plotter.js")
+end
+
+get '/test_data' do
+ content_type 'binary/octet-stream'
+ data = ""
+ # Use ./test_data if it exists. Otherwise random data.
+ if (File.exists?("./test_data"))
+ data = File.read("./test_data")
+ else
+ 1000.times do
+ data += (1024.times.collect do |i|
+ (rand() * 480 - 160)
+ end.pack("F*"))
+ end
+ end
+ data
+end
+
diff --git a/y2016/wpilib/wpilib_interface.cc b/y2016/wpilib/wpilib_interface.cc
index acf820f..d7fc261 100644
--- a/y2016/wpilib/wpilib_interface.cc
+++ b/y2016/wpilib/wpilib_interface.cc
@@ -3,6 +3,7 @@
#include <unistd.h>
#include <inttypes.h>
+#include <chrono>
#include <thread>
#include <mutex>
#include <functional>
@@ -282,8 +283,8 @@
dma_synchronizer_->Start();
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(4));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(5),
+ ::std::chrono::milliseconds(4));
::aos::SetCurrentThreadRealtimePriority(40);
while (run_) {
@@ -472,8 +473,8 @@
::aos::SetCurrentThreadName("Solenoids");
::aos::SetCurrentThreadRealtimePriority(27);
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
- ::aos::time::Time::InMS(1));
+ ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
+ ::std::chrono::milliseconds(1));
while (run_) {
{
diff --git a/y2016_bot3/BUILD b/y2016_bot3/BUILD
new file mode 100644
index 0000000..1d89c1a
--- /dev/null
+++ b/y2016_bot3/BUILD
@@ -0,0 +1,53 @@
+load('/aos/downloader/downloader', 'aos_downloader')
+
+cc_binary(
+ name = 'joystick_reader',
+ srcs = [
+ 'joystick_reader.cc',
+ ],
+ deps = [
+ '//aos/common/actions:action_lib',
+ '//aos/common/logging',
+ '//aos/common/util:log_interval',
+ '//aos/common:time',
+ '//aos/input:joystick_input',
+ '//aos/linux_code:init',
+ '//frc971/autonomous:auto_queue',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
+ '//frc971/queues:gyro',
+ '//y2016_bot3/actors:autonomous_action_lib',
+ '//y2016_bot3/control_loops/intake:intake_lib',
+ '//y2016_bot3/control_loops/intake:intake_queue',
+ '//y2016_bot3/queues:ball_detector',
+ ],
+)
+
+aos_downloader(
+ name = 'download',
+ start_srcs = [
+ ':joystick_reader',
+ '//aos:prime_start_binaries',
+ '//y2016_bot3/control_loops/drivetrain:drivetrain',
+ '//y2016_bot3/control_loops/intake:intake',
+ '//y2016_bot3/actors:autonomous_action',
+ '//y2016_bot3/wpilib:wpilib_interface',
+ ],
+ srcs = [
+ '//aos:prime_binaries',
+ ],
+)
+
+aos_downloader(
+ name = 'download_stripped',
+ start_srcs = [
+ ':joystick_reader.stripped',
+ '//aos:prime_start_binaries_stripped',
+ '//y2016_bot3/control_loops/drivetrain:drivetrain.stripped',
+ '//y2016_bot3/control_loops/intake:intake.stripped',
+ '//y2016_bot3/actors:autonomous_action.stripped',
+ '//y2016_bot3/wpilib:wpilib_interface.stripped',
+ ],
+ srcs = [
+ '//aos:prime_binaries_stripped',
+ ],
+)
diff --git a/y2016_bot3/actors/BUILD b/y2016_bot3/actors/BUILD
new file mode 100644
index 0000000..6453f13
--- /dev/null
+++ b/y2016_bot3/actors/BUILD
@@ -0,0 +1,102 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+filegroup(
+ name = 'binaries',
+ srcs = [
+ ':drivetrain_action',
+ ':autonomous_action',
+ ],
+)
+
+queue_library(
+ name = 'drivetrain_action_queue',
+ srcs = [
+ 'drivetrain_action.q',
+ ],
+ deps = [
+ '//aos/common/actions:action_queue',
+ ],
+)
+
+cc_library(
+ name = 'drivetrain_action_lib',
+ srcs = [
+ 'drivetrain_actor.cc',
+ ],
+ hdrs = [
+ 'drivetrain_actor.h',
+ ],
+ deps = [
+ ':drivetrain_action_queue',
+ '//aos/common:time',
+ '//aos/common:math',
+ '//aos/common/util:phased_loop',
+ '//aos/common/logging',
+ '//aos/common/actions:action_lib',
+ '//aos/common/logging:queue_logging',
+ '//aos/common/util:trapezoid_profile',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
+ '//frc971/control_loops:state_feedback_loop',
+ '//third_party/eigen',
+ '//y2016_bot3/control_loops/intake:intake_lib',
+ '//y2016_bot3/control_loops/drivetrain:drivetrain_base',
+ '//y2016_bot3/control_loops/drivetrain:polydrivetrain_plants',
+ ],
+)
+
+cc_binary(
+ name = 'drivetrain_action',
+ srcs = [
+ 'drivetrain_actor_main.cc',
+ ],
+ deps = [
+ ':drivetrain_action_lib',
+ ':drivetrain_action_queue',
+ '//aos/linux_code:init',
+ ],
+)
+
+queue_library(
+ name = 'autonomous_action_queue',
+ srcs = [
+ 'autonomous_action.q',
+ ],
+ deps = [
+ '//aos/common/actions:action_queue',
+ ],
+)
+
+cc_library(
+ name = 'autonomous_action_lib',
+ srcs = [
+ 'autonomous_actor.cc',
+ ],
+ hdrs = [
+ 'autonomous_actor.h',
+ ],
+ deps = [
+ ':autonomous_action_queue',
+ '//aos/common/util:phased_loop',
+ '//aos/common/logging',
+ '//aos/common/actions:action_lib',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
+ '//y2016_bot3/queues:ball_detector',
+ '//y2016_bot3/control_loops/intake:intake_queue',
+ '//y2016_bot3/control_loops/drivetrain:drivetrain_base',
+ '//y2016_bot3/queues:profile_params',
+ ],
+)
+
+cc_binary(
+ name = 'autonomous_action',
+ srcs = [
+ 'autonomous_actor_main.cc',
+ ],
+ deps = [
+ ':autonomous_action_lib',
+ ':autonomous_action_queue',
+ '//aos/linux_code:init',
+ ],
+)
diff --git a/y2016_bot3/actors/autonomous_action.q b/y2016_bot3/actors/autonomous_action.q
new file mode 100644
index 0000000..37e4866
--- /dev/null
+++ b/y2016_bot3/actors/autonomous_action.q
@@ -0,0 +1,29 @@
+package y2016_bot3.actors;
+
+import "aos/common/actions/actions.q";
+
+message AutonomousMode {
+ // Mode read from the mode setting sensors.
+ int32_t mode;
+};
+
+queue AutonomousMode auto_mode;
+
+struct AutonomousActionParams {
+ // The mode from the sensors when auto starts.
+ int32_t mode;
+};
+
+queue_group AutonomousActionQueueGroup {
+ implements aos.common.actions.ActionQueueGroup;
+
+ message Goal {
+ uint32_t run;
+ AutonomousActionParams params;
+ };
+
+ queue Goal goal;
+ queue aos.common.actions.Status status;
+};
+
+queue_group AutonomousActionQueueGroup autonomous_action;
diff --git a/y2016_bot3/actors/autonomous_actor.cc b/y2016_bot3/actors/autonomous_actor.cc
new file mode 100644
index 0000000..d6263a7
--- /dev/null
+++ b/y2016_bot3/actors/autonomous_actor.cc
@@ -0,0 +1,358 @@
+#include "y2016_bot3/actors/autonomous_actor.h"
+
+#include <inttypes.h>
+
+#include <cmath>
+
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/logging/logging.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_base.h"
+#include "y2016_bot3/control_loops/intake/intake.q.h"
+#include "y2016_bot3/actors/autonomous_action.q.h"
+#include "y2016_bot3/queues/ball_detector.q.h"
+
+namespace y2016_bot3 {
+namespace actors {
+using ::frc971::control_loops::drivetrain_queue;
+
+namespace {
+const ProfileParameters kLowBarDrive = {1.3, 2.5};
+} // namespace
+
+AutonomousActor::AutonomousActor(actors::AutonomousActionQueueGroup *s)
+ : aos::common::actions::ActorBase<actors::AutonomousActionQueueGroup>(s),
+ dt_config_(control_loops::drivetrain::GetDrivetrainConfig()),
+ initial_drivetrain_({0.0, 0.0}) {}
+
+void AutonomousActor::ResetDrivetrain() {
+ LOG(INFO, "resetting the drivetrain\n");
+ drivetrain_queue.goal.MakeWithBuilder()
+ .control_loop_driving(false)
+ .steering(0.0)
+ .throttle(0.0)
+ .left_goal(initial_drivetrain_.left)
+ .left_velocity_goal(0)
+ .right_goal(initial_drivetrain_.right)
+ .right_velocity_goal(0)
+ .Send();
+}
+
+void AutonomousActor::StartDrive(double distance, double angle,
+ ProfileParameters linear) {
+ {
+ LOG(INFO, "Driving distance %f, angle %f\n", distance, angle);
+ {
+ const double dangle = angle * dt_config_.robot_radius;
+ initial_drivetrain_.left += distance - dangle;
+ initial_drivetrain_.right += distance + dangle;
+ }
+
+ auto drivetrain_message = drivetrain_queue.goal.MakeMessage();
+ drivetrain_message->control_loop_driving = true;
+ drivetrain_message->steering = 0.0;
+ drivetrain_message->throttle = 0.0;
+ drivetrain_message->left_goal = initial_drivetrain_.left;
+ drivetrain_message->left_velocity_goal = 0;
+ drivetrain_message->right_goal = initial_drivetrain_.right;
+ drivetrain_message->right_velocity_goal = 0;
+ drivetrain_message->linear = linear;
+
+ LOG_STRUCT(DEBUG, "drivetrain_goal", *drivetrain_message);
+
+ drivetrain_message.Send();
+ }
+}
+
+void AutonomousActor::InitializeEncoders() {
+ drivetrain_queue.status.FetchAnother();
+ initial_drivetrain_.left = drivetrain_queue.status->estimated_left_position;
+ initial_drivetrain_.right = drivetrain_queue.status->estimated_right_position;
+}
+
+void AutonomousActor::WaitUntilDoneOrCanceled(
+ ::std::unique_ptr<aos::common::actions::Action> action) {
+ if (!action) {
+ LOG(ERROR, "No action, not waiting\n");
+ return;
+ }
+
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ while (true) {
+ // Poll the running bit and see if we should cancel.
+ phased_loop.SleepUntilNext();
+ if (!action->Running() || ShouldCancel()) {
+ return;
+ }
+ }
+}
+
+bool AutonomousActor::WaitForDriveNear(double distance, double angle) {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ constexpr double kPositionTolerance = 0.02;
+ constexpr double kProfileTolerance = 0.001;
+
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (drivetrain_queue.status.get()) {
+ const double left_profile_error =
+ (initial_drivetrain_.left -
+ drivetrain_queue.status->profiled_left_position_goal);
+ const double right_profile_error =
+ (initial_drivetrain_.right -
+ drivetrain_queue.status->profiled_right_position_goal);
+
+ const double left_error =
+ (initial_drivetrain_.left -
+ drivetrain_queue.status->estimated_left_position);
+ const double right_error =
+ (initial_drivetrain_.right -
+ drivetrain_queue.status->estimated_right_position);
+
+ const double profile_distance_to_go =
+ (left_profile_error + right_profile_error) / 2.0;
+ const double profile_angle_to_go =
+ (right_profile_error - left_profile_error) /
+ (dt_config_.robot_radius * 2.0);
+
+ const double distance_to_go = (left_error + right_error) / 2.0;
+ const double angle_to_go =
+ (right_error - left_error) / (dt_config_.robot_radius * 2.0);
+
+ if (::std::abs(profile_distance_to_go) < distance + kProfileTolerance &&
+ ::std::abs(profile_angle_to_go) < angle + kProfileTolerance &&
+ ::std::abs(distance_to_go) < distance + kPositionTolerance &&
+ ::std::abs(angle_to_go) < angle + kPositionTolerance) {
+ LOG(INFO, "Closer than %f distance, %f angle\n", distance, angle);
+ return true;
+ }
+ }
+ }
+}
+
+bool AutonomousActor::WaitForDriveProfileDone() {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ constexpr double kProfileTolerance = 0.001;
+
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (drivetrain_queue.status.get()) {
+ if (::std::abs(drivetrain_queue.status->profiled_left_position_goal -
+ initial_drivetrain_.left) < kProfileTolerance &&
+ ::std::abs(drivetrain_queue.status->profiled_right_position_goal -
+ initial_drivetrain_.right) < kProfileTolerance) {
+ LOG(INFO, "Finished drive\n");
+ return true;
+ }
+ }
+ }
+}
+
+bool AutonomousActor::IsDriveDone() {
+ constexpr double kPositionTolerance = 0.02;
+ constexpr double kVelocityTolerance = 0.10;
+ constexpr double kProfileTolerance = 0.001;
+
+ if (drivetrain_queue.status.get()) {
+ if (::std::abs(drivetrain_queue.status->profiled_left_position_goal -
+ initial_drivetrain_.left) < kProfileTolerance &&
+ ::std::abs(drivetrain_queue.status->profiled_right_position_goal -
+ initial_drivetrain_.right) < kProfileTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_left_position -
+ initial_drivetrain_.left) < kPositionTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_right_position -
+ initial_drivetrain_.right) < kPositionTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_left_velocity) <
+ kVelocityTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_right_velocity) <
+ kVelocityTolerance) {
+ LOG(INFO, "Finished drive\n");
+ return true;
+ }
+ }
+ return false;
+}
+
+bool AutonomousActor::WaitForDriveDone() {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return true;
+ }
+ }
+}
+
+void AutonomousActor::MoveIntake(double intake_goal,
+ const ProfileParameters intake_params,
+ bool traverse_up, double roller_power) {
+
+ auto new_intake_goal =
+ ::y2016_bot3::control_loops::intake_queue.goal.MakeMessage();
+
+ new_intake_goal->angle_intake = intake_goal;
+
+ new_intake_goal->max_angular_velocity_intake =
+ intake_params.max_velocity;
+
+ new_intake_goal->max_angular_acceleration_intake =
+ intake_params.max_acceleration;
+
+ new_intake_goal->voltage_top_rollers = roller_power;
+ new_intake_goal->voltage_bottom_rollers = roller_power;
+
+ new_intake_goal->traverse_unlatched = true;
+ new_intake_goal->traverse_down = !traverse_up;
+
+ if (!new_intake_goal.Send()) {
+ LOG(ERROR, "Sending intake goal failed.\n");
+ }
+}
+
+bool AutonomousActor::IntakeDone() {
+ control_loops::intake_queue.status.FetchAnother();
+
+ constexpr double kProfileError = 1e-5;
+ constexpr double kEpsilon = 0.15;
+
+ if (control_loops::intake_queue.status->state < 12 ||
+ control_loops::intake_queue.status->state == 16) {
+ LOG(ERROR, "Intake no longer running, aborting action\n");
+ return true;
+ }
+
+ if (::std::abs(control_loops::intake_queue.status->intake.goal_angle -
+ intake_goal_.intake) < kProfileError &&
+ ::std::abs(control_loops::intake_queue.status->intake
+ .goal_angular_velocity) < kProfileError) {
+ LOG(DEBUG, "Profile done.\n");
+ if (::std::abs(control_loops::intake_queue.status->intake.angle -
+ intake_goal_.intake) < kEpsilon &&
+ ::std::abs(control_loops::intake_queue.status->intake
+ .angular_velocity) < kEpsilon) {
+ LOG(INFO, "Near goal, done.\n");
+ return true;
+ }
+ }
+ return false;
+}
+
+void AutonomousActor::WaitForIntake() {
+ while (true) {
+ if (ShouldCancel()) return;
+ if (IntakeDone()) return;
+ }
+}
+
+void AutonomousActor::LowBarDrive() {
+ StartDrive(-5.5, 0.0, kLowBarDrive);
+
+ if (!WaitForDriveNear(5.3, 0.0)) return;
+
+ if (!WaitForDriveNear(5.0, 0.0)) return;
+
+ StartDrive(0.0, 0.0, kLowBarDrive);
+
+ if (!WaitForDriveNear(3.0, 0.0)) return;
+
+ StartDrive(0.0, 0.0, kLowBarDrive);
+
+ if (!WaitForDriveNear(1.0, 0.0)) return;
+
+ StartDrive(0, -M_PI / 4.0 - 0.2, kLowBarDrive);
+}
+
+void AutonomousActor::WaitForBallOrDriveDone() {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ while (true) {
+ if (ShouldCancel()) {
+ return;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return;
+ }
+
+ ::y2016_bot3::sensors::ball_detector.FetchLatest();
+ if (::y2016_bot3::sensors::ball_detector.get()) {
+ const bool ball_detected =
+ ::y2016_bot3::sensors::ball_detector->voltage > 2.5;
+ if (ball_detected) {
+ return;
+ }
+ }
+ }
+}
+
+void AutonomousActor::WaitForBall() {
+ while (true) {
+ ::y2016_bot3::sensors::ball_detector.FetchAnother();
+ if (::y2016_bot3::sensors::ball_detector.get()) {
+ const bool ball_detected =
+ ::y2016_bot3::sensors::ball_detector->voltage > 2.5;
+ if (ball_detected) {
+ return;
+ }
+ if (ShouldCancel()) return;
+ }
+ }
+}
+
+bool AutonomousActor::RunAction(const actors::AutonomousActionParams ¶ms) {
+ aos::time::Time start_time = aos::time::Time::Now();
+ LOG(INFO, "Starting autonomous action with mode %" PRId32 "\n", params.mode);
+
+ InitializeEncoders();
+ ResetDrivetrain();
+
+ switch (params.mode) {
+ case 0:
+ default:
+ // TODO: Write auto code
+ LOG(ERROR, "Uhh... someone implement this please :)");
+ break;
+ }
+
+ if (!WaitForDriveDone()) return true;
+
+ LOG(INFO, "Done %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
+
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+
+ while (!ShouldCancel()) {
+ phased_loop.SleepUntilNext();
+ }
+ LOG(DEBUG, "Done running\n");
+
+ return true;
+}
+
+::std::unique_ptr<AutonomousAction> MakeAutonomousAction(
+ const ::y2016_bot3::actors::AutonomousActionParams ¶ms) {
+ return ::std::unique_ptr<AutonomousAction>(
+ new AutonomousAction(&::y2016_bot3::actors::autonomous_action, params));
+}
+
+} // namespace actors
+} // namespace y2016_bot3
diff --git a/y2016_bot3/actors/autonomous_actor.h b/y2016_bot3/actors/autonomous_actor.h
new file mode 100644
index 0000000..607e833
--- /dev/null
+++ b/y2016_bot3/actors/autonomous_actor.h
@@ -0,0 +1,90 @@
+#ifndef Y2016_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
+#define Y2016_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
+
+#include <memory>
+
+#include "aos/common/actions/actor.h"
+#include "aos/common/actions/actions.h"
+
+#include "y2016_bot3/actors/autonomous_action.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2016_bot3 {
+namespace actors {
+using ::frc971::ProfileParameters;
+
+class AutonomousActor
+ : public ::aos::common::actions::ActorBase<AutonomousActionQueueGroup> {
+ public:
+ explicit AutonomousActor(AutonomousActionQueueGroup *s);
+
+ bool RunAction(const actors::AutonomousActionParams ¶ms) override;
+
+ private:
+ void ResetDrivetrain();
+ void InitializeEncoders();
+ void WaitUntilDoneOrCanceled(::std::unique_ptr<aos::common::actions::Action>
+ action);
+ void StartDrive(double distance, double angle,
+ ::frc971::ProfileParameters linear);
+ // Waits for the drive motion to finish. Returns true if it succeeded, and
+ // false if it cancels.
+ bool WaitForDriveDone();
+ void WaitForBallOrDriveDone();
+
+ void StealAndMoveOverBy(double distance);
+
+ // Returns true if the drive has finished.
+ bool IsDriveDone();
+
+ // Waits until the profile and distance is within distance and angle of the
+ // goal. Returns true on success, and false when canceled.
+ bool WaitForDriveNear(double distance, double angle);
+
+ const ::frc971::control_loops::drivetrain::DrivetrainConfig dt_config_;
+
+ // Initial drivetrain positions.
+ struct InitialDrivetrain {
+ double left;
+ double right;
+ };
+ InitialDrivetrain initial_drivetrain_;
+
+ // Internal struct holding superstructure goals sent by autonomous to the
+ // loop.
+ struct IntakeGoal {
+ double intake;
+ };
+ IntakeGoal intake_goal_;
+
+ void MoveIntake(double intake, const ProfileParameters intake_params,
+ bool traverse_up, double roller_power);
+ void WaitForIntakeProfile();
+ void WaitForIntakeLow();
+ void WaitForIntake();
+ bool IntakeDone();
+ bool WaitForDriveProfileDone();
+
+ void WaitForBall();
+
+ void LowBarDrive();
+ // Drive to the middle spot over the middle position. Designed for the rock
+ // wall, rough terain, or ramparts.
+ void MiddleDrive();
+
+ void OneFromMiddleDrive(bool left);
+ void TwoFromMiddleDrive();
+};
+
+typedef ::aos::common::actions::TypedAction<AutonomousActionQueueGroup>
+ AutonomousAction;
+
+// Makes a new AutonomousActor action.
+::std::unique_ptr<AutonomousAction> MakeAutonomousAction(
+ const ::y2016_bot3::actors::AutonomousActionParams ¶ms);
+
+} // namespace actors
+} // namespace y2016_bot3
+
+#endif // Y2016_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2016_bot3/actors/autonomous_actor_main.cc b/y2016_bot3/actors/autonomous_actor_main.cc
new file mode 100644
index 0000000..43cbbe8
--- /dev/null
+++ b/y2016_bot3/actors/autonomous_actor_main.cc
@@ -0,0 +1,18 @@
+#include <stdio.h>
+
+#include "aos/linux_code/init.h"
+#include "y2016_bot3/actors/autonomous_action.q.h"
+#include "y2016_bot3/actors/autonomous_actor.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char * /*argv*/ []) {
+ ::aos::Init(-1);
+
+ ::y2016_bot3::actors::AutonomousActor autonomous(
+ &::y2016_bot3::actors::autonomous_action);
+ autonomous.Run();
+
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2016_bot3/actors/drivetrain_action.q b/y2016_bot3/actors/drivetrain_action.q
new file mode 100644
index 0000000..7775cad
--- /dev/null
+++ b/y2016_bot3/actors/drivetrain_action.q
@@ -0,0 +1,29 @@
+package y2016_bot3.actors;
+
+import "aos/common/actions/actions.q";
+
+// Parameters to send with start.
+struct DrivetrainActionParams {
+ double left_initial_position;
+ double right_initial_position;
+ double y_offset;
+ double theta_offset;
+ double maximum_velocity;
+ double maximum_acceleration;
+ double maximum_turn_velocity;
+ double maximum_turn_acceleration;
+};
+
+queue_group DrivetrainActionQueueGroup {
+ implements aos.common.actions.ActionQueueGroup;
+
+ message Goal {
+ uint32_t run;
+ DrivetrainActionParams params;
+ };
+
+ queue Goal goal;
+ queue aos.common.actions.Status status;
+};
+
+queue_group DrivetrainActionQueueGroup drivetrain_action;
diff --git a/y2016_bot3/actors/drivetrain_actor.cc b/y2016_bot3/actors/drivetrain_actor.cc
new file mode 100644
index 0000000..686c50f
--- /dev/null
+++ b/y2016_bot3/actors/drivetrain_actor.cc
@@ -0,0 +1,181 @@
+#include "y2016_bot3/actors/drivetrain_actor.h"
+
+#include <functional>
+#include <numeric>
+
+#include <Eigen/Dense>
+
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/util/trapezoid_profile.h"
+#include "aos/common/commonmath.h"
+#include "aos/common/time.h"
+
+#include "y2016_bot3/actors/drivetrain_actor.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+
+namespace y2016_bot3 {
+namespace actors {
+
+DrivetrainActor::DrivetrainActor(actors::DrivetrainActionQueueGroup *s)
+ : aos::common::actions::ActorBase<actors::DrivetrainActionQueueGroup>(s),
+ loop_(::y2016_bot3::control_loops::drivetrain::MakeDrivetrainLoop()) {
+ loop_.set_controller_index(3);
+}
+
+bool DrivetrainActor::RunAction(const actors::DrivetrainActionParams ¶ms) {
+ static const auto K = loop_.K();
+
+ const double yoffset = params.y_offset;
+ const double turn_offset =
+ params.theta_offset * control_loops::drivetrain::kRobotRadius;
+ LOG(INFO, "Going to move %f and turn %f\n", yoffset, turn_offset);
+
+ // Measured conversion to get the distance right.
+ ::aos::util::TrapezoidProfile profile(::aos::time::Time::InMS(5));
+ ::aos::util::TrapezoidProfile turn_profile(::aos::time::Time::InMS(5));
+ const double goal_velocity = 0.0;
+ const double epsilon = 0.01;
+ ::Eigen::Matrix<double, 2, 1> left_goal_state, right_goal_state;
+
+ profile.set_maximum_acceleration(params.maximum_acceleration);
+ profile.set_maximum_velocity(params.maximum_velocity);
+ turn_profile.set_maximum_acceleration(
+ params.maximum_turn_acceleration *
+ control_loops::drivetrain::kRobotRadius);
+ turn_profile.set_maximum_velocity(params.maximum_turn_velocity *
+ control_loops::drivetrain::kRobotRadius);
+
+ while (true) {
+ ::aos::time::PhasedLoopXMS(5, 2500);
+
+ ::frc971::control_loops::drivetrain_queue.status.FetchLatest();
+ if (::frc971::control_loops::drivetrain_queue.status.get()) {
+ const auto &status = *::frc971::control_loops::drivetrain_queue.status;
+ if (::std::abs(status.uncapped_left_voltage -
+ status.uncapped_right_voltage) > 24) {
+ LOG(DEBUG, "spinning in place\n");
+ // They're more than 24V apart, so stop moving forwards and let it deal
+ // with spinning first.
+ profile.SetGoal(
+ (status.estimated_left_position + status.estimated_right_position -
+ params.left_initial_position - params.right_initial_position) /
+ 2.0);
+ } else {
+ static const double divisor = K(0, 0) + K(0, 2);
+ double dx_left, dx_right;
+
+ if (status.uncapped_left_voltage > 12.0) {
+ dx_left = (status.uncapped_left_voltage - 12.0) / divisor;
+ } else if (status.uncapped_left_voltage < -12.0) {
+ dx_left = (status.uncapped_left_voltage + 12.0) / divisor;
+ } else {
+ dx_left = 0;
+ }
+
+ if (status.uncapped_right_voltage > 12.0) {
+ dx_right = (status.uncapped_right_voltage - 12.0) / divisor;
+ } else if (status.uncapped_right_voltage < -12.0) {
+ dx_right = (status.uncapped_right_voltage + 12.0) / divisor;
+ } else {
+ dx_right = 0;
+ }
+
+ double dx;
+
+ if (dx_left == 0 && dx_right == 0) {
+ dx = 0;
+ } else if (dx_left != 0 && dx_right != 0 &&
+ ::aos::sign(dx_left) != ::aos::sign(dx_right)) {
+ // Both saturating in opposite directions. Don't do anything.
+ LOG(DEBUG, "Saturating opposite ways, not adjusting\n");
+ dx = 0;
+ } else if (::std::abs(dx_left) > ::std::abs(dx_right)) {
+ dx = dx_left;
+ } else {
+ dx = dx_right;
+ }
+
+ if (dx != 0) {
+ LOG(DEBUG, "adjusting goal by %f\n", dx);
+ profile.MoveGoal(-dx);
+ }
+ }
+ } else {
+ // If we ever get here, that's bad and we should just give up
+ LOG(ERROR, "no drivetrain status!\n");
+ return false;
+ }
+
+ const auto drive_profile_goal_state =
+ profile.Update(yoffset, goal_velocity);
+ const auto turn_profile_goal_state = turn_profile.Update(turn_offset, 0.0);
+ left_goal_state = drive_profile_goal_state - turn_profile_goal_state;
+ right_goal_state = drive_profile_goal_state + turn_profile_goal_state;
+
+ if (::std::abs(drive_profile_goal_state(0, 0) - yoffset) < epsilon &&
+ ::std::abs(turn_profile_goal_state(0, 0) - turn_offset) < epsilon) {
+ break;
+ }
+
+ if (ShouldCancel()) return true;
+
+ LOG(DEBUG, "Driving left to %f, right to %f\n",
+ left_goal_state(0, 0) + params.left_initial_position,
+ right_goal_state(0, 0) + params.right_initial_position);
+ ::frc971::control_loops::drivetrain_queue.goal.MakeWithBuilder()
+ .control_loop_driving(true)
+ .highgear(true)
+ .left_goal(left_goal_state(0, 0) + params.left_initial_position)
+ .right_goal(right_goal_state(0, 0) + params.right_initial_position)
+ .left_velocity_goal(left_goal_state(1, 0))
+ .right_velocity_goal(right_goal_state(1, 0))
+ .Send();
+ }
+ if (ShouldCancel()) return true;
+ ::frc971::control_loops::drivetrain_queue.status.FetchLatest();
+
+ while (!::frc971::control_loops::drivetrain_queue.status.get()) {
+ LOG(WARNING,
+ "No previous drivetrain status packet, trying to fetch again\n");
+ ::frc971::control_loops::drivetrain_queue.status.FetchNextBlocking();
+ if (ShouldCancel()) return true;
+ }
+
+ while (true) {
+ if (ShouldCancel()) return true;
+ const double kPositionThreshold = 0.05;
+
+ const double left_error =
+ ::std::abs(::frc971::control_loops::drivetrain_queue.status
+ ->estimated_left_position -
+ (left_goal_state(0, 0) + params.left_initial_position));
+ const double right_error =
+ ::std::abs(::frc971::control_loops::drivetrain_queue.status
+ ->estimated_right_position -
+ (right_goal_state(0, 0) + params.right_initial_position));
+ const double velocity_error = ::std::abs(
+ ::frc971::control_loops::drivetrain_queue.status->robot_speed);
+ if (left_error < kPositionThreshold && right_error < kPositionThreshold &&
+ velocity_error < 0.2) {
+ break;
+ } else {
+ LOG(DEBUG, "Drivetrain error is %f, %f, %f\n", left_error, right_error,
+ velocity_error);
+ }
+ ::frc971::control_loops::drivetrain_queue.status.FetchNextBlocking();
+ }
+
+ LOG(INFO, "Done moving\n");
+ return true;
+}
+
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+ const ::y2016_bot3::actors::DrivetrainActionParams ¶ms) {
+ return ::std::unique_ptr<DrivetrainAction>(
+ new DrivetrainAction(&::y2016_bot3::actors::drivetrain_action, params));
+}
+
+} // namespace actors
+} // namespace y2016_bot3
diff --git a/y2016_bot3/actors/drivetrain_actor.h b/y2016_bot3/actors/drivetrain_actor.h
new file mode 100644
index 0000000..ebf3ed5
--- /dev/null
+++ b/y2016_bot3/actors/drivetrain_actor.h
@@ -0,0 +1,36 @@
+#ifndef Y2016_BOT3_ACTORS_DRIVETRAIN_ACTOR_H_
+#define Y2016_BOT3_ACTORS_DRIVETRAIN_ACTOR_H_
+
+#include <memory>
+
+#include "aos/common/actions/actor.h"
+#include "aos/common/actions/actions.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+
+#include "y2016_bot3/actors/drivetrain_action.q.h"
+
+namespace y2016_bot3 {
+namespace actors {
+
+class DrivetrainActor
+ : public ::aos::common::actions::ActorBase<DrivetrainActionQueueGroup> {
+ public:
+ explicit DrivetrainActor(DrivetrainActionQueueGroup *s);
+
+ bool RunAction(const actors::DrivetrainActionParams ¶ms) override;
+
+ private:
+ StateFeedbackLoop<4, 2, 2> loop_;
+};
+
+typedef ::aos::common::actions::TypedAction<DrivetrainActionQueueGroup>
+ DrivetrainAction;
+
+// Makes a new DrivetrainActor action.
+::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
+ const ::y2016_bot3::actors::DrivetrainActionParams ¶ms);
+
+} // namespace actors
+} // namespace y2016_bot3
+
+#endif
diff --git a/y2016_bot3/actors/drivetrain_actor_main.cc b/y2016_bot3/actors/drivetrain_actor_main.cc
new file mode 100644
index 0000000..41a4d28
--- /dev/null
+++ b/y2016_bot3/actors/drivetrain_actor_main.cc
@@ -0,0 +1,18 @@
+#include <stdio.h>
+
+#include "aos/linux_code/init.h"
+#include "y2016_bot3/actors/drivetrain_action.q.h"
+#include "y2016_bot3/actors/drivetrain_actor.h"
+
+using ::aos::time::Time;
+
+int main(int /*argc*/, char* /*argv*/ []) {
+ ::aos::Init(-1);
+
+ ::y2016_bot3::actors::DrivetrainActor drivetrain(
+ &::y2016_bot3::actors::drivetrain_action);
+ drivetrain.Run();
+
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2016_bot3/control_loops/drivetrain/BUILD b/y2016_bot3/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..c6e95c4
--- /dev/null
+++ b/y2016_bot3/control_loops/drivetrain/BUILD
@@ -0,0 +1,77 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+genrule(
+ name = 'genrule_drivetrain',
+ visibility = ['//visibility:private'],
+ cmd = '$(location //y2016_bot3/control_loops/python:drivetrain) $(OUTS)',
+ tools = [
+ '//y2016_bot3/control_loops/python:drivetrain',
+ ],
+ outs = [
+ 'drivetrain_dog_motor_plant.h',
+ 'drivetrain_dog_motor_plant.cc',
+ 'kalman_drivetrain_motor_plant.h',
+ 'kalman_drivetrain_motor_plant.cc',
+ ],
+)
+
+genrule(
+ name = 'genrule_polydrivetrain',
+ visibility = ['//visibility:private'],
+ cmd = '$(location //y2016_bot3/control_loops/python:polydrivetrain) $(OUTS)',
+ tools = [
+ '//y2016_bot3/control_loops/python:polydrivetrain',
+ ],
+ outs = [
+ 'polydrivetrain_dog_motor_plant.h',
+ 'polydrivetrain_dog_motor_plant.cc',
+ 'polydrivetrain_cim_plant.h',
+ 'polydrivetrain_cim_plant.cc',
+ ],
+)
+
+cc_library(
+ name = 'polydrivetrain_plants',
+ srcs = [
+ 'polydrivetrain_dog_motor_plant.cc',
+ 'drivetrain_dog_motor_plant.cc',
+ 'kalman_drivetrain_motor_plant.cc',
+ ],
+ hdrs = [
+ 'polydrivetrain_dog_motor_plant.h',
+ 'drivetrain_dog_motor_plant.h',
+ 'kalman_drivetrain_motor_plant.h',
+ ],
+ deps = [
+ '//frc971/control_loops:state_feedback_loop',
+ ],
+)
+
+cc_library(
+ name = 'drivetrain_base',
+ srcs = [
+ 'drivetrain_base.cc',
+ ],
+ hdrs = [
+ 'drivetrain_base.h',
+ ],
+ deps = [
+ ':polydrivetrain_plants',
+ '//frc971/control_loops/drivetrain:drivetrain_config',
+ '//frc971:shifter_hall_effect',
+ ],
+)
+
+cc_binary(
+ name = 'drivetrain',
+ srcs = [
+ 'drivetrain_main.cc',
+ ],
+ deps = [
+ ':drivetrain_base',
+ '//aos/linux_code:init',
+ '//frc971/control_loops/drivetrain:drivetrain_lib',
+ ],
+)
diff --git a/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc b/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..cefb1cf
--- /dev/null
+++ b/y2016_bot3/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,46 @@
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2016_bot3/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+#include "y2016_bot3/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace y2016_bot3 {
+namespace control_loops {
+namespace drivetrain {
+
+using ::frc971::constants::ShifterHallEffect;
+
+const ShifterHallEffect kThreeStateDriveShifter{0.0, 0.0, 0.0, 0.0, 0.25, 0.75};
+
+const DrivetrainConfig &GetDrivetrainConfig() {
+ static DrivetrainConfig kDrivetrainConfig{
+ ::frc971::control_loops::drivetrain::ShifterType::NO_SHIFTER,
+ ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
+
+ ::y2016_bot3::control_loops::drivetrain::MakeDrivetrainLoop,
+ ::y2016_bot3::control_loops::drivetrain::MakeVelocityDrivetrainLoop,
+ ::y2016_bot3::control_loops::drivetrain::MakeKFDrivetrainLoop,
+
+ drivetrain::kDt,
+ drivetrain::kRobotRadius,
+ drivetrain::kWheelRadius,
+ drivetrain::kV,
+
+ drivetrain::kHighGearRatio,
+ drivetrain::kHighGearRatio,
+ kThreeStateDriveShifter,
+ kThreeStateDriveShifter,
+ true,
+ 0.0};
+
+ return kDrivetrainConfig;
+};
+
+} // namespace drivetrain
+} // namespace control_loops
+} // namespace y2016_bot3
diff --git a/y2016_bot3/control_loops/drivetrain/drivetrain_base.h b/y2016_bot3/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..d6a041e
--- /dev/null
+++ b/y2016_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,24 @@
+#ifndef Y2016_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2016_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2016_bot3 {
+namespace constants {
+static constexpr double drivetrain_max_speed = 5.0;
+
+// The ratio from the encoder shaft to the drivetrain wheels.
+// TODO(constants): Update these.
+static constexpr double kDrivetrainEncoderRatio = 1.0;
+
+} // namespace constants
+namespace control_loops {
+namespace drivetrain {
+const ::frc971::control_loops::drivetrain::DrivetrainConfig &
+GetDrivetrainConfig();
+
+} // namespace drivetrain
+} // namespace control_loops
+} // namespace y2016_bot3
+
+#endif // Y2016_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2016_bot3/control_loops/drivetrain/drivetrain_main.cc b/y2016_bot3/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..3eaccce
--- /dev/null
+++ b/y2016_bot3/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,15 @@
+#include "aos/linux_code/init.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+
+int main() {
+ ::aos::Init();
+ DrivetrainLoop drivetrain(
+ ::y2016_bot3::control_loops::drivetrain::GetDrivetrainConfig());
+ drivetrain.Run();
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2016_bot3/control_loops/intake/BUILD b/y2016_bot3/control_loops/intake/BUILD
new file mode 100644
index 0000000..887a63c
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/BUILD
@@ -0,0 +1,96 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+queue_library(
+ name = 'intake_queue',
+ srcs = [
+ 'intake.q',
+ ],
+ deps = [
+ '//aos/common/controls:control_loop_queues',
+ '//frc971/control_loops:queues',
+ ],
+)
+
+genrule(
+ name = 'genrule_intake',
+ visibility = ['//visibility:private'],
+ cmd = '$(location //y2016_bot3/control_loops/python:intake) $(OUTS)',
+ tools = [
+ '//y2016_bot3/control_loops/python:intake',
+ ],
+ outs = [
+ 'intake_plant.h',
+ 'intake_plant.cc',
+ 'integral_intake_plant.h',
+ 'integral_intake_plant.cc',
+ ],
+)
+
+cc_library(
+ name = 'intake_plants',
+ srcs = [
+ 'intake_plant.cc',
+ 'integral_intake_plant.cc',
+ ],
+ hdrs = [
+ 'intake_plant.h',
+ 'integral_intake_plant.h',
+ ],
+ deps = [
+ '//frc971/control_loops:state_feedback_loop',
+ ],
+)
+
+cc_library(
+ name = 'intake_lib',
+ srcs = [
+ 'intake.cc',
+ 'intake_controls.cc',
+ ],
+ hdrs = [
+ 'intake.h',
+ 'intake_controls.h',
+ ],
+ deps = [
+ ':intake_queue',
+ ':intake_plants',
+ '//aos/common/controls:control_loop',
+ '//aos/common/util:trapezoid_profile',
+ '//aos/common:math',
+ '//y2016_bot3/queues:ball_detector',
+ '//frc971/control_loops:state_feedback_loop',
+ '//frc971/control_loops:simple_capped_state_feedback_loop',
+ '//frc971/zeroing',
+ ],
+)
+
+cc_test(
+ name = 'intake_lib_test',
+ srcs = [
+ 'intake_lib_test.cc',
+ ],
+ deps = [
+ ':intake_queue',
+ ':intake_lib',
+ '//aos/testing:googletest',
+ '//aos/common:queues',
+ '//aos/common/controls:control_loop_test',
+ '//aos/common:math',
+ '//aos/common:time',
+ '//frc971/control_loops:position_sensor_sim',
+ ],
+)
+
+cc_binary(
+ name = 'intake',
+ srcs = [
+ 'intake_main.cc',
+ ],
+ deps = [
+ '//aos/linux_code:init',
+ ':intake_lib',
+ ':intake_queue',
+ ],
+)
diff --git a/y2016_bot3/control_loops/intake/intake.cc b/y2016_bot3/control_loops/intake/intake.cc
new file mode 100644
index 0000000..5320cd5
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake.cc
@@ -0,0 +1,265 @@
+#include "y2016_bot3/control_loops/intake/intake.h"
+#include "y2016_bot3/control_loops/intake/intake_controls.h"
+
+#include "aos/common/commonmath.h"
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+
+#include "y2016_bot3/control_loops/intake/integral_intake_plant.h"
+#include "y2016_bot3/queues/ball_detector.q.h"
+
+namespace y2016_bot3 {
+namespace control_loops {
+namespace intake {
+
+namespace {
+// The maximum voltage the intake roller will be allowed to use.
+constexpr float kMaxIntakeTopVoltage = 12.0;
+constexpr float kMaxIntakeBottomVoltage = 12.0;
+
+}
+// namespace
+
+void LimitChecker::UpdateGoal(double intake_angle_goal) {
+ intake_->set_unprofiled_goal(intake_angle_goal);
+}
+
+Intake::Intake(control_loops::IntakeQueue *intake_queue)
+ : aos::controls::ControlLoop<control_loops::IntakeQueue>(intake_queue),
+ limit_checker_(&intake_) {}
+bool Intake::IsIntakeNear(double tolerance) {
+ return ((intake_.unprofiled_goal() - intake_.X_hat())
+ .block<2, 1>(0, 0)
+ .lpNorm<Eigen::Infinity>() < tolerance);
+}
+
+double Intake::MoveButKeepAbove(double reference_angle, double current_angle,
+ double move_distance) {
+ return -MoveButKeepBelow(-reference_angle, -current_angle, -move_distance);
+}
+
+double Intake::MoveButKeepBelow(double reference_angle, double current_angle,
+ double move_distance) {
+ // There are 3 interesting places to move to.
+ const double small_negative_move = current_angle - move_distance;
+ const double small_positive_move = current_angle + move_distance;
+ // And the reference angle.
+
+ // Move the the highest one that is below reference_angle.
+ if (small_negative_move > reference_angle) {
+ return reference_angle;
+ } else if (small_positive_move > reference_angle) {
+ return small_negative_move;
+ } else {
+ return small_positive_move;
+ }
+}
+
+void Intake::RunIteration(const control_loops::IntakeQueue::Goal *unsafe_goal,
+ const control_loops::IntakeQueue::Position *position,
+ control_loops::IntakeQueue::Output *output,
+ control_loops::IntakeQueue::Status *status) {
+ const State state_before_switch = state_;
+ if (WasReset()) {
+ LOG(ERROR, "WPILib reset, restarting\n");
+ intake_.Reset();
+ state_ = UNINITIALIZED;
+ }
+
+ // Bool to track if we should turn the motors on or not.
+ bool disable = output == nullptr;
+
+ intake_.Correct(position->intake);
+
+ // There are 2 main zeroing paths, HIGH_ARM_ZERO and LOW_ARM_ZERO.
+ //
+ // HIGH_ARM_ZERO works by lifting the arm all the way up so it is clear,
+ // moving the shooter to be horizontal, moving the intake out, and then moving
+ // the arm back down.
+ //
+ // LOW_ARM_ZERO works by moving the intake out of the way, lifting the arm up,
+ // leveling the shooter, and then moving back down.
+
+ if (intake_.error()) {
+ state_ = ESTOP;
+ }
+
+ switch (state_) {
+ case UNINITIALIZED:
+ // Wait in the uninitialized state until intake is initialized.
+ LOG(DEBUG, "Uninitialized, waiting for intake\n");
+ if (intake_.initialized()) {
+ state_ = DISABLED_INITIALIZED;
+ }
+ disable = true;
+ break;
+
+ case DISABLED_INITIALIZED:
+ // Wait here until we are either fully zeroed while disabled, or we become
+ // enabled.
+ if (disable) {
+ if (intake_.zeroed()) {
+ state_ = SLOW_RUNNING;
+ }
+ } else {
+ if (intake_.angle() <= kIntakeMiddleAngle) {
+ state_ = ZERO_LIFT_INTAKE;
+ } else {
+ state_ = ZERO_LOWER_INTAKE;
+ }
+ }
+
+ // Set the goals to where we are now so when we start back up, we don't
+ // jump.
+ intake_.ForceGoal(intake_.angle());
+ // Set up the profile to be the zeroing profile.
+ intake_.AdjustProfile(0.5, 10);
+
+ // We are not ready to start doing anything yet.
+ disable = true;
+ break;
+
+ case ZERO_LOWER_INTAKE:
+ if (disable) {
+ state_ = DISABLED_INITIALIZED;
+ } else {
+ intake_.set_unprofiled_goal(kIntakeDownAngle);
+
+ if (IsIntakeNear(kLooseTolerance)) {
+ // Close enough, start the next move.
+ state_ = RUNNING;
+ }
+ }
+ break;
+
+ case ZERO_LIFT_INTAKE:
+ if (disable) {
+ state_ = DISABLED_INITIALIZED;
+ } else {
+ intake_.set_unprofiled_goal(kIntakeUpAngle);
+
+ if (IsIntakeNear(kLooseTolerance)) {
+ // Close enough, start the next move.
+ state_ = RUNNING;
+ }
+ }
+ break;
+
+ // These 4 cases are very similar.
+ case SLOW_RUNNING:
+ case RUNNING: {
+ if (disable) {
+ // If we are disabled, go to slow running if we are collided.
+ // Reset the profile to the current position so it moves well from here.
+ intake_.ForceGoal(intake_.angle());
+ }
+
+ double requested_intake = M_PI / 2.0;
+
+ if (unsafe_goal) {
+ intake_.AdjustProfile(unsafe_goal->max_angular_velocity_intake,
+ unsafe_goal->max_angular_acceleration_intake);
+
+ requested_intake = unsafe_goal->angle_intake;
+ }
+ //Push the request out to the hardware.
+ limit_checker_.UpdateGoal(requested_intake);
+
+ // ESTOP if we hit the hard limits.
+ if (intake_.CheckHardLimits() && output) {
+ state_ = ESTOP;
+ }
+ } break;
+
+ case ESTOP:
+ LOG(ERROR, "Estop\n");
+ disable = true;
+ break;
+ }
+
+ // Set the voltage limits.
+ const double max_voltage =
+ (state_ == RUNNING) ? kOperatingVoltage : kZeroingVoltage;
+
+ intake_.set_max_voltage(max_voltage);
+
+ // Calculate the loops for a cycle.
+ {
+ Eigen::Matrix<double, 3, 1> error = intake_.controller().error();
+ status->intake.position_power = intake_.controller().K(0, 0) * error(0, 0);
+ status->intake.velocity_power = intake_.controller().K(0, 1) * error(1, 0);
+ }
+
+ intake_.Update(disable);
+
+ // Write out all the voltages.
+ if (output) {
+ output->voltage_intake = intake_.intake_voltage();
+
+ output->voltage_top_rollers = 0.0;
+ output->voltage_bottom_rollers = 0.0;
+
+ if (unsafe_goal) {
+ // Ball detector lights.
+ ::y2016_bot3::sensors::ball_detector.FetchLatest();
+ bool ball_detected = false;
+ if (::y2016_bot3::sensors::ball_detector.get()) {
+ ball_detected = ::y2016_bot3::sensors::ball_detector->voltage > 2.5;
+ }
+
+ // Intake.
+ if (unsafe_goal->force_intake || !ball_detected) {
+ output->voltage_top_rollers = ::std::max(
+ -kMaxIntakeTopVoltage,
+ ::std::min(unsafe_goal->voltage_top_rollers, kMaxIntakeTopVoltage));
+ output->voltage_bottom_rollers =
+ ::std::max(-kMaxIntakeBottomVoltage,
+ ::std::min(unsafe_goal->voltage_bottom_rollers,
+ kMaxIntakeBottomVoltage));
+ } else {
+ output->voltage_top_rollers = 0.0;
+ output->voltage_bottom_rollers = 0.0;
+ }
+
+ // Traverse.
+ output->traverse_unlatched = unsafe_goal->traverse_unlatched;
+ output->traverse_down = unsafe_goal->traverse_down;
+ }
+ }
+
+ // Save debug/internal state.
+ status->zeroed = intake_.zeroed();
+
+ status->intake.angle = intake_.X_hat(0, 0);
+ status->intake.angular_velocity = intake_.X_hat(1, 0);
+ status->intake.goal_angle = intake_.goal(0, 0);
+ status->intake.goal_angular_velocity = intake_.goal(1, 0);
+ status->intake.unprofiled_goal_angle = intake_.unprofiled_goal(0, 0);
+ status->intake.unprofiled_goal_angular_velocity =
+ intake_.unprofiled_goal(1, 0);
+ status->intake.calculated_velocity =
+ (intake_.angle() - last_intake_angle_) / 0.005;
+ status->intake.voltage_error = intake_.X_hat(2, 0);
+ status->intake.estimator_state = intake_.IntakeEstimatorState();
+ status->intake.feedforwards_power = intake_.controller().ff_U(0, 0);
+
+ last_intake_angle_ = intake_.angle();
+
+ status->estopped = (state_ == ESTOP);
+
+ status->state = state_;
+
+ last_state_ = state_before_switch;
+}
+
+constexpr double Intake::kZeroingVoltage;
+constexpr double Intake::kOperatingVoltage;
+constexpr double Intake::kLooseTolerance;
+constexpr double Intake::kTightTolerance;
+constexpr double Intake::kIntakeUpAngle;
+constexpr double Intake::kIntakeMiddleAngle;
+constexpr double Intake::kIntakeDownAngle;
+
+} // namespace intake
+} // namespace control_loops
+} // namespace y2016_bot3
diff --git a/y2016_bot3/control_loops/intake/intake.h b/y2016_bot3/control_loops/intake/intake.h
new file mode 100644
index 0000000..fed17ab
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake.h
@@ -0,0 +1,153 @@
+#ifndef Y2016_BOT3_CONTROL_LOOPS_INTAKE_INTAKE_H_
+#define Y2016_BOT3_CONTROL_LOOPS_INTAKE_INTAKE_H_
+
+#include <memory>
+
+#include "aos/common/controls/control_loop.h"
+#include "aos/common/util/trapezoid_profile.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+
+#include "frc971/zeroing/zeroing.h"
+#include "y2016_bot3/control_loops/intake/intake.q.h"
+#include "y2016_bot3/control_loops/intake/intake_controls.h"
+
+namespace y2016_bot3 {
+namespace constants {
+static const int kZeroingSampleSize = 200;
+
+// Ratios for our subsystems.
+// TODO(constants): Update these.
+static constexpr double kIntakeEncoderRatio = 18.0 / 72.0 * 15.0 / 48.0;
+
+static constexpr double kIntakePotRatio = 15.0 / 48.0;
+
+// Difference in radians between index pulses.
+static constexpr double kIntakeEncoderIndexDifference =
+ 2.0 * M_PI * kIntakeEncoderRatio;
+
+// Subsystem motion ranges, in whatever units that their respective queues say
+// the use.
+// TODO(constants): Update these.
+static constexpr ::frc971::constants::Range kIntakeRange{// Lower hard stop
+ -0.5,
+ // Upper hard stop
+ 2.90,
+ // Lower soft stop
+ -0.300,
+ // Uppper soft stop
+ 2.725};
+
+struct IntakeZero {
+ double pot_offset = 0.0;
+ ::frc971::constants::ZeroingConstants zeroing{
+ kZeroingSampleSize, kIntakeEncoderIndexDifference, 0.0, 0.3};
+};
+} // namespace constants
+namespace control_loops {
+namespace intake {
+namespace testing {
+class IntakeTest_RespectsRange_Test;
+class IntakeTest_DisabledGoalTest_Test;
+class IntakeTest_IntakeZeroingErrorTest_Test;
+class IntakeTest_UpperHardstopStartup_Test;
+class IntakeTest_DisabledWhileZeroingHigh_Test;
+class IntakeTest_DisabledWhileZeroingLow_Test;
+}
+
+class LimitChecker {
+ public:
+ LimitChecker(IntakeArm *intake) : intake_(intake) {}
+ void UpdateGoal(double intake_angle_goal);
+ private:
+ IntakeArm *intake_;
+};
+
+class Intake : public ::aos::controls::ControlLoop<control_loops::IntakeQueue> {
+ public:
+ explicit Intake(
+ control_loops::IntakeQueue *my_intake = &control_loops::intake_queue);
+
+ static constexpr double kZeroingVoltage = 6.0;
+ static constexpr double kOperatingVoltage = 12.0;
+
+ // This is the large scale movement tolerance.
+ static constexpr double kLooseTolerance = 0.05;
+
+ // This is the small scale movement tolerance.
+ static constexpr double kTightTolerance = 0.03;
+
+ static constexpr double kIntakeUpAngle = M_PI / 2;
+
+ static constexpr double kIntakeDownAngle = 0.0;
+
+ static constexpr double kIntakeMiddleAngle =
+ (kIntakeUpAngle + kIntakeDownAngle) / 2;
+
+ enum State {
+ // Wait for all the filters to be ready before starting the initialization
+ // process.
+ UNINITIALIZED = 0,
+
+ // We now are ready to decide how to zero. Decide what to do once we are
+ // enabled.
+ DISABLED_INITIALIZED = 1,
+
+ ZERO_LOWER_INTAKE = 2,
+
+ ZERO_LIFT_INTAKE = 3,
+ // Run, but limit power to zeroing voltages.
+ SLOW_RUNNING = 12,
+ // Run with full power.
+ RUNNING = 13,
+ // Internal error caused the intake to abort.
+ ESTOP = 16,
+ };
+
+ bool IsRunning() const {
+ return (state_ == SLOW_RUNNING || state_ == RUNNING);
+ }
+
+ State state() const { return state_; }
+
+ // Returns the value to move the joint to such that it will stay below
+ // reference_angle starting at current_angle, but move at least move_distance
+ static double MoveButKeepBelow(double reference_angle, double current_angle,
+ double move_distance);
+ // Returns the value to move the joint to such that it will stay above
+ // reference_angle starting at current_angle, but move at least move_distance
+ static double MoveButKeepAbove(double reference_angle, double current_angle,
+ double move_distance);
+
+ protected:
+ void RunIteration(const control_loops::IntakeQueue::Goal *unsafe_goal,
+ const control_loops::IntakeQueue::Position *position,
+ control_loops::IntakeQueue::Output *output,
+ control_loops::IntakeQueue::Status *status) override;
+
+ private:
+ friend class testing::IntakeTest_DisabledGoalTest_Test;
+ friend class testing::IntakeTest_IntakeZeroingErrorTest_Test;
+ friend class testing::IntakeTest_RespectsRange_Test;
+ friend class testing::IntakeTest_UpperHardstopStartup_Test;
+ friend class testing::IntakeTest_DisabledWhileZeroingHigh_Test;
+ friend class testing::IntakeTest_DisabledWhileZeroingLow_Test;
+ IntakeArm intake_;
+
+ State state_ = UNINITIALIZED;
+ State last_state_ = UNINITIALIZED;
+
+ float last_intake_angle_ = 0.0;
+ LimitChecker limit_checker_;
+ // Returns true if the profile has finished, and the joint is within the
+ // specified tolerance.
+ bool IsIntakeNear(double tolerance);
+
+ DISALLOW_COPY_AND_ASSIGN(Intake);
+};
+
+
+} // namespace intake
+} // namespace control_loops
+} // namespace y2016_bot3
+
+#endif // Y2016_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2016_bot3/control_loops/intake/intake.q b/y2016_bot3/control_loops/intake/intake.q
new file mode 100644
index 0000000..da3edbb
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake.q
@@ -0,0 +1,112 @@
+package y2016_bot3.control_loops;
+
+import "aos/common/controls/control_loops.q";
+import "frc971/control_loops/control_loops.q";
+
+struct JointState {
+ // Angle of the joint in radians.
+ float angle;
+ // Angular velocity of the joint in radians/second.
+ float angular_velocity;
+ // Profiled goal angle of the joint in radians.
+ float goal_angle;
+ // Profiled goal angular velocity of the joint in radians/second.
+ float goal_angular_velocity;
+ // Unprofiled goal angle of the joint in radians.
+ float unprofiled_goal_angle;
+ // Unprofiled goal angular velocity of the joint in radians/second.
+ float unprofiled_goal_angular_velocity;
+
+ // The estimated voltage error.
+ float voltage_error;
+
+ // The calculated velocity with delta x/delta t
+ float calculated_velocity;
+
+ // Components of the control loop output
+ float position_power;
+ float velocity_power;
+ float feedforwards_power;
+
+ // State of the estimator.
+ .frc971.EstimatorState estimator_state;
+};
+
+queue_group IntakeQueue {
+ implements aos.control_loops.ControlLoop;
+
+ message Goal {
+ // Zero on the intake is when the horizontal tube stock members are level
+ // with the ground. This will be essentially when we are in the intaking
+ // position. Positive is up. The angle is measured relative to the top
+ // of the robot frame.
+ // Zero on the shoulder is horizontal. Positive is up. The angle is
+ // measured relative to the top of the robot frame.
+ // Zero on the wrist is horizontal and landed in the bellypan. Positive is
+ // the same direction as the shoulder. The angle is measured relative to
+ // the top of the robot frame.
+
+ // Goal angles and angular velocities of the intake.
+ double angle_intake;
+
+ // Caps on velocity/acceleration for profiling. 0 for the default.
+ float max_angular_velocity_intake;
+
+ float max_angular_acceleration_intake;
+
+ // Voltage to send to the rollers. Positive is sucking in.
+ float voltage_top_rollers;
+ float voltage_bottom_rollers;
+
+ bool force_intake;
+
+ // If true, release the latch which holds the traverse mechanism in the
+ // middle.
+ bool traverse_unlatched;
+ // If true, fire the traverse mechanism down.
+ bool traverse_down;
+ };
+
+ message Status {
+ // Is the intake zeroed?
+ bool zeroed;
+
+ // If true, we have aborted.
+ bool estopped;
+
+ // The internal state of the state machine.
+ int32_t state;
+
+
+ // Estimated angle and angular velocitie of the intake.
+ JointState intake;
+
+ // Is the intake collided?
+ bool is_collided;
+ };
+
+ message Position {
+ // Zero for the intake potentiometer value is horizontal, and positive is
+ // up.
+ .frc971.PotAndIndexPosition intake;
+ };
+
+ message Output {
+ float voltage_intake;
+
+ float voltage_top_rollers;
+ float voltage_bottom_rollers;
+
+ // If true, release the latch to hold the traverse mechanism in the middle.
+ bool traverse_unlatched;
+ // If true, fire the traverse mechanism down.
+ bool traverse_down;
+ };
+
+ queue Goal goal;
+ queue Position position;
+ queue Output output;
+ queue Status status;
+};
+
+queue_group IntakeQueue intake_queue;
diff --git a/y2016_bot3/control_loops/intake/intake_controls.cc b/y2016_bot3/control_loops/intake/intake_controls.cc
new file mode 100644
index 0000000..f5ada8c
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake_controls.cc
@@ -0,0 +1,168 @@
+#include "y2016_bot3/control_loops/intake/intake_controls.h"
+
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+
+#include "y2016_bot3/control_loops/intake/integral_intake_plant.h"
+
+#include "y2016_bot3/control_loops/intake/intake.h"
+
+namespace y2016_bot3 {
+namespace constants {
+IntakeZero intake_zero;
+}
+namespace control_loops {
+namespace intake {
+
+using ::frc971::PotAndIndexPosition;
+using ::frc971::EstimatorState;
+
+namespace {
+double UseUnlessZero(double target_value, double default_value) {
+ if (target_value != 0.0) {
+ return target_value;
+ } else {
+ return default_value;
+ }
+}
+} // namespace
+
+// Intake
+IntakeArm::IntakeArm()
+ : loop_(new ::frc971::control_loops::SimpleCappedStateFeedbackLoop<3, 1, 1>(
+ ::y2016_bot3::control_loops::intake::MakeIntegralIntakeLoop())),
+ estimator_(y2016_bot3::constants::intake_zero.zeroing),
+ profile_(::aos::controls::kLoopFrequency) {
+ Y_.setZero();
+ unprofiled_goal_.setZero();
+ offset_.setZero();
+ AdjustProfile(0.0, 0.0);
+}
+
+void IntakeArm::UpdateIntakeOffset(double offset) {
+ const double doffset = offset - offset_(0, 0);
+ LOG(INFO, "Adjusting Intake offset from %f to %f\n", offset_(0, 0), offset);
+
+ loop_->mutable_X_hat()(0, 0) += doffset;
+ Y_(0, 0) += doffset;
+ loop_->mutable_R(0, 0) += doffset;
+
+ profile_.MoveGoal(doffset);
+ offset_(0, 0) = offset;
+
+ CapGoal("R", &loop_->mutable_R());
+}
+
+void IntakeArm::Correct(PotAndIndexPosition position) {
+ estimator_.UpdateEstimate(position);
+
+ if (estimator_.error()) {
+ LOG(ERROR, "zeroing error with intake_estimator\n");
+ return;
+ }
+
+ if (!initialized_) {
+ if (estimator_.offset_ready()) {
+ UpdateIntakeOffset(estimator_.offset());
+ initialized_ = true;
+ }
+ }
+
+ if (!zeroed_ && estimator_.zeroed()) {
+ UpdateIntakeOffset(estimator_.offset());
+ zeroed_ = true;
+ }
+
+ Y_ << position.encoder;
+ Y_ += offset_;
+ loop_->Correct(Y_);
+}
+
+void IntakeArm::CapGoal(const char *name, Eigen::Matrix<double, 3, 1> *goal) {
+ // Limit the goal to min/max allowable angles.
+ if ((*goal)(0, 0) > y2016_bot3::constants::kIntakeRange.upper) {
+ LOG(WARNING, "Intake goal %s above limit, %f > %f\n", name, (*goal)(0, 0),
+ y2016_bot3::constants::kIntakeRange.upper);
+ (*goal)(0, 0) = y2016_bot3::constants::kIntakeRange.upper;
+ }
+ if ((*goal)(0, 0) < y2016_bot3::constants::kIntakeRange.lower) {
+ LOG(WARNING, "Intake goal %s below limit, %f < %f\n", name, (*goal)(0, 0),
+ y2016_bot3::constants::kIntakeRange.lower);
+ (*goal)(0, 0) = y2016_bot3::constants::kIntakeRange.lower;
+ }
+}
+
+void IntakeArm::ForceGoal(double goal) {
+ set_unprofiled_goal(goal);
+ loop_->mutable_R() = unprofiled_goal_;
+ loop_->mutable_next_R() = loop_->R();
+
+ profile_.MoveCurrentState(loop_->R().block<2, 1>(0, 0));
+}
+
+void IntakeArm::set_unprofiled_goal(double unprofiled_goal) {
+ unprofiled_goal_(0, 0) = unprofiled_goal;
+ unprofiled_goal_(1, 0) = 0.0;
+ unprofiled_goal_(2, 0) = 0.0;
+ CapGoal("unprofiled R", &unprofiled_goal_);
+}
+
+void IntakeArm::Update(bool disable) {
+ if (!disable) {
+ ::Eigen::Matrix<double, 2, 1> goal_state =
+ profile_.Update(unprofiled_goal_(0, 0), unprofiled_goal_(1, 0));
+
+ loop_->mutable_next_R(0, 0) = goal_state(0, 0);
+ loop_->mutable_next_R(1, 0) = goal_state(1, 0);
+ loop_->mutable_next_R(2, 0) = 0.0;
+ CapGoal("next R", &loop_->mutable_next_R());
+ }
+
+ loop_->Update(disable);
+
+ if (!disable && loop_->U(0, 0) != loop_->U_uncapped(0, 0)) {
+ profile_.MoveCurrentState(loop_->R().block<2, 1>(0, 0));
+ }
+}
+
+bool IntakeArm::CheckHardLimits() {
+ // Returns whether hard limits have been exceeded.
+
+ if (angle() > y2016_bot3::constants::kIntakeRange.upper_hard ||
+ angle() < y2016_bot3::constants::kIntakeRange.lower_hard) {
+ LOG(ERROR, "Intake at %f out of bounds [%f, %f], ESTOPing\n", angle(),
+ y2016_bot3::constants::kIntakeRange.lower_hard,
+ y2016_bot3::constants::kIntakeRange.upper_hard);
+ return true;
+ }
+
+ return false;
+}
+
+void IntakeArm::set_max_voltage(double voltage) {
+ loop_->set_max_voltage(0, voltage);
+}
+
+void IntakeArm::AdjustProfile(double max_angular_velocity,
+ double max_angular_acceleration) {
+ profile_.set_maximum_velocity(UseUnlessZero(max_angular_velocity, 10.0));
+ profile_.set_maximum_acceleration(
+ UseUnlessZero(max_angular_acceleration, 10.0));
+}
+
+void IntakeArm::Reset() {
+ estimator_.Reset();
+ initialized_ = false;
+ zeroed_ = false;
+}
+
+EstimatorState IntakeArm::IntakeEstimatorState() {
+ EstimatorState estimator_state;
+ ::frc971::zeroing::PopulateEstimatorState(estimator_, &estimator_state);
+
+ return estimator_state;
+}
+
+} // namespace intake
+} // namespace control_loops
+} // namespace y2016_bot3
diff --git a/y2016_bot3/control_loops/intake/intake_controls.h b/y2016_bot3/control_loops/intake/intake_controls.h
new file mode 100644
index 0000000..0b2daa0
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake_controls.h
@@ -0,0 +1,112 @@
+#ifndef Y2016_BOT3_CONTROL_LOOPS_INTAKE_INTAKE_CONTROLS_H_
+#define Y2016_BOT3_CONTROL_LOOPS_INTAKE_INTAKE_CONTROLS_H_
+
+#include <memory>
+
+#include "aos/common/controls/control_loop.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/simple_capped_state_feedback_loop.h"
+#include "aos/common/util/trapezoid_profile.h"
+
+#include "frc971/zeroing/zeroing.h"
+#include "y2016_bot3/control_loops/intake/intake.q.h"
+
+namespace y2016_bot3 {
+namespace control_loops {
+namespace intake {
+namespace testing {
+class IntakeTest_DisabledGoalTest_Test;
+} // namespace testing
+
+class IntakeArm {
+ public:
+ IntakeArm();
+ // Returns whether the estimators have been initialized and zeroed.
+ bool initialized() const { return initialized_; }
+ bool zeroed() const { return zeroed_; }
+ // Returns whether an error has occured
+ bool error() const { return estimator_.error(); }
+
+ // Updates our estimator with the latest position.
+ void Correct(::frc971::PotAndIndexPosition position);
+ // Runs the controller and profile generator for a cycle.
+ void Update(bool disabled);
+ // Sets the maximum voltage that will be commanded by the loop.
+ void set_max_voltage(double voltage);
+
+ // Forces the current goal to the provided goal, bypassing the profiler.
+ void ForceGoal(double goal);
+ // Sets the unprofiled goal. The profiler will generate a profile to go to
+ // this goal.
+ void set_unprofiled_goal(double unprofiled_goal);
+ // Limits our profiles to a max velocity and acceleration for proper motion.
+ void AdjustProfile(double max_angular_velocity,
+ double max_angular_acceleration);
+
+ // Returns true if we have exceeded any hard limits.
+ bool CheckHardLimits();
+ // Resets the internal state.
+ void Reset();
+
+ // Returns the current internal estimator state for logging.
+ ::frc971::EstimatorState IntakeEstimatorState();
+
+ // Returns the requested intake voltage.
+ double intake_voltage() const { return loop_->U(0, 0); }
+
+ // Returns the current position.
+ double angle() const { return Y_(0, 0); }
+
+ // Returns the controller error.
+ const StateFeedbackLoop<3, 1, 1> &controller() const { return *loop_; }
+
+ // Returns the filtered goal.
+ const Eigen::Matrix<double, 3, 1> &goal() const { return loop_->R(); }
+ double goal(int row, int col) const { return loop_->R(row, col); }
+
+ // Returns the unprofiled goal.
+ const Eigen::Matrix<double, 3, 1> &unprofiled_goal() const {
+ return unprofiled_goal_;
+ }
+ double unprofiled_goal(int row, int col) const {
+ return unprofiled_goal_(row, col);
+ }
+
+ // Returns the current state estimate.
+ const Eigen::Matrix<double, 3, 1> &X_hat() const { return loop_->X_hat(); }
+ double X_hat(int row, int col) const { return loop_->X_hat(row, col); }
+
+ // For testing:
+ // Triggers an estimator error.
+ void TriggerEstimatorError() { estimator_.TriggerError(); }
+
+ private:
+ // Limits the provided goal to the soft limits. Prints "name" when it fails
+ // to aid debugging.
+ void CapGoal(const char *name, Eigen::Matrix<double, 3, 1> *goal);
+
+ void UpdateIntakeOffset(double offset);
+
+ ::std::unique_ptr<
+ ::frc971::control_loops::SimpleCappedStateFeedbackLoop<3, 1, 1>> loop_;
+
+ ::frc971::zeroing::ZeroingEstimator estimator_;
+ aos::util::TrapezoidProfile profile_;
+
+ // Current measurement.
+ Eigen::Matrix<double, 1, 1> Y_;
+ // Current offset. Y_ = offset_ + raw_sensor;
+ Eigen::Matrix<double, 1, 1> offset_;
+
+ // The goal that the profile tries to reach.
+ Eigen::Matrix<double, 3, 1> unprofiled_goal_;
+
+ bool initialized_ = false;
+ bool zeroed_ = false;
+};
+
+} // namespace intake
+} // namespace control_loops
+} // namespace y2016_bot3
+
+#endif // Y2016_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_CONTROLS_H_
diff --git a/y2016_bot3/control_loops/intake/intake_lib_test.cc b/y2016_bot3/control_loops/intake/intake_lib_test.cc
new file mode 100644
index 0000000..43232aa
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake_lib_test.cc
@@ -0,0 +1,552 @@
+#include "y2016_bot3/control_loops/intake/intake.h"
+
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/queue.h"
+#include "aos/common/controls/control_loop_test.h"
+#include "aos/common/commonmath.h"
+#include "aos/common/time.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "y2016_bot3/control_loops/intake/intake.q.h"
+#include "y2016_bot3/control_loops/intake/intake_plant.h"
+
+using ::aos::time::Time;
+using ::frc971::control_loops::PositionSensorSimulator;
+
+namespace y2016_bot3 {
+namespace control_loops {
+namespace intake {
+namespace testing {
+
+class IntakePlant : public StateFeedbackPlant<2, 1, 1> {
+ public:
+ explicit IntakePlant(StateFeedbackPlant<2, 1, 1> &&other)
+ : StateFeedbackPlant<2, 1, 1>(::std::move(other)) {}
+
+ void CheckU() override {
+ for (int i = 0; i < kNumInputs; ++i) {
+ assert(U(i, 0) <= U_max(i, 0) + 0.00001 + voltage_offset_);
+ assert(U(i, 0) >= U_min(i, 0) - 0.00001 + voltage_offset_);
+ }
+ }
+
+ double voltage_offset() const { return voltage_offset_; }
+ void set_voltage_offset(double voltage_offset) {
+ voltage_offset_ = voltage_offset;
+ }
+
+ private:
+ double voltage_offset_ = 0.0;
+};
+
+// Class which simulates the intake and sends out queue messages with
+// the position.
+class IntakeSimulation {
+ public:
+ static constexpr double kNoiseScalar = 0.1;
+ IntakeSimulation()
+ : intake_plant_(new IntakePlant(MakeIntakePlant())),
+ pot_encoder_intake_(
+ y2016_bot3::constants::kIntakeEncoderIndexDifference),
+ intake_queue_(".y2016_bot3.control_loops.intake", 0x0,
+ ".y2016_bot3.control_loops.intake.goal",
+ ".y2016_bot3.control_loops.intake.status",
+ ".y2016_bot3.control_loops.intake.output",
+ ".y2016_bot3.control_loops.intake.status") {
+ InitializeIntakePosition(0.0);
+ }
+
+ void InitializeIntakePosition(double start_pos) {
+ intake_plant_->mutable_X(0, 0) = start_pos;
+ intake_plant_->mutable_X(1, 0) = 0.0;
+
+ pot_encoder_intake_.Initialize(start_pos, kNoiseScalar);
+ }
+
+ // Sends a queue message with the position.
+ void SendPositionMessage() {
+ ::aos::ScopedMessagePtr<control_loops::IntakeQueue::Position> position =
+ intake_queue_.position.MakeMessage();
+
+ pot_encoder_intake_.GetSensorValues(&position->intake);
+
+ position.Send();
+ }
+
+ double intake_angle() const { return intake_plant_->X(0, 0); }
+ double intake_angular_velocity() const { return intake_plant_->X(1, 0); }
+
+ // Sets the difference between the commanded and applied powers.
+ // This lets us test that the integrators work.
+ void set_power_error(double power_error_intake) {
+ intake_plant_->set_voltage_offset(power_error_intake);
+ }
+
+ // Simulates for a single timestep.
+ void Simulate() {
+ EXPECT_TRUE(intake_queue_.output.FetchLatest());
+
+ // Feed voltages into physics simulation.
+ intake_plant_->mutable_U() << intake_queue_.output->voltage_intake +
+ intake_plant_->voltage_offset();
+
+ // Verify that the correct power limits are being respected depending on
+ // which mode we are in.
+ EXPECT_TRUE(intake_queue_.status.FetchLatest());
+ if (intake_queue_.status->state == Intake::RUNNING) {
+ CHECK_LE(::std::abs(intake_queue_.output->voltage_intake),
+ Intake::kOperatingVoltage);
+ } else {
+ CHECK_LE(::std::abs(intake_queue_.output->voltage_intake),
+ Intake::kZeroingVoltage);
+ }
+
+ // Use the plant to generate the next physical state given the voltages to
+ // the motors.
+ intake_plant_->Update();
+
+ const double angle_intake = intake_plant_->Y(0, 0);
+
+ // Use the physical state to simulate sensor readings.
+ pot_encoder_intake_.MoveTo(angle_intake);
+
+ // Validate that everything is within range.
+ EXPECT_GE(angle_intake, y2016_bot3::constants::kIntakeRange.lower_hard);
+ EXPECT_LE(angle_intake, y2016_bot3::constants::kIntakeRange.upper_hard);
+ }
+
+ private:
+ ::std::unique_ptr<IntakePlant> intake_plant_;
+
+ PositionSensorSimulator pot_encoder_intake_;
+
+ IntakeQueue intake_queue_;
+};
+
+class IntakeTest : public ::aos::testing::ControlLoopTest {
+ protected:
+ IntakeTest()
+ : intake_queue_(".y2016_bot3.control_loops.intake", 0x0,
+ ".y2016_bot3.control_loops.intake.goal",
+ ".y2016_bot3.control_loops.intake.status",
+ ".y2016_bot3.control_loops.intake.output",
+ ".y2016_bot3.control_loops.intake.status"),
+ intake_(&intake_queue_),
+ intake_plant_() {}
+
+ void VerifyNearGoal() {
+ intake_queue_.goal.FetchLatest();
+ intake_queue_.status.FetchLatest();
+
+ EXPECT_TRUE(intake_queue_.goal.get() != nullptr);
+ EXPECT_TRUE(intake_queue_.status.get() != nullptr);
+
+ EXPECT_NEAR(intake_queue_.goal->angle_intake,
+ intake_queue_.status->intake.angle, 0.001);
+ EXPECT_NEAR(intake_queue_.goal->angle_intake, intake_plant_.intake_angle(),
+ 0.001);
+ }
+
+ // Runs one iteration of the whole simulation
+ void RunIteration(bool enabled = true) {
+ SendMessages(enabled);
+
+ intake_plant_.SendPositionMessage();
+ intake_.Iterate();
+ intake_plant_.Simulate();
+
+ TickTime();
+ }
+
+ // Runs iterations until the specified amount of simulated time has elapsed.
+ void RunForTime(const Time &run_for, bool enabled = true) {
+ const auto start_time = Time::Now();
+ while (Time::Now() < start_time + run_for) {
+ const auto loop_start_time = Time::Now();
+ double begin_intake_velocity = intake_plant_.intake_angular_velocity();
+ RunIteration(enabled);
+ const double loop_time = (Time::Now() - loop_start_time).ToSeconds();
+ const double intake_acceleration =
+ (intake_plant_.intake_angular_velocity() - begin_intake_velocity) /
+ loop_time;
+ EXPECT_GE(peak_intake_acceleration_, intake_acceleration);
+ EXPECT_LE(-peak_intake_acceleration_, intake_acceleration);
+
+ EXPECT_GE(peak_intake_velocity_, intake_plant_.intake_angular_velocity());
+ EXPECT_LE(-peak_intake_velocity_,
+ intake_plant_.intake_angular_velocity());
+ }
+ }
+
+ // Runs iterations while watching the average acceleration per cycle and
+ // making sure it doesn't exceed the provided bounds.
+ void set_peak_intake_acceleration(double value) {
+ peak_intake_acceleration_ = value;
+ }
+ void set_peak_intake_velocity(double value) { peak_intake_velocity_ = value; }
+
+
+
+ // Create a new instance of the test queue so that it invalidates the queue
+ // that it points to. Otherwise, we will have a pointed to
+ // shared memory that is no longer valid.
+ IntakeQueue intake_queue_;
+
+ // Create a control loop and simulation.
+ Intake intake_;
+ IntakeSimulation intake_plant_;
+
+ private:
+ // The acceleration limits to check for while moving for the 3 axes.
+ double peak_intake_acceleration_ = 1e10;
+ // The velocity limits to check for while moving for the 3 axes.
+ double peak_intake_velocity_ = 1e10;
+};
+
+// Tests that the intake does nothing when the goal is zero.
+TEST_F(IntakeTest, DoesNothing) {
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(0)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ // TODO(phil): Send a goal of some sort.
+ RunForTime(Time::InSeconds(5));
+ VerifyNearGoal();
+}
+
+// Tests that the loop can reach a goal.
+TEST_F(IntakeTest, ReachesGoal) {
+ // Set a reasonable goal.
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(M_PI / 4.0)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ // Give it a lot of time to get there.
+ RunForTime(Time::InSeconds(8));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop doesn't try and go beyond the physical range of the
+// mechanisms.
+TEST_F(IntakeTest, RespectsRange) {
+ // Set some ridiculous goals to test upper limits.
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(M_PI * 10)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+ RunForTime(Time::InSeconds(10));
+
+ // Check that we are near our soft limit.
+ intake_queue_.status.FetchLatest();
+ EXPECT_NEAR(y2016_bot3::constants::kIntakeRange.upper,
+ intake_queue_.status->intake.angle, 0.001);
+
+
+ // Set some ridiculous goals to test lower limits.
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(-M_PI * 10)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ RunForTime(Time::InSeconds(10));
+
+ // Check that we are near our soft limit.
+ intake_queue_.status.FetchLatest();
+ EXPECT_NEAR(y2016_bot3::constants::kIntakeRange.lower,
+ intake_queue_.status->intake.angle, 0.001);
+}
+
+// Tests that the loop zeroes when run for a while.
+TEST_F(IntakeTest, ZeroTest) {
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.lower)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ RunForTime(Time::InSeconds(10));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop zeroes when run for a while without a goal.
+TEST_F(IntakeTest, ZeroNoGoal) {
+ RunForTime(Time::InSeconds(5));
+
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+}
+
+// Tests that starting at the lower hardstops doesn't cause an abort.
+TEST_F(IntakeTest, LowerHardstopStartup) {
+ intake_plant_.InitializeIntakePosition(
+ y2016_bot3::constants::kIntakeRange.lower);
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.upper)
+ .Send());
+
+ RunForTime(Time::InSeconds(15));
+ VerifyNearGoal();
+}
+
+// Tests that starting at the upper hardstops doesn't cause an abort.
+TEST_F(IntakeTest, UpperHardstopStartup) {
+ intake_plant_.InitializeIntakePosition(
+ y2016_bot3::constants::kIntakeRange.upper);
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.lower)
+ .Send());
+
+ RunForTime(Time::InSeconds(15));
+ VerifyNearGoal();
+}
+
+// Tests that resetting WPILib results in a rezero.
+TEST_F(IntakeTest, ResetTest) {
+ intake_plant_.InitializeIntakePosition(
+ y2016_bot3::constants::kIntakeRange.upper);
+
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.lower + 0.3)
+ .Send());
+ RunForTime(Time::InSeconds(15));
+
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+ VerifyNearGoal();
+ SimulateSensorReset();
+ RunForTime(Time::InMS(100));
+ EXPECT_NE(Intake::RUNNING, intake_.state());
+ RunForTime(Time::InMS(10000));
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+ VerifyNearGoal();
+}
+
+// Tests that the internal goals don't change while disabled.
+TEST_F(IntakeTest, DisabledGoalTest) {
+ ASSERT_TRUE(
+ intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.lower + 0.03)
+ .Send());
+
+ RunForTime(Time::InMS(100), false);
+ EXPECT_EQ(0.0, intake_.intake_.goal(0, 0));
+
+ // Now make sure they move correctly
+ RunForTime(Time::InMS(4000), true);
+ EXPECT_NE(0.0, intake_.intake_.goal(0, 0));
+}
+
+// Tests that disabling while zeroing at any state restarts from beginning
+TEST_F(IntakeTest, DisabledWhileZeroingHigh) {
+ intake_plant_.InitializeIntakePosition(
+ y2016_bot3::constants::kIntakeRange.upper);
+
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.upper)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ // Expected states to cycle through and check in order.
+ Intake::State ExpectedStateOrder[] = {
+ Intake::DISABLED_INITIALIZED, Intake::ZERO_LOWER_INTAKE};
+
+ // Cycle through until intake_ is initialized in intake.cc
+ while (intake_.state() < Intake::DISABLED_INITIALIZED) {
+ RunIteration(true);
+ }
+
+ static const int kNumberOfStates =
+ sizeof(ExpectedStateOrder) / sizeof(ExpectedStateOrder[0]);
+
+ // Next state when reached to disable
+ for (int i = 0; i < kNumberOfStates; i++) {
+ // Next expected state after being disabled that is expected until next
+ // state to disable at is reached
+ for (int j = 0; intake_.state() != ExpectedStateOrder[i] && j <= i; j++) {
+ // RunIteration until next expected state is reached with a maximum
+ // of 10000 times to ensure a breakout
+ for (int o = 0; intake_.state() < ExpectedStateOrder[j] && o < 10000;
+ o++) {
+ RunIteration(true);
+ }
+ EXPECT_EQ(ExpectedStateOrder[j], intake_.state());
+ }
+
+ EXPECT_EQ(ExpectedStateOrder[i], intake_.state());
+
+ // Disable
+ RunIteration(false);
+
+ EXPECT_EQ(Intake::DISABLED_INITIALIZED, intake_.state());
+ }
+
+ RunForTime(Time::InSeconds(10));
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+}
+
+// Tests that disabling while zeroing at any state restarts from beginning
+TEST_F(IntakeTest, DisabledWhileZeroingLow) {
+ intake_plant_.InitializeIntakePosition(
+ y2016_bot3::constants::kIntakeRange.lower);
+
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(y2016_bot3::constants::kIntakeRange.lower)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ // Expected states to cycle through and check in order.
+ Intake::State ExpectedStateOrder[] = {
+ Intake::DISABLED_INITIALIZED, Intake::ZERO_LIFT_INTAKE};
+
+ // Cycle through until intake_ is initialized in intake.cc
+ while (intake_.state() < Intake::DISABLED_INITIALIZED) {
+ RunIteration(true);
+ }
+
+ static const int kNumberOfStates =
+ sizeof(ExpectedStateOrder) / sizeof(ExpectedStateOrder[0]);
+
+ // Next state when reached to disable
+ for (int i = 0; i < kNumberOfStates; i++) {
+ // Next expected state after being disabled that is expected until next
+ // state to disable at is reached
+ for (int j = 0; intake_.state() != ExpectedStateOrder[i] && j <= i; j++) {
+ // RunIteration until next expected state is reached with a maximum
+ // of 10000 times to ensure a breakout
+ for (int o = 0; intake_.state() < ExpectedStateOrder[j] && o < 10000;
+ o++) {
+ RunIteration(true);
+ }
+ EXPECT_EQ(ExpectedStateOrder[j], intake_.state());
+ }
+
+ EXPECT_EQ(ExpectedStateOrder[i], intake_.state());
+
+ // Disable
+ RunIteration(false);
+
+ EXPECT_EQ(Intake::DISABLED_INITIALIZED, intake_.state());
+ }
+
+ RunForTime(Time::InSeconds(10));
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+}
+
+// Tests that MoveButKeepBelow returns sane values.
+TEST_F(IntakeTest, MoveButKeepBelowTest) {
+ EXPECT_EQ(1.0, Intake::MoveButKeepBelow(1.0, 10.0, 1.0));
+ EXPECT_EQ(1.0, Intake::MoveButKeepBelow(1.0, 2.0, 1.0));
+ EXPECT_EQ(0.0, Intake::MoveButKeepBelow(1.0, 1.0, 1.0));
+ EXPECT_EQ(1.0, Intake::MoveButKeepBelow(1.0, 0.0, 1.0));
+}
+
+// Tests that the integrators works.
+TEST_F(IntakeTest, IntegratorTest) {
+ intake_plant_.InitializeIntakePosition(
+ y2016_bot3::constants::kIntakeRange.lower);
+ intake_plant_.set_power_error(1.0);
+ intake_queue_.goal.MakeWithBuilder().angle_intake(0.0).Send();
+
+ RunForTime(Time::InSeconds(8));
+
+ VerifyNearGoal();
+}
+
+// Tests that zeroing while disabled works. Starts the superstructure near a
+// pulse, lets it initialize, moves it past the pulse, enables, and then make
+// sure it goes to the right spot.
+TEST_F(IntakeTest, DisabledZeroTest) {
+ intake_plant_.InitializeIntakePosition(-0.001);
+
+ intake_queue_.goal.MakeWithBuilder().angle_intake(0.0).Send();
+
+ // Run disabled for 2 seconds
+ RunForTime(Time::InSeconds(2), false);
+ EXPECT_EQ(Intake::DISABLED_INITIALIZED, intake_.state());
+
+ intake_plant_.set_power_error(1.0);
+
+ RunForTime(Time::InSeconds(1), false);
+
+ EXPECT_EQ(Intake::SLOW_RUNNING, intake_.state());
+ RunForTime(Time::InSeconds(2), true);
+
+ VerifyNearGoal();
+}
+
+// Tests that the zeroing errors in the intake are caught
+TEST_F(IntakeTest, IntakeZeroingErrorTest) {
+ RunIteration();
+ EXPECT_NE(Intake::ESTOP, intake_.state());
+ intake_.intake_.TriggerEstimatorError();
+ RunIteration();
+
+ EXPECT_EQ(Intake::ESTOP, intake_.state());
+}
+
+// Tests that the loop respects intake acceleration limits while moving.
+TEST_F(IntakeTest, IntakeAccelerationLimitTest) {
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(0.0)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ RunForTime(Time::InSeconds(6));
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+
+ VerifyNearGoal();
+
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(0.5)
+ .max_angular_velocity_intake(1)
+ .max_angular_acceleration_intake(1)
+ .Send());
+
+ set_peak_intake_acceleration(1.20);
+ RunForTime(Time::InSeconds(4));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop respects intake handles saturation while accelerating
+// correctly.
+TEST_F(IntakeTest, SaturatedIntakeProfileTest) {
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(0.0)
+ .max_angular_velocity_intake(20)
+ .max_angular_acceleration_intake(20)
+ .Send());
+
+ RunForTime(Time::InSeconds(6));
+ EXPECT_EQ(Intake::RUNNING, intake_.state());
+
+ VerifyNearGoal();
+
+ ASSERT_TRUE(intake_queue_.goal.MakeWithBuilder()
+ .angle_intake(0.5)
+ .max_angular_velocity_intake(4.5)
+ .max_angular_acceleration_intake(800)
+ .Send());
+
+ set_peak_intake_velocity(4.65);
+ RunForTime(Time::InSeconds(4));
+
+ VerifyNearGoal();
+}
+
+} // namespace testing
+} // namespace intake
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2016_bot3/control_loops/intake/intake_main.cc b/y2016_bot3/control_loops/intake/intake_main.cc
new file mode 100644
index 0000000..a60f914
--- /dev/null
+++ b/y2016_bot3/control_loops/intake/intake_main.cc
@@ -0,0 +1,11 @@
+#include "y2016_bot3/control_loops/intake/intake.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+ ::aos::Init();
+ ::y2016_bot3::control_loops::intake::Intake intake;
+ intake.Run();
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2016_bot3/control_loops/python/BUILD b/y2016_bot3/control_loops/python/BUILD
new file mode 100644
index 0000000..1c2ef63
--- /dev/null
+++ b/y2016_bot3/control_loops/python/BUILD
@@ -0,0 +1,65 @@
+package(default_visibility = ['//y2016_bot3:__subpackages__'])
+
+py_binary(
+ name = 'drivetrain',
+ srcs = [
+ 'drivetrain.py',
+ ],
+ deps = [
+ '//external:python-gflags',
+ '//external:python-glog',
+ '//frc971/control_loops/python:controls',
+ ],
+)
+
+py_binary(
+ name = 'polydrivetrain',
+ srcs = [
+ 'polydrivetrain.py',
+ 'drivetrain.py',
+ ],
+ deps = [
+ '//external:python-gflags',
+ '//external:python-glog',
+ '//frc971/control_loops/python:controls',
+ ],
+)
+
+py_library(
+ name = 'polydrivetrain_lib',
+ srcs = [
+ 'polydrivetrain.py',
+ 'drivetrain.py',
+ ],
+ deps = [
+ '//external:python-gflags',
+ '//external:python-glog',
+ '//frc971/control_loops/python:controls',
+ ],
+)
+
+py_binary(
+ name = 'intake',
+ srcs = [
+ 'intake.py',
+ ],
+ deps = [
+ '//aos/common/util:py_trapezoid_profile',
+ '//external:python-gflags',
+ '//external:python-glog',
+ '//frc971/control_loops/python:controls',
+ ],
+)
+
+py_library(
+ name = 'intake_lib',
+ srcs = [
+ 'intake.py',
+ ],
+ deps = [
+ '//aos/common/util:py_trapezoid_profile',
+ '//external:python-gflags',
+ '//external:python-glog',
+ '//frc971/control_loops/python:controls',
+ ],
+)
diff --git a/y2016_bot3/control_loops/python/drivetrain.py b/y2016_bot3/control_loops/python/drivetrain.py
new file mode 100755
index 0000000..5a67416
--- /dev/null
+++ b/y2016_bot3/control_loops/python/drivetrain.py
@@ -0,0 +1,398 @@
+#!/usr/bin/python
+
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+import numpy
+import sys
+import argparse
+from matplotlib import pylab
+
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
+class CIM(control_loop.ControlLoop):
+ def __init__(self):
+ super(CIM, self).__init__("CIM")
+ # Stall Torque in N m
+ self.stall_torque = 2.42
+ # Stall Current in Amps
+ self.stall_current = 133
+ # Free Speed in RPM
+ self.free_speed = 4650.0
+ # Free Current in Amps
+ self.free_current = 2.7
+ # Moment of inertia of the CIM in kg m^2
+ self.J = 0.0001
+ # Resistance of the motor, divided by 2 to account for the 2 motors
+ self.resistance = 12.0 / self.stall_current
+ # Motor velocity constant
+ self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+ (12.0 - self.resistance * self.free_current))
+ # Torque constant
+ self.Kt = self.stall_torque / self.stall_current
+ # Control loop time step
+ self.dt = 0.005
+
+ # State feedback matrices
+ self.A_continuous = numpy.matrix(
+ [[-self.Kt / self.Kv / (self.J * self.resistance)]])
+ self.B_continuous = numpy.matrix(
+ [[self.Kt / (self.J * self.resistance)]])
+ self.C = numpy.matrix([[1]])
+ self.D = numpy.matrix([[0]])
+
+ self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+ self.B_continuous, self.dt)
+
+ self.PlaceControllerPoles([0.01])
+ self.PlaceObserverPoles([0.01])
+
+ self.U_max = numpy.matrix([[12.0]])
+ self.U_min = numpy.matrix([[-12.0]])
+
+ self.InitializeState()
+
+
+class Drivetrain(control_loop.ControlLoop):
+ def __init__(self, name="Drivetrain", left_low=True, right_low=True):
+ super(Drivetrain, self).__init__(name)
+ # Number of motors per side
+ self.num_motors = 2
+ # Stall Torque in N m
+ self.stall_torque = 2.42 * self.num_motors * 0.60
+ # Stall Current in Amps
+ self.stall_current = 133.0 * self.num_motors
+ # Free Speed in RPM. Used number from last year.
+ self.free_speed = 5500.0
+ # Free Current in Amps
+ self.free_current = 4.7 * self.num_motors
+ # Moment of inertia of the drivetrain in kg m^2
+ self.J = 2.0
+ # Mass of the robot, in kg.
+ self.m = 68
+ # Radius of the robot, in meters (requires tuning by hand)
+ self.rb = 0.601 / 2.0
+ # Radius of the wheels, in meters.
+ self.r = 0.097155 * 0.9811158901447808 / 118.0 * 115.75
+ # Resistance of the motor, divided by the number of motors.
+ self.resistance = 12.0 / self.stall_current
+ # Motor velocity constant
+ self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+ (12.0 - self.resistance * self.free_current))
+ # Torque constant
+ self.Kt = self.stall_torque / self.stall_current
+ # Gear ratios
+ self.G_low = 14.0 / 48.0 * 18.0 / 60.0 * 18.0 / 36.0
+ self.G_high = 14.0 / 48.0 * 28.0 / 50.0 * 18.0 / 36.0
+ if left_low:
+ self.Gl = self.G_low
+ else:
+ self.Gl = self.G_high
+ if right_low:
+ self.Gr = self.G_low
+ else:
+ self.Gr = self.G_high
+
+ # Control loop time step
+ self.dt = 0.005
+
+ # These describe the way that a given side of a robot will be influenced
+ # by the other side. Units of 1 / kg.
+ self.msp = 1.0 / self.m + self.rb * self.rb / self.J
+ self.msn = 1.0 / self.m - self.rb * self.rb / self.J
+ # The calculations which we will need for A and B.
+ self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.resistance * self.r * self.r)
+ self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.resistance * self.r * self.r)
+ self.mpl = self.Kt / (self.Gl * self.resistance * self.r)
+ self.mpr = self.Kt / (self.Gr * self.resistance * self.r)
+
+ # State feedback matrices
+ # X will be of the format
+ # [[positionl], [velocityl], [positionr], velocityr]]
+ self.A_continuous = numpy.matrix(
+ [[0, 1, 0, 0],
+ [0, self.msp * self.tcl, 0, self.msn * self.tcr],
+ [0, 0, 0, 1],
+ [0, self.msn * self.tcl, 0, self.msp * self.tcr]])
+ self.B_continuous = numpy.matrix(
+ [[0, 0],
+ [self.msp * self.mpl, self.msn * self.mpr],
+ [0, 0],
+ [self.msn * self.mpl, self.msp * self.mpr]])
+ self.C = numpy.matrix([[1, 0, 0, 0],
+ [0, 0, 1, 0]])
+ self.D = numpy.matrix([[0, 0],
+ [0, 0]])
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ if left_low or right_low:
+ q_pos = 0.12
+ q_vel = 1.0
+ else:
+ q_pos = 0.14
+ q_vel = 0.95
+
+ self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
+ [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
+ [0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
+ [0.0, 0.0, 0.0, (1.0 / (q_vel ** 2.0))]])
+
+ self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
+ [0.0, (1.0 / (12.0 ** 2.0))]])
+ self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+
+ glog.debug('DT q_pos %f q_vel %s %s', q_pos, q_vel, name)
+ glog.debug(str(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+ glog.debug('K %s', repr(self.K))
+
+ self.hlp = 0.3
+ self.llp = 0.4
+ self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
+
+ self.U_max = numpy.matrix([[12.0], [12.0]])
+ self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+ self.InitializeState()
+
+
+class KFDrivetrain(Drivetrain):
+ def __init__(self, name="KFDrivetrain", left_low=True, right_low=True):
+ super(KFDrivetrain, self).__init__(name, left_low, right_low)
+
+ self.unaugmented_A_continuous = self.A_continuous
+ self.unaugmented_B_continuous = self.B_continuous
+
+ # The states are
+ # The practical voltage applied to the wheels is
+ # V_left = U_left + left_voltage_error
+ #
+ # [left position, left velocity, right position, right velocity,
+ # left voltage error, right voltage error, angular_error]
+ #
+ # The left and right positions are filtered encoder positions and are not
+ # adjusted for heading error.
+ # The turn velocity as computed by the left and right velocities is
+ # adjusted by the gyro velocity.
+ # The angular_error is the angular velocity error between the wheel speed
+ # and the gyro speed.
+ self.A_continuous = numpy.matrix(numpy.zeros((7, 7)))
+ self.B_continuous = numpy.matrix(numpy.zeros((7, 2)))
+ self.A_continuous[0:4,0:4] = self.unaugmented_A_continuous
+ self.A_continuous[0:4,4:6] = self.unaugmented_B_continuous
+ self.B_continuous[0:4,0:2] = self.unaugmented_B_continuous
+ self.A_continuous[0,6] = 1
+ self.A_continuous[2,6] = -1
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ self.C = numpy.matrix([[1, 0, 0, 0, 0, 0, 0],
+ [0, 0, 1, 0, 0, 0, 0],
+ [0, -0.5 / self.rb, 0, 0.5 / self.rb, 0, 0, 0]])
+
+ self.D = numpy.matrix([[0, 0],
+ [0, 0],
+ [0, 0]])
+
+ q_pos = 0.05
+ q_vel = 1.00
+ q_voltage = 10.0
+ q_encoder_uncertainty = 2.00
+
+ self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
+ [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0, 0.0, 0.0],
+ [0.0, 0.0, (q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0, 0.0],
+ [0.0, 0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0), 0.0],
+ [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, (q_encoder_uncertainty ** 2.0)]])
+
+ r_pos = 0.0001
+ r_gyro = 0.000001
+ self.R = numpy.matrix([[(r_pos ** 2.0), 0.0, 0.0],
+ [0.0, (r_pos ** 2.0), 0.0],
+ [0.0, 0.0, (r_gyro ** 2.0)]])
+
+ # Solving for kf gains.
+ self.KalmanGain, self.Q_steady = controls.kalman(
+ A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+ self.L = self.A * self.KalmanGain
+
+ unaug_K = self.K
+
+ # Implement a nice closed loop controller for use by the closed loop
+ # controller.
+ self.K = numpy.matrix(numpy.zeros((self.B.shape[1], self.A.shape[0])))
+ self.K[0:2, 0:4] = unaug_K
+ self.K[0, 4] = 1.0
+ self.K[1, 5] = 1.0
+
+ self.Qff = numpy.matrix(numpy.zeros((4, 4)))
+ qff_pos = 0.005
+ qff_vel = 1.00
+ self.Qff[0, 0] = 1.0 / qff_pos ** 2.0
+ self.Qff[1, 1] = 1.0 / qff_vel ** 2.0
+ self.Qff[2, 2] = 1.0 / qff_pos ** 2.0
+ self.Qff[3, 3] = 1.0 / qff_vel ** 2.0
+ self.Kff = numpy.matrix(numpy.zeros((2, 7)))
+ self.Kff[0:2, 0:4] = controls.TwoStateFeedForwards(self.B[0:4,:], self.Qff)
+
+ self.InitializeState()
+
+
+def main(argv):
+ argv = FLAGS(argv)
+ glog.init()
+
+ # Simulate the response of the system to a step input.
+ drivetrain = Drivetrain(left_low=False, right_low=False)
+ simulated_left = []
+ simulated_right = []
+ for _ in xrange(100):
+ drivetrain.Update(numpy.matrix([[12.0], [12.0]]))
+ simulated_left.append(drivetrain.X[0, 0])
+ simulated_right.append(drivetrain.X[2, 0])
+
+ if FLAGS.plot:
+ pylab.plot(range(100), simulated_left)
+ pylab.plot(range(100), simulated_right)
+ pylab.suptitle('Acceleration Test')
+ pylab.show()
+
+ # Simulate forwards motion.
+ drivetrain = Drivetrain(left_low=False, right_low=False)
+ close_loop_left = []
+ close_loop_right = []
+ left_power = []
+ right_power = []
+ R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
+ for _ in xrange(300):
+ U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+ drivetrain.U_min, drivetrain.U_max)
+ drivetrain.UpdateObserver(U)
+ drivetrain.Update(U)
+ close_loop_left.append(drivetrain.X[0, 0])
+ close_loop_right.append(drivetrain.X[2, 0])
+ left_power.append(U[0, 0])
+ right_power.append(U[1, 0])
+
+ if FLAGS.plot:
+ pylab.plot(range(300), close_loop_left, label='left position')
+ pylab.plot(range(300), close_loop_right, label='right position')
+ pylab.plot(range(300), left_power, label='left power')
+ pylab.plot(range(300), right_power, label='right power')
+ pylab.suptitle('Linear Move')
+ pylab.legend()
+ pylab.show()
+
+ # Try turning in place
+ drivetrain = Drivetrain()
+ close_loop_left = []
+ close_loop_right = []
+ R = numpy.matrix([[-1.0], [0.0], [1.0], [0.0]])
+ for _ in xrange(100):
+ U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+ drivetrain.U_min, drivetrain.U_max)
+ drivetrain.UpdateObserver(U)
+ drivetrain.Update(U)
+ close_loop_left.append(drivetrain.X[0, 0])
+ close_loop_right.append(drivetrain.X[2, 0])
+
+ if FLAGS.plot:
+ pylab.plot(range(100), close_loop_left)
+ pylab.plot(range(100), close_loop_right)
+ pylab.suptitle('Angular Move')
+ pylab.show()
+
+ # Try turning just one side.
+ drivetrain = Drivetrain()
+ close_loop_left = []
+ close_loop_right = []
+ R = numpy.matrix([[0.0], [0.0], [1.0], [0.0]])
+ for _ in xrange(100):
+ U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
+ drivetrain.U_min, drivetrain.U_max)
+ drivetrain.UpdateObserver(U)
+ drivetrain.Update(U)
+ close_loop_left.append(drivetrain.X[0, 0])
+ close_loop_right.append(drivetrain.X[2, 0])
+
+ if FLAGS.plot:
+ pylab.plot(range(100), close_loop_left)
+ pylab.plot(range(100), close_loop_right)
+ pylab.suptitle('Pivot')
+ pylab.show()
+
+ # Write the generated constants out to a file.
+ drivetrain_low_low = Drivetrain(
+ name="DrivetrainLowLow", left_low=True, right_low=True)
+ drivetrain_low_high = Drivetrain(
+ name="DrivetrainLowHigh", left_low=True, right_low=False)
+ drivetrain_high_low = Drivetrain(
+ name="DrivetrainHighLow", left_low=False, right_low=True)
+ drivetrain_high_high = Drivetrain(
+ name="DrivetrainHighHigh", left_low=False, right_low=False)
+
+ kf_drivetrain_low_low = KFDrivetrain(
+ name="KFDrivetrainLowLow", left_low=True, right_low=True)
+ kf_drivetrain_low_high = KFDrivetrain(
+ name="KFDrivetrainLowHigh", left_low=True, right_low=False)
+ kf_drivetrain_high_low = KFDrivetrain(
+ name="KFDrivetrainHighLow", left_low=False, right_low=True)
+ kf_drivetrain_high_high = KFDrivetrain(
+ name="KFDrivetrainHighHigh", left_low=False, right_low=False)
+
+ if len(argv) != 5:
+ print "Expected .h file name and .cc file name"
+ else:
+ namespaces = ['y2016_bot3', 'control_loops', 'drivetrain']
+ dog_loop_writer = control_loop.ControlLoopWriter(
+ "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
+ drivetrain_high_low, drivetrain_high_high],
+ namespaces = namespaces)
+ dog_loop_writer.AddConstant(control_loop.Constant("kDt", "%f",
+ drivetrain_low_low.dt))
+ dog_loop_writer.AddConstant(control_loop.Constant("kStallTorque", "%f",
+ drivetrain_low_low.stall_torque))
+ dog_loop_writer.AddConstant(control_loop.Constant("kStallCurrent", "%f",
+ drivetrain_low_low.stall_current))
+ dog_loop_writer.AddConstant(control_loop.Constant("kFreeSpeedRPM", "%f",
+ drivetrain_low_low.free_speed))
+ dog_loop_writer.AddConstant(control_loop.Constant("kFreeCurrent", "%f",
+ drivetrain_low_low.free_current))
+ dog_loop_writer.AddConstant(control_loop.Constant("kJ", "%f",
+ drivetrain_low_low.J))
+ dog_loop_writer.AddConstant(control_loop.Constant("kMass", "%f",
+ drivetrain_low_low.m))
+ dog_loop_writer.AddConstant(control_loop.Constant("kRobotRadius", "%f",
+ drivetrain_low_low.rb))
+ dog_loop_writer.AddConstant(control_loop.Constant("kWheelRadius", "%f",
+ drivetrain_low_low.r))
+ dog_loop_writer.AddConstant(control_loop.Constant("kR", "%f",
+ drivetrain_low_low.resistance))
+ dog_loop_writer.AddConstant(control_loop.Constant("kV", "%f",
+ drivetrain_low_low.Kv))
+ dog_loop_writer.AddConstant(control_loop.Constant("kT", "%f",
+ drivetrain_low_low.Kt))
+ dog_loop_writer.AddConstant(control_loop.Constant("kLowGearRatio", "%f",
+ drivetrain_low_low.G_low))
+ dog_loop_writer.AddConstant(control_loop.Constant("kHighGearRatio", "%f",
+ drivetrain_high_high.G_high))
+
+ dog_loop_writer.Write(argv[1], argv[2])
+
+ kf_loop_writer = control_loop.ControlLoopWriter(
+ "KFDrivetrain", [kf_drivetrain_low_low, kf_drivetrain_low_high,
+ kf_drivetrain_high_low, kf_drivetrain_high_high],
+ namespaces = namespaces)
+ kf_loop_writer.Write(argv[3], argv[4])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2016_bot3/control_loops/python/intake.py b/y2016_bot3/control_loops/python/intake.py
new file mode 100755
index 0000000..fa34063
--- /dev/null
+++ b/y2016_bot3/control_loops/python/intake.py
@@ -0,0 +1,314 @@
+#!/usr/bin/python
+
+from aos.common.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+import numpy
+import sys
+import matplotlib
+from matplotlib import pylab
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+class Intake(control_loop.ControlLoop):
+ def __init__(self, name="Intake"):
+ super(Intake, self).__init__(name)
+ # TODO(constants): Update all of these & retune poles.
+ # Stall Torque in N m
+ self.stall_torque = 0.71
+ # Stall Current in Amps
+ self.stall_current = 134
+ # Free Speed in RPM
+ self.free_speed = 18730
+ # Free Current in Amps
+ self.free_current = 0.7
+
+ # Resistance of the motor
+ self.R = 12.0 / self.stall_current
+ # Motor velocity constant
+ self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
+ (12.0 - self.R * self.free_current))
+ # Torque constant
+ self.Kt = self.stall_torque / self.stall_current
+ # Gear ratio
+ self.G = (56.0 / 12.0) * (54.0 / 14.0) * (64.0 / 18.0) * (48.0 / 16.0)
+
+ # Moment of inertia, measured in CAD.
+ # Extra mass to compensate for friction is added on.
+ self.J = 0.34 + 0.40
+
+ # Control loop time step
+ self.dt = 0.005
+
+ # State is [position, velocity]
+ # Input is [Voltage]
+
+ C1 = self.G * self.G * self.Kt / (self.R * self.J * self.Kv)
+ C2 = self.Kt * self.G / (self.J * self.R)
+
+ self.A_continuous = numpy.matrix(
+ [[0, 1],
+ [0, -C1]])
+
+ # Start with the unmodified input
+ self.B_continuous = numpy.matrix(
+ [[0],
+ [C2]])
+
+ self.C = numpy.matrix([[1, 0]])
+ self.D = numpy.matrix([[0]])
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ controllability = controls.ctrb(self.A, self.B)
+
+ glog.debug("Free speed is %f", self.free_speed * numpy.pi * 2.0 / 60.0 / self.G)
+
+ q_pos = 0.20
+ q_vel = 5.0
+ self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
+ [0.0, (1.0 / (q_vel ** 2.0))]])
+
+ self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
+ self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
+
+ q_pos_ff = 0.005
+ q_vel_ff = 1.0
+ self.Qff = numpy.matrix([[(1.0 / (q_pos_ff ** 2.0)), 0.0],
+ [0.0, (1.0 / (q_vel_ff ** 2.0))]])
+
+ self.Kff = controls.TwoStateFeedForwards(self.B, self.Qff)
+
+ glog.debug('K %s', repr(self.K))
+ glog.debug('Poles are %s',
+ repr(numpy.linalg.eig(self.A - self.B * self.K)[0]))
+
+ self.rpl = 0.30
+ self.ipl = 0.10
+ self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+ self.rpl - 1j * self.ipl])
+
+ glog.debug('L is %s', repr(self.L))
+
+ q_pos = 0.10
+ q_vel = 1.65
+ self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0],
+ [0.0, (q_vel ** 2.0)]])
+
+ r_volts = 0.025
+ self.R = numpy.matrix([[(r_volts ** 2.0)]])
+
+ self.KalmanGain, self.Q_steady = controls.kalman(
+ A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+ glog.debug('Kal %s', repr(self.KalmanGain))
+ self.L = self.A * self.KalmanGain
+ glog.debug('KalL is %s', repr(self.L))
+
+ # The box formed by U_min and U_max must encompass all possible values,
+ # or else Austin's code gets angry.
+ self.U_max = numpy.matrix([[12.0]])
+ self.U_min = numpy.matrix([[-12.0]])
+
+ self.InitializeState()
+
+class IntegralIntake(Intake):
+ def __init__(self, name="IntegralIntake"):
+ super(IntegralIntake, self).__init__(name=name)
+
+ self.A_continuous_unaugmented = self.A_continuous
+ self.B_continuous_unaugmented = self.B_continuous
+
+ self.A_continuous = numpy.matrix(numpy.zeros((3, 3)))
+ self.A_continuous[0:2, 0:2] = self.A_continuous_unaugmented
+ self.A_continuous[0:2, 2] = self.B_continuous_unaugmented
+
+ self.B_continuous = numpy.matrix(numpy.zeros((3, 1)))
+ self.B_continuous[0:2, 0] = self.B_continuous_unaugmented
+
+ self.C_unaugmented = self.C
+ self.C = numpy.matrix(numpy.zeros((1, 3)))
+ self.C[0:1, 0:2] = self.C_unaugmented
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ q_pos = 0.12
+ q_vel = 2.00
+ q_voltage = 4.0
+ self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0],
+ [0.0, (q_vel ** 2.0), 0.0],
+ [0.0, 0.0, (q_voltage ** 2.0)]])
+
+ r_pos = 0.05
+ self.R = numpy.matrix([[(r_pos ** 2.0)]])
+
+ self.KalmanGain, self.Q_steady = controls.kalman(
+ A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+ self.L = self.A * self.KalmanGain
+
+ self.K_unaugmented = self.K
+ self.K = numpy.matrix(numpy.zeros((1, 3)))
+ self.K[0, 0:2] = self.K_unaugmented
+ self.K[0, 2] = 1
+
+ self.Kff = numpy.concatenate((self.Kff, numpy.matrix(numpy.zeros((1, 1)))), axis=1)
+
+ self.InitializeState()
+
+class ScenarioPlotter(object):
+ def __init__(self):
+ # Various lists for graphing things.
+ self.t = []
+ self.x = []
+ self.v = []
+ self.a = []
+ self.x_hat = []
+ self.u = []
+ self.offset = []
+
+ def run_test(self, intake, end_goal,
+ controller_intake,
+ observer_intake=None,
+ iterations=200):
+ """Runs the intake plant with an initial condition and goal.
+
+ Args:
+ intake: intake object to use.
+ end_goal: end_goal state.
+ controller_intake: Intake object to get K from, or None if we should
+ use intake.
+ observer_intake: Intake object to use for the observer, or None if we should
+ use the actual state.
+ iterations: Number of timesteps to run the model for.
+ """
+
+ if controller_intake is None:
+ controller_intake = intake
+
+ vbat = 12.0
+
+ if self.t:
+ initial_t = self.t[-1] + intake.dt
+ else:
+ initial_t = 0
+
+ goal = numpy.concatenate((intake.X, numpy.matrix(numpy.zeros((1, 1)))), axis=0)
+
+ profile = TrapezoidProfile(intake.dt)
+ profile.set_maximum_acceleration(70.0)
+ profile.set_maximum_velocity(10.0)
+ profile.SetGoal(goal[0, 0])
+
+ U_last = numpy.matrix(numpy.zeros((1, 1)))
+ for i in xrange(iterations):
+ observer_intake.Y = intake.Y
+ observer_intake.CorrectObserver(U_last)
+
+ self.offset.append(observer_intake.X_hat[2, 0])
+ self.x_hat.append(observer_intake.X_hat[0, 0])
+
+ next_goal = numpy.concatenate(
+ (profile.Update(end_goal[0, 0], end_goal[1, 0]),
+ numpy.matrix(numpy.zeros((1, 1)))),
+ axis=0)
+
+ ff_U = controller_intake.Kff * (next_goal - observer_intake.A * goal)
+
+ U_uncapped = controller_intake.K * (goal - observer_intake.X_hat) + ff_U
+ U = U_uncapped.copy()
+ U[0, 0] = numpy.clip(U[0, 0], -vbat, vbat)
+ self.x.append(intake.X[0, 0])
+
+ if self.v:
+ last_v = self.v[-1]
+ else:
+ last_v = 0
+
+ self.v.append(intake.X[1, 0])
+ self.a.append((self.v[-1] - last_v) / intake.dt)
+
+ offset = 0.0
+ if i > 100:
+ offset = 2.0
+ intake.Update(U + offset)
+
+ observer_intake.PredictObserver(U)
+
+ self.t.append(initial_t + i * intake.dt)
+ self.u.append(U[0, 0])
+
+ ff_U -= U_uncapped - U
+ goal = controller_intake.A * goal + controller_intake.B * ff_U
+
+ if U[0, 0] != U_uncapped[0, 0]:
+ profile.MoveCurrentState(
+ numpy.matrix([[goal[0, 0]], [goal[1, 0]]]))
+
+ glog.debug('Time: %f', self.t[-1])
+ glog.debug('goal_error %s', repr(end_goal - goal))
+ glog.debug('error %s', repr(observer_intake.X_hat - end_goal))
+
+ def Plot(self):
+ pylab.subplot(3, 1, 1)
+ pylab.plot(self.t, self.x, label='x')
+ pylab.plot(self.t, self.x_hat, label='x_hat')
+ pylab.legend()
+
+ pylab.subplot(3, 1, 2)
+ pylab.plot(self.t, self.u, label='u')
+ pylab.plot(self.t, self.offset, label='voltage_offset')
+ pylab.legend()
+
+ pylab.subplot(3, 1, 3)
+ pylab.plot(self.t, self.a, label='a')
+ pylab.legend()
+
+ pylab.show()
+
+
+def main(argv):
+ argv = FLAGS(argv)
+ glog.init()
+
+ scenario_plotter = ScenarioPlotter()
+
+ intake = Intake()
+ intake_controller = IntegralIntake()
+ observer_intake = IntegralIntake()
+
+ # Test moving the intake with constant separation.
+ initial_X = numpy.matrix([[0.0], [0.0]])
+ R = numpy.matrix([[numpy.pi/2.0], [0.0], [0.0]])
+ scenario_plotter.run_test(intake, end_goal=R,
+ controller_intake=intake_controller,
+ observer_intake=observer_intake, iterations=200)
+
+ if FLAGS.plot:
+ scenario_plotter.Plot()
+
+ # Write the generated constants out to a file.
+ if len(argv) != 5:
+ glog.fatal('Expected .h file name and .cc file name for the intake and integral intake.')
+ else:
+ namespaces = ['y2016_bot3', 'control_loops', 'intake']
+ intake = Intake("Intake")
+ loop_writer = control_loop.ControlLoopWriter('Intake', [intake],
+ namespaces=namespaces)
+ loop_writer.Write(argv[1], argv[2])
+
+ integral_intake = IntegralIntake("IntegralIntake")
+ integral_loop_writer = control_loop.ControlLoopWriter("IntegralIntake", [integral_intake],
+ namespaces=namespaces)
+ integral_loop_writer.Write(argv[3], argv[4])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2016_bot3/control_loops/python/polydrivetrain.py b/y2016_bot3/control_loops/python/polydrivetrain.py
new file mode 100755
index 0000000..ac85bb6
--- /dev/null
+++ b/y2016_bot3/control_loops/python/polydrivetrain.py
@@ -0,0 +1,501 @@
+#!/usr/bin/python
+
+import numpy
+import sys
+from frc971.control_loops.python import polytope
+from y2016_bot3.control_loops.python import drivetrain
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import controls
+from matplotlib import pylab
+
+import gflags
+import glog
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+def CoerceGoal(region, K, w, R):
+ """Intersects a line with a region, and finds the closest point to R.
+
+ Finds a point that is closest to R inside the region, and on the line
+ defined by K X = w. If it is not possible to find a point on the line,
+ finds a point that is inside the region and closest to the line. This
+ function assumes that
+
+ Args:
+ region: HPolytope, the valid goal region.
+ K: numpy.matrix (2 x 1), the matrix for the equation [K1, K2] [x1; x2] = w
+ w: float, the offset in the equation above.
+ R: numpy.matrix (2 x 1), the point to be closest to.
+
+ Returns:
+ numpy.matrix (2 x 1), the point.
+ """
+ return DoCoerceGoal(region, K, w, R)[0]
+
+def DoCoerceGoal(region, K, w, R):
+ if region.IsInside(R):
+ return (R, True)
+
+ perpendicular_vector = K.T / numpy.linalg.norm(K)
+ parallel_vector = numpy.matrix([[perpendicular_vector[1, 0]],
+ [-perpendicular_vector[0, 0]]])
+
+ # We want to impose the constraint K * X = w on the polytope H * X <= k.
+ # We do this by breaking X up into parallel and perpendicular components to
+ # the half plane. This gives us the following equation.
+ #
+ # parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) = X
+ #
+ # Then, substitute this into the polytope.
+ #
+ # H * (parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) <= k
+ #
+ # Substitute K * X = w
+ #
+ # H * parallel * (parallel.T \dot X) + H * perpendicular * w <= k
+ #
+ # Move all the knowns to the right side.
+ #
+ # H * parallel * ([parallel1 parallel2] * X) <= k - H * perpendicular * w
+ #
+ # Let t = parallel.T \dot X, the component parallel to the surface.
+ #
+ # H * parallel * t <= k - H * perpendicular * w
+ #
+ # This is a polytope which we can solve, and use to figure out the range of X
+ # that we care about!
+
+ t_poly = polytope.HPolytope(
+ region.H * parallel_vector,
+ region.k - region.H * perpendicular_vector * w)
+
+ vertices = t_poly.Vertices()
+
+ if vertices.shape[0]:
+ # The region exists!
+ # Find the closest vertex
+ min_distance = numpy.infty
+ closest_point = None
+ for vertex in vertices:
+ point = parallel_vector * vertex + perpendicular_vector * w
+ length = numpy.linalg.norm(R - point)
+ if length < min_distance:
+ min_distance = length
+ closest_point = point
+
+ return (closest_point, True)
+ else:
+ # Find the vertex of the space that is closest to the line.
+ region_vertices = region.Vertices()
+ min_distance = numpy.infty
+ closest_point = None
+ for vertex in region_vertices:
+ point = vertex.T
+ length = numpy.abs((perpendicular_vector.T * point)[0, 0])
+ if length < min_distance:
+ min_distance = length
+ closest_point = point
+
+ return (closest_point, False)
+
+
+class VelocityDrivetrainModel(control_loop.ControlLoop):
+ def __init__(self, left_low=True, right_low=True, name="VelocityDrivetrainModel"):
+ super(VelocityDrivetrainModel, self).__init__(name)
+ self._drivetrain = drivetrain.Drivetrain(left_low=left_low,
+ right_low=right_low)
+ self.dt = 0.005
+ self.A_continuous = numpy.matrix(
+ [[self._drivetrain.A_continuous[1, 1], self._drivetrain.A_continuous[1, 3]],
+ [self._drivetrain.A_continuous[3, 1], self._drivetrain.A_continuous[3, 3]]])
+
+ self.B_continuous = numpy.matrix(
+ [[self._drivetrain.B_continuous[1, 0], self._drivetrain.B_continuous[1, 1]],
+ [self._drivetrain.B_continuous[3, 0], self._drivetrain.B_continuous[3, 1]]])
+ self.C = numpy.matrix(numpy.eye(2))
+ self.D = numpy.matrix(numpy.zeros((2, 2)))
+
+ self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
+ self.B_continuous, self.dt)
+
+ # FF * X = U (steady state)
+ self.FF = self.B.I * (numpy.eye(2) - self.A)
+
+ self.PlaceControllerPoles([0.67, 0.67])
+ self.PlaceObserverPoles([0.02, 0.02])
+
+ self.G_high = self._drivetrain.G_high
+ self.G_low = self._drivetrain.G_low
+ self.resistance = self._drivetrain.resistance
+ self.r = self._drivetrain.r
+ self.Kv = self._drivetrain.Kv
+ self.Kt = self._drivetrain.Kt
+
+ self.U_max = self._drivetrain.U_max
+ self.U_min = self._drivetrain.U_min
+
+
+class VelocityDrivetrain(object):
+ HIGH = 'high'
+ LOW = 'low'
+ SHIFTING_UP = 'up'
+ SHIFTING_DOWN = 'down'
+
+ def __init__(self):
+ self.drivetrain_low_low = VelocityDrivetrainModel(
+ left_low=True, right_low=True, name='VelocityDrivetrainLowLow')
+ self.drivetrain_low_high = VelocityDrivetrainModel(left_low=True, right_low=False, name='VelocityDrivetrainLowHigh')
+ self.drivetrain_high_low = VelocityDrivetrainModel(left_low=False, right_low=True, name = 'VelocityDrivetrainHighLow')
+ self.drivetrain_high_high = VelocityDrivetrainModel(left_low=False, right_low=False, name = 'VelocityDrivetrainHighHigh')
+
+ # X is [lvel, rvel]
+ self.X = numpy.matrix(
+ [[0.0],
+ [0.0]])
+
+ self.U_poly = polytope.HPolytope(
+ numpy.matrix([[1, 0],
+ [-1, 0],
+ [0, 1],
+ [0, -1]]),
+ numpy.matrix([[12],
+ [12],
+ [12],
+ [12]]))
+
+ self.U_max = numpy.matrix(
+ [[12.0],
+ [12.0]])
+ self.U_min = numpy.matrix(
+ [[-12.0000000000],
+ [-12.0000000000]])
+
+ self.dt = 0.005
+
+ self.R = numpy.matrix(
+ [[0.0],
+ [0.0]])
+
+ self.U_ideal = numpy.matrix(
+ [[0.0],
+ [0.0]])
+
+ # ttrust is the comprimise between having full throttle negative inertia,
+ # and having no throttle negative inertia. A value of 0 is full throttle
+ # inertia. A value of 1 is no throttle negative inertia.
+ self.ttrust = 1.0
+
+ self.left_gear = VelocityDrivetrain.LOW
+ self.right_gear = VelocityDrivetrain.LOW
+ self.left_shifter_position = 0.0
+ self.right_shifter_position = 0.0
+ self.left_cim = drivetrain.CIM()
+ self.right_cim = drivetrain.CIM()
+
+ def IsInGear(self, gear):
+ return gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.LOW
+
+ def MotorRPM(self, shifter_position, velocity):
+ if shifter_position > 0.5:
+ return (velocity / self.CurrentDrivetrain().G_high /
+ self.CurrentDrivetrain().r)
+ else:
+ return (velocity / self.CurrentDrivetrain().G_low /
+ self.CurrentDrivetrain().r)
+
+ def CurrentDrivetrain(self):
+ if self.left_shifter_position > 0.5:
+ if self.right_shifter_position > 0.5:
+ return self.drivetrain_high_high
+ else:
+ return self.drivetrain_high_low
+ else:
+ if self.right_shifter_position > 0.5:
+ return self.drivetrain_low_high
+ else:
+ return self.drivetrain_low_low
+
+ def SimShifter(self, gear, shifter_position):
+ if gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.SHIFTING_UP:
+ shifter_position = min(shifter_position + 0.5, 1.0)
+ else:
+ shifter_position = max(shifter_position - 0.5, 0.0)
+
+ if shifter_position == 1.0:
+ gear = VelocityDrivetrain.HIGH
+ elif shifter_position == 0.0:
+ gear = VelocityDrivetrain.LOW
+
+ return gear, shifter_position
+
+ def ComputeGear(self, wheel_velocity, should_print=False, current_gear=False, gear_name=None):
+ high_omega = (wheel_velocity / self.CurrentDrivetrain().G_high /
+ self.CurrentDrivetrain().r)
+ low_omega = (wheel_velocity / self.CurrentDrivetrain().G_low /
+ self.CurrentDrivetrain().r)
+ #print gear_name, "Motor Energy Difference.", 0.5 * 0.000140032647 * (low_omega * low_omega - high_omega * high_omega), "joules"
+ high_torque = ((12.0 - high_omega / self.CurrentDrivetrain().Kv) *
+ self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().resistance)
+ low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
+ self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().resistance)
+ high_power = high_torque * high_omega
+ low_power = low_torque * low_omega
+ #if should_print:
+ # print gear_name, "High omega", high_omega, "Low omega", low_omega
+ # print gear_name, "High torque", high_torque, "Low torque", low_torque
+ # print gear_name, "High power", high_power, "Low power", low_power
+
+ # Shift algorithm improvements.
+ # TODO(aschuh):
+ # It takes time to shift. Shifting down for 1 cycle doesn't make sense
+ # because you will end up slower than without shifting. Figure out how
+ # to include that info.
+ # If the driver is still in high gear, but isn't asking for the extra power
+ # from low gear, don't shift until he asks for it.
+ goal_gear_is_high = high_power > low_power
+ #goal_gear_is_high = True
+
+ if not self.IsInGear(current_gear):
+ glog.debug('%s Not in gear.', gear_name)
+ return current_gear
+ else:
+ is_high = current_gear is VelocityDrivetrain.HIGH
+ if is_high != goal_gear_is_high:
+ if goal_gear_is_high:
+ glog.debug('%s Shifting up.', gear_name)
+ return VelocityDrivetrain.SHIFTING_UP
+ else:
+ glog.debug('%s Shifting down.', gear_name)
+ return VelocityDrivetrain.SHIFTING_DOWN
+ else:
+ return current_gear
+
+ def FilterVelocity(self, throttle):
+ # Invert the plant to figure out how the velocity filter would have to work
+ # out in order to filter out the forwards negative inertia.
+ # This math assumes that the left and right power and velocity are equal.
+
+ # The throttle filter should filter such that the motor in the highest gear
+ # should be controlling the time constant.
+ # Do this by finding the index of FF that has the lowest value, and computing
+ # the sums using that index.
+ FF_sum = self.CurrentDrivetrain().FF.sum(axis=1)
+ min_FF_sum_index = numpy.argmin(FF_sum)
+ min_FF_sum = FF_sum[min_FF_sum_index, 0]
+ min_K_sum = self.CurrentDrivetrain().K[min_FF_sum_index, :].sum()
+ # Compute the FF sum for high gear.
+ high_min_FF_sum = self.drivetrain_high_high.FF[0, :].sum()
+
+ # U = self.K[0, :].sum() * (R - x_avg) + self.FF[0, :].sum() * R
+ # throttle * 12.0 = (self.K[0, :].sum() + self.FF[0, :].sum()) * R
+ # - self.K[0, :].sum() * x_avg
+
+ # R = (throttle * 12.0 + self.K[0, :].sum() * x_avg) /
+ # (self.K[0, :].sum() + self.FF[0, :].sum())
+
+ # U = (K + FF) * R - K * X
+ # (K + FF) ^-1 * (U + K * X) = R
+
+ # Scale throttle by min_FF_sum / high_min_FF_sum. This will make low gear
+ # have the same velocity goal as high gear, and so that the robot will hold
+ # the same speed for the same throttle for all gears.
+ adjusted_ff_voltage = numpy.clip(throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0)
+ return ((adjusted_ff_voltage + self.ttrust * min_K_sum * (self.X[0, 0] + self.X[1, 0]) / 2.0)
+ / (self.ttrust * min_K_sum + min_FF_sum))
+
+ def Update(self, throttle, steering):
+ # Shift into the gear which sends the most power to the floor.
+ # This is the same as sending the most torque down to the floor at the
+ # wheel.
+
+ self.left_gear = self.right_gear = True
+ if True:
+ self.left_gear = self.ComputeGear(self.X[0, 0], should_print=True,
+ current_gear=self.left_gear,
+ gear_name="left")
+ self.right_gear = self.ComputeGear(self.X[1, 0], should_print=True,
+ current_gear=self.right_gear,
+ gear_name="right")
+ if self.IsInGear(self.left_gear):
+ self.left_cim.X[0, 0] = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
+
+ if self.IsInGear(self.right_gear):
+ self.right_cim.X[0, 0] = self.MotorRPM(self.right_shifter_position, self.X[0, 0])
+
+ if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+ # Filter the throttle to provide a nicer response.
+ fvel = self.FilterVelocity(throttle)
+
+ # Constant radius means that angualar_velocity / linear_velocity = constant.
+ # Compute the left and right velocities.
+ steering_velocity = numpy.abs(fvel) * steering
+ left_velocity = fvel - steering_velocity
+ right_velocity = fvel + steering_velocity
+
+ # Write this constraint in the form of K * R = w
+ # angular velocity / linear velocity = constant
+ # (left - right) / (left + right) = constant
+ # left - right = constant * left + constant * right
+
+ # (fvel - steering * numpy.abs(fvel) - fvel - steering * numpy.abs(fvel)) /
+ # (fvel - steering * numpy.abs(fvel) + fvel + steering * numpy.abs(fvel)) =
+ # constant
+ # (- 2 * steering * numpy.abs(fvel)) / (2 * fvel) = constant
+ # (-steering * sign(fvel)) = constant
+ # (-steering * sign(fvel)) * (left + right) = left - right
+ # (steering * sign(fvel) + 1) * left + (steering * sign(fvel) - 1) * right = 0
+
+ equality_k = numpy.matrix(
+ [[1 + steering * numpy.sign(fvel), -(1 - steering * numpy.sign(fvel))]])
+ equality_w = 0.0
+
+ self.R[0, 0] = left_velocity
+ self.R[1, 0] = right_velocity
+
+ # Construct a constraint on R by manipulating the constraint on U
+ # Start out with H * U <= k
+ # U = FF * R + K * (R - X)
+ # H * (FF * R + K * R - K * X) <= k
+ # H * (FF + K) * R <= k + H * K * X
+ R_poly = polytope.HPolytope(
+ self.U_poly.H * (self.CurrentDrivetrain().K + self.CurrentDrivetrain().FF),
+ self.U_poly.k + self.U_poly.H * self.CurrentDrivetrain().K * self.X)
+
+ # Limit R back inside the box.
+ self.boxed_R = CoerceGoal(R_poly, equality_k, equality_w, self.R)
+
+ FF_volts = self.CurrentDrivetrain().FF * self.boxed_R
+ self.U_ideal = self.CurrentDrivetrain().K * (self.boxed_R - self.X) + FF_volts
+ else:
+ glog.debug('Not all in gear')
+ if not self.IsInGear(self.left_gear) and not self.IsInGear(self.right_gear):
+ # TODO(austin): Use battery volts here.
+ R_left = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
+ self.U_ideal[0, 0] = numpy.clip(
+ self.left_cim.K * (R_left - self.left_cim.X) + R_left / self.left_cim.Kv,
+ self.left_cim.U_min, self.left_cim.U_max)
+ self.left_cim.Update(self.U_ideal[0, 0])
+
+ R_right = self.MotorRPM(self.right_shifter_position, self.X[1, 0])
+ self.U_ideal[1, 0] = numpy.clip(
+ self.right_cim.K * (R_right - self.right_cim.X) + R_right / self.right_cim.Kv,
+ self.right_cim.U_min, self.right_cim.U_max)
+ self.right_cim.Update(self.U_ideal[1, 0])
+ else:
+ assert False
+
+ self.U = numpy.clip(self.U_ideal, self.U_min, self.U_max)
+
+ # TODO(austin): Model the robot as not accelerating when you shift...
+ # This hack only works when you shift at the same time.
+ if self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
+ self.X = self.CurrentDrivetrain().A * self.X + self.CurrentDrivetrain().B * self.U
+
+ self.left_gear, self.left_shifter_position = self.SimShifter(
+ self.left_gear, self.left_shifter_position)
+ self.right_gear, self.right_shifter_position = self.SimShifter(
+ self.right_gear, self.right_shifter_position)
+
+ glog.debug('U is %s %s', str(self.U[0, 0]), str(self.U[1, 0]))
+ glog.debug('Left shifter %s %d Right shifter %s %d',
+ self.left_gear, self.left_shifter_position,
+ self.right_gear, self.right_shifter_position)
+
+
+def main(argv):
+ argv = FLAGS(argv)
+
+ vdrivetrain = VelocityDrivetrain()
+
+ if not FLAGS.plot:
+ if len(argv) != 5:
+ glog.fatal('Expected .h file name and .cc file name')
+ else:
+ namespaces = ['y2016_bot3', 'control_loops', 'drivetrain']
+ dog_loop_writer = control_loop.ControlLoopWriter(
+ "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
+ vdrivetrain.drivetrain_low_high,
+ vdrivetrain.drivetrain_high_low,
+ vdrivetrain.drivetrain_high_high],
+ namespaces=namespaces)
+
+ dog_loop_writer.Write(argv[1], argv[2])
+
+ cim_writer = control_loop.ControlLoopWriter(
+ "CIM", [drivetrain.CIM()])
+
+ cim_writer.Write(argv[3], argv[4])
+ return
+
+ vl_plot = []
+ vr_plot = []
+ ul_plot = []
+ ur_plot = []
+ radius_plot = []
+ t_plot = []
+ left_gear_plot = []
+ right_gear_plot = []
+ vdrivetrain.left_shifter_position = 0.0
+ vdrivetrain.right_shifter_position = 0.0
+ vdrivetrain.left_gear = VelocityDrivetrain.LOW
+ vdrivetrain.right_gear = VelocityDrivetrain.LOW
+
+ glog.debug('K is %s', str(vdrivetrain.CurrentDrivetrain().K))
+
+ if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
+ glog.debug('Left is high')
+ else:
+ glog.debug('Left is low')
+ if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
+ glog.debug('Right is high')
+ else:
+ glog.debug('Right is low')
+
+ for t in numpy.arange(0, 1.7, vdrivetrain.dt):
+ if t < 0.5:
+ vdrivetrain.Update(throttle=0.00, steering=1.0)
+ elif t < 1.2:
+ vdrivetrain.Update(throttle=0.5, steering=1.0)
+ else:
+ vdrivetrain.Update(throttle=0.00, steering=1.0)
+ t_plot.append(t)
+ vl_plot.append(vdrivetrain.X[0, 0])
+ vr_plot.append(vdrivetrain.X[1, 0])
+ ul_plot.append(vdrivetrain.U[0, 0])
+ ur_plot.append(vdrivetrain.U[1, 0])
+ left_gear_plot.append((vdrivetrain.left_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
+ right_gear_plot.append((vdrivetrain.right_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
+
+ fwd_velocity = (vdrivetrain.X[1, 0] + vdrivetrain.X[0, 0]) / 2
+ turn_velocity = (vdrivetrain.X[1, 0] - vdrivetrain.X[0, 0])
+ if abs(fwd_velocity) < 0.0000001:
+ radius_plot.append(turn_velocity)
+ else:
+ radius_plot.append(turn_velocity / fwd_velocity)
+
+ # TODO(austin):
+ # Shifting compensation.
+
+ # Tighten the turn.
+ # Closed loop drive.
+
+ pylab.plot(t_plot, vl_plot, label='left velocity')
+ pylab.plot(t_plot, vr_plot, label='right velocity')
+ pylab.plot(t_plot, ul_plot, label='left voltage')
+ pylab.plot(t_plot, ur_plot, label='right voltage')
+ pylab.plot(t_plot, radius_plot, label='radius')
+ pylab.plot(t_plot, left_gear_plot, label='left gear high')
+ pylab.plot(t_plot, right_gear_plot, label='right gear high')
+ pylab.legend()
+ pylab.show()
+ return 0
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2016_bot3/control_loops/python/polydrivetrain_test.py b/y2016_bot3/control_loops/python/polydrivetrain_test.py
new file mode 100755
index 0000000..434cdca
--- /dev/null
+++ b/y2016_bot3/control_loops/python/polydrivetrain_test.py
@@ -0,0 +1,82 @@
+#!/usr/bin/python
+
+import polydrivetrain
+import numpy
+from numpy.testing import *
+import polytope
+import unittest
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+
+class TestVelocityDrivetrain(unittest.TestCase):
+ def MakeBox(self, x1_min, x1_max, x2_min, x2_max):
+ H = numpy.matrix([[1, 0],
+ [-1, 0],
+ [0, 1],
+ [0, -1]])
+ K = numpy.matrix([[x1_max],
+ [-x1_min],
+ [x2_max],
+ [-x2_min]])
+ return polytope.HPolytope(H, K)
+
+ def test_coerce_inside(self):
+ """Tests coercion when the point is inside the box."""
+ box = self.MakeBox(1, 2, 1, 2)
+
+ # x1 = x2
+ K = numpy.matrix([[1, -1]])
+ w = 0
+
+ assert_array_equal(polydrivetrain.CoerceGoal(box, K, w,
+ numpy.matrix([[1.5], [1.5]])),
+ numpy.matrix([[1.5], [1.5]]))
+
+ def test_coerce_outside_intersect(self):
+ """Tests coercion when the line intersects the box."""
+ box = self.MakeBox(1, 2, 1, 2)
+
+ # x1 = x2
+ K = numpy.matrix([[1, -1]])
+ w = 0
+
+ assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+ numpy.matrix([[2.0], [2.0]]))
+
+ def test_coerce_outside_no_intersect(self):
+ """Tests coercion when the line does not intersect the box."""
+ box = self.MakeBox(3, 4, 1, 2)
+
+ # x1 = x2
+ K = numpy.matrix([[1, -1]])
+ w = 0
+
+ assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+ numpy.matrix([[3.0], [2.0]]))
+
+ def test_coerce_middle_of_edge(self):
+ """Tests coercion when the line intersects the middle of an edge."""
+ box = self.MakeBox(0, 4, 1, 2)
+
+ # x1 = x2
+ K = numpy.matrix([[-1, 1]])
+ w = 0
+
+ assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+ numpy.matrix([[2.0], [2.0]]))
+
+ def test_coerce_perpendicular_line(self):
+ """Tests coercion when the line does not intersect and is in quadrant 2."""
+ box = self.MakeBox(1, 2, 1, 2)
+
+ # x1 = -x2
+ K = numpy.matrix([[1, 1]])
+ w = 0
+
+ assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
+ numpy.matrix([[1.0], [1.0]]))
+
+
+if __name__ == '__main__':
+ unittest.main()
diff --git a/y2016_bot3/joystick_reader.cc b/y2016_bot3/joystick_reader.cc
new file mode 100644
index 0000000..a02142d
--- /dev/null
+++ b/y2016_bot3/joystick_reader.cc
@@ -0,0 +1,271 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <math.h>
+
+#include "aos/linux_code/init.h"
+#include "aos/input/joystick_input.h"
+#include "aos/common/input/driver_station_data.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/util/log_interval.h"
+#include "aos/common/time.h"
+#include "aos/common/actions/actions.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2016_bot3/control_loops/intake/intake.q.h"
+#include "y2016_bot3/control_loops/intake/intake.h"
+#include "y2016_bot3/queues/ball_detector.q.h"
+
+#include "frc971/queues/gyro.q.h"
+#include "frc971/autonomous/auto.q.h"
+#include "y2016_bot3/actors/autonomous_actor.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain_queue;
+using ::y2016_bot3::control_loops::intake_queue;
+
+using ::aos::input::driver_station::ButtonLocation;
+using ::aos::input::driver_station::ControlBit;
+using ::aos::input::driver_station::JoystickAxis;
+using ::aos::input::driver_station::POVLocation;
+
+namespace y2016_bot3 {
+namespace input {
+namespace joysticks {
+
+const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
+const ButtonLocation kQuickTurn(1, 5);
+
+const ButtonLocation kTurn1(1, 7);
+const ButtonLocation kTurn2(1, 11);
+
+// Buttons on the lexan driver station to get things running on bring-up day.
+const ButtonLocation kIntakeDown(3, 11);
+const ButtonLocation kIntakeIn(3, 12);
+const ButtonLocation kFire(3, 3);
+const ButtonLocation kIntakeOut(3, 9);
+const ButtonLocation kChevalDeFrise(3, 8);
+
+class Reader : public ::aos::input::JoystickInput {
+ public:
+ Reader()
+ : intake_goal_(0.0),
+ dt_config_(control_loops::drivetrain::GetDrivetrainConfig()) {}
+
+ void RunIteration(const ::aos::input::driver_station::Data &data) override {
+ bool last_auto_running = auto_running_;
+ auto_running_ = data.GetControlBit(ControlBit::kAutonomous) &&
+ data.GetControlBit(ControlBit::kEnabled);
+ if (auto_running_ != last_auto_running) {
+ if (auto_running_) {
+ StartAuto();
+ } else {
+ StopAuto();
+ }
+ }
+
+ if (!data.GetControlBit(ControlBit::kEnabled)) {
+ // If we are not enabled, reset the waiting for zero bit.
+ LOG(DEBUG, "Waiting for zero.\n");
+ waiting_for_zero_ = true;
+ }
+
+ if (!auto_running_) {
+ HandleDrivetrain(data);
+ HandleTeleop(data);
+ }
+
+ // Process any pending actions.
+ action_queue_.Tick();
+ was_running_ = action_queue_.Running();
+ }
+
+ void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
+ bool is_control_loop_driving = false;
+ static double left_goal = 0.0;
+ static double right_goal = 0.0;
+
+ const double wheel = -data.GetAxis(kSteeringWheel);
+ const double throttle = -data.GetAxis(kDriveThrottle);
+ drivetrain_queue.status.FetchLatest();
+
+ if (data.PosEdge(kTurn1) || data.PosEdge(kTurn2)) {
+ if (drivetrain_queue.status.get()) {
+ left_goal = drivetrain_queue.status->estimated_left_position;
+ right_goal = drivetrain_queue.status->estimated_right_position;
+ }
+ }
+ if (data.IsPressed(kTurn1) || data.IsPressed(kTurn2)) {
+ is_control_loop_driving = true;
+ }
+ if (!drivetrain_queue.goal.MakeWithBuilder()
+ .steering(wheel)
+ .throttle(throttle)
+ .quickturn(data.IsPressed(kQuickTurn))
+ .control_loop_driving(is_control_loop_driving)
+ .left_goal(left_goal - wheel * 0.5 + throttle * 0.3)
+ .right_goal(right_goal + wheel * 0.5 + throttle * 0.3)
+ .left_velocity_goal(0)
+ .right_velocity_goal(0)
+ .Send()) {
+ LOG(WARNING, "sending stick values failed\n");
+ }
+ }
+
+ void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+ intake_goal_ = y2016_bot3::constants::kIntakeRange.upper - 0.04;
+
+ if (!data.GetControlBit(ControlBit::kEnabled)) {
+ action_queue_.CancelAllActions();
+ LOG(DEBUG, "Canceling\n");
+ }
+
+ intake_queue.status.FetchLatest();
+ if (!intake_queue.status.get()) {
+ LOG(ERROR, "Got no intake status packet.\n");
+ }
+
+ if (intake_queue.status.get() && intake_queue.status->zeroed) {
+ if (waiting_for_zero_) {
+ LOG(DEBUG, "Zeroed! Starting teleop mode.\n");
+ waiting_for_zero_ = false;
+ }
+ } else {
+ waiting_for_zero_ = true;
+ }
+
+ bool ball_detected = false;
+ ::y2016_bot3::sensors::ball_detector.FetchLatest();
+ if (::y2016_bot3::sensors::ball_detector.get()) {
+ ball_detected = ::y2016_bot3::sensors::ball_detector->voltage > 2.5;
+ }
+ if (data.PosEdge(kIntakeIn)) {
+ saw_ball_when_started_intaking_ = ball_detected;
+ }
+
+ if (data.IsPressed(kIntakeIn)) {
+ is_intaking_ = (!ball_detected || saw_ball_when_started_intaking_);
+ } else {
+ is_intaking_ = false;
+ }
+
+ is_outtaking_ = data.IsPressed(kIntakeOut);
+
+ if (is_intaking_ || is_outtaking_) {
+ recently_intaking_accumulator_ = 20;
+ }
+
+ if (data.IsPressed(kIntakeDown)) {
+ if (recently_intaking_accumulator_) {
+ intake_goal_ = 0.1;
+ } else {
+ intake_goal_ = -0.05;
+ }
+ }
+
+ if (recently_intaking_accumulator_ > 0) {
+ --recently_intaking_accumulator_;
+ }
+
+ if (data.IsPressed(kChevalDeFrise)) {
+ traverse_unlatched_ = false;
+ traverse_down_ = true;
+ } else {
+ traverse_unlatched_ = true;
+ traverse_down_ = false;
+ }
+
+ if (!waiting_for_zero_) {
+ auto new_intake_goal = intake_queue.goal.MakeMessage();
+ new_intake_goal->angle_intake = intake_goal_;
+
+ new_intake_goal->max_angular_velocity_intake = 7.0;
+ new_intake_goal->max_angular_acceleration_intake = 40.0;
+
+ // Granny mode
+ /*
+ new_intake_goal->max_angular_velocity_intake = 0.2;
+ new_intake_goal->max_angular_acceleration_intake = 1.0;
+ */
+ if (is_intaking_) {
+ new_intake_goal->voltage_top_rollers = 12.0;
+ new_intake_goal->voltage_bottom_rollers = 12.0;
+ } else if (is_outtaking_) {
+ new_intake_goal->voltage_top_rollers = -12.0;
+ new_intake_goal->voltage_bottom_rollers = -7.0;
+ } else {
+ new_intake_goal->voltage_top_rollers = 0.0;
+ new_intake_goal->voltage_bottom_rollers = 0.0;
+ }
+
+ new_intake_goal->traverse_unlatched = traverse_unlatched_;
+ new_intake_goal->traverse_down = traverse_down_;
+ new_intake_goal->force_intake = true;
+
+ if (!new_intake_goal.Send()) {
+ LOG(ERROR, "Sending intake goal failed.\n");
+ } else {
+ LOG(DEBUG, "sending goal: intake: %f\n", intake_goal_);
+ }
+ }
+ }
+
+ private:
+ void StartAuto() {
+ LOG(INFO, "Starting auto mode\n");
+
+ actors::AutonomousActionParams params;
+ actors::auto_mode.FetchLatest();
+ if (actors::auto_mode.get() != nullptr) {
+ params.mode = actors::auto_mode->mode;
+ } else {
+ LOG(WARNING, "no auto mode values\n");
+ params.mode = 0;
+ }
+ action_queue_.EnqueueAction(actors::MakeAutonomousAction(params));
+ }
+
+ void StopAuto() {
+ LOG(INFO, "Stopping auto mode\n");
+ action_queue_.CancelAllActions();
+ }
+
+ // Whatever these are set to are our default goals to send out after zeroing.
+ double intake_goal_;
+
+ bool was_running_ = false;
+ bool auto_running_ = false;
+
+ bool traverse_unlatched_ = false;
+ bool traverse_down_ = false;
+
+ // If we're waiting for the subsystems to zero.
+ bool waiting_for_zero_ = true;
+
+ // If true, the ball was present when the intaking button was pressed.
+ bool saw_ball_when_started_intaking_ = false;
+
+ bool is_intaking_ = false;
+ bool is_outtaking_ = false;
+
+ int recently_intaking_accumulator_ = 0;
+
+ ::aos::common::actions::ActionQueue action_queue_;
+
+ const ::frc971::control_loops::drivetrain::DrivetrainConfig dt_config_;
+
+ ::aos::util::SimpleLogInterval no_drivetrain_status_ =
+ ::aos::util::SimpleLogInterval(::aos::time::Time::InSeconds(0.2), WARNING,
+ "no drivetrain status");
+};
+
+} // namespace joysticks
+} // namespace input
+} // namespace y2016_bot3
+
+int main() {
+ ::aos::Init(-1);
+ ::y2016_bot3::input::joysticks::Reader reader;
+ reader.Run();
+ ::aos::Cleanup();
+}
diff --git a/y2016_bot3/queues/BUILD b/y2016_bot3/queues/BUILD
new file mode 100644
index 0000000..81f75d4
--- /dev/null
+++ b/y2016_bot3/queues/BUILD
@@ -0,0 +1,17 @@
+package(default_visibility = ['//visibility:public'])
+
+load('/aos/build/queues', 'queue_library')
+
+queue_library(
+ name = 'ball_detector',
+ srcs = [
+ 'ball_detector.q',
+ ],
+)
+
+queue_library(
+ name = 'profile_params',
+ srcs = [
+ 'profile_params.q',
+ ],
+)
diff --git a/y2016_bot3/queues/ball_detector.q b/y2016_bot3/queues/ball_detector.q
new file mode 100644
index 0000000..bd2e02f
--- /dev/null
+++ b/y2016_bot3/queues/ball_detector.q
@@ -0,0 +1,13 @@
+package y2016_bot3.sensors;
+
+message BallDetector {
+ // Voltage measured by the ball detector sensor.
+
+ // Higher voltage means ball is closer to detector, lower voltage means ball
+ // is far from the sensor or not in the robot at all.
+ // TODO(comran): Check to see if our sensor's output corresponds with the
+ // comment above.
+
+ double voltage;
+};
+queue BallDetector ball_detector;
diff --git a/y2016_bot3/queues/profile_params.q b/y2016_bot3/queues/profile_params.q
new file mode 100644
index 0000000..351682d
--- /dev/null
+++ b/y2016_bot3/queues/profile_params.q
@@ -0,0 +1,6 @@
+package y2016_bot3;
+
+struct ProfileParams {
+ double velocity;
+ double acceleration;
+};
diff --git a/y2016_bot3/wpilib/BUILD b/y2016_bot3/wpilib/BUILD
new file mode 100644
index 0000000..e86eacc
--- /dev/null
+++ b/y2016_bot3/wpilib/BUILD
@@ -0,0 +1,43 @@
+package(default_visibility = ['//visibility:public'])
+
+cc_binary(
+ name = 'wpilib_interface',
+ srcs = [
+ 'wpilib_interface.cc',
+ ],
+ deps = [
+ '//aos/common:stl_mutex',
+ '//aos/common/logging',
+ '//aos/common:math',
+ '//aos/common/controls:control_loop',
+ '//aos/common/util:log_interval',
+ '//aos/common:time',
+ '//aos/common/logging:queue_logging',
+ '//aos/common/messages:robot_state',
+ '//aos/common/util:phased_loop',
+ '//aos/common/util:wrapping_counter',
+ '//aos/linux_code:init',
+ '//third_party/allwpilib_2016:wpilib',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
+ '//frc971/control_loops:queues',
+ '//frc971/wpilib:joystick_sender',
+ '//frc971/wpilib:loop_output_handler',
+ '//frc971/wpilib:buffered_pcm',
+ '//frc971/wpilib:gyro_sender',
+ '//frc971/wpilib:dma_edge_counting',
+ '//frc971/wpilib:interrupt_edge_counting',
+ '//frc971/wpilib:wpilib_robot_base',
+ '//frc971/wpilib:encoder_and_potentiometer',
+ '//frc971/wpilib:logging_queue',
+ '//frc971/wpilib:wpilib_interface',
+ '//frc971/wpilib:pdp_fetcher',
+ '//frc971/wpilib:ADIS16448',
+ '//frc971/wpilib:dma',
+ '//y2016_bot3/control_loops/drivetrain:polydrivetrain_plants',
+ '//y2016_bot3/control_loops/intake:intake_queue',
+ '//y2016_bot3/queues:ball_detector',
+ '//y2016_bot3/actors:autonomous_action_queue',
+ '//y2016_bot3/control_loops/intake:intake_lib',
+ '//y2016_bot3/control_loops/drivetrain:drivetrain_base',
+ ],
+)
diff --git a/y2016_bot3/wpilib/wpilib_interface.cc b/y2016_bot3/wpilib/wpilib_interface.cc
new file mode 100644
index 0000000..59dce44
--- /dev/null
+++ b/y2016_bot3/wpilib/wpilib_interface.cc
@@ -0,0 +1,507 @@
+#include <stdio.h>
+#include <string.h>
+#include <unistd.h>
+#include <inttypes.h>
+
+#include <thread>
+#include <mutex>
+#include <functional>
+#include <array>
+
+#include "Encoder.h"
+#include "Talon.h"
+#include "Relay.h"
+#include "DriverStation.h"
+#include "AnalogInput.h"
+#include "Compressor.h"
+#include "frc971/wpilib/wpilib_robot_base.h"
+#include "DigitalGlitchFilter.h"
+#undef ERROR
+
+#include "aos/common/logging/logging.h"
+#include "aos/common/logging/queue_logging.h"
+#include "aos/common/time.h"
+#include "aos/common/util/log_interval.h"
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/util/wrapping_counter.h"
+#include "aos/common/stl_mutex.h"
+#include "aos/linux_code/init.h"
+#include "aos/common/messages/robot_state.q.h"
+#include "aos/common/commonmath.h"
+
+#include "frc971/control_loops/control_loops.q.h"
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2016_bot3/control_loops/intake/intake.q.h"
+#include "y2016_bot3/queues/ball_detector.q.h"
+#include "y2016_bot3/actors/autonomous_action.q.h"
+
+#include "frc971/wpilib/joystick_sender.h"
+#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/buffered_solenoid.h"
+#include "frc971/wpilib/buffered_pcm.h"
+#include "frc971/wpilib/gyro_sender.h"
+#include "frc971/wpilib/dma_edge_counting.h"
+#include "frc971/wpilib/interrupt_edge_counting.h"
+#include "frc971/wpilib/encoder_and_potentiometer.h"
+#include "frc971/wpilib/logging.q.h"
+#include "frc971/wpilib/wpilib_interface.h"
+#include "frc971/wpilib/pdp_fetcher.h"
+#include "frc971/wpilib/dma.h"
+
+#include "y2016_bot3/control_loops/intake/intake.h"
+#include "y2016_bot3/control_loops/drivetrain/drivetrain_base.h"
+
+#ifndef M_PI
+#define M_PI 3.14159265358979323846
+#endif
+
+using ::frc971::control_loops::drivetrain_queue;
+using ::y2016_bot3::control_loops::intake_queue;
+
+namespace y2016_bot3 {
+namespace constants {
+IntakeZero intake_zero;
+}
+namespace wpilib {
+namespace {
+constexpr double kMaxBringupPower = 12.0;
+} // namespace
+
+// TODO(Brian): Fix the interpretation of the result of GetRaw here and in the
+// DMA stuff and then removing the * 2.0 in *_translate.
+// The low bit is direction.
+
+// TODO(brian): Replace this with ::std::make_unique once all our toolchains
+// have support.
+template <class T, class... U>
+std::unique_ptr<T> make_unique(U &&... u) {
+ return std::unique_ptr<T>(new T(std::forward<U>(u)...));
+}
+
+// TODO(Campbell): Update values
+// Translates for the sensor values to convert raw index pulses into something
+// with proper units.
+
+double drivetrain_translate(int32_t in) {
+ return -static_cast<double>(in) / (256.0 /*cpr*/ * 4.0 /*4x*/) *
+ ::y2016_bot3::constants::kDrivetrainEncoderRatio *
+ control_loops::drivetrain::kWheelRadius * 2.0 * M_PI;
+}
+
+double drivetrain_velocity_translate(double in) {
+ return (1.0 / in) / 256.0 /*cpr*/ *
+ ::y2016_bot3::constants::kDrivetrainEncoderRatio *
+ control_loops::drivetrain::kWheelRadius * 2.0 * M_PI;
+}
+
+double intake_translate(int32_t in) {
+ return static_cast<double>(in) / (512.0 /*cpr*/ * 4.0 /*4x*/) *
+ ::y2016_bot3::constants::kIntakeEncoderRatio * (2 * M_PI /*radians*/);
+}
+
+double intake_pot_translate(double voltage) {
+ return voltage * ::y2016_bot3::constants::kIntakePotRatio *
+ (10.0 /*turns*/ / 5.0 /*volts*/) * (2 * M_PI /*radians*/);
+}
+
+constexpr double kMaxDrivetrainEncoderPulsesPerSecond =
+ 5600.0 /* CIM free speed RPM */ * 14.0 / 48.0 /* 1st reduction */ * 28.0 /
+ 50.0 /* 2nd reduction (high gear) */ * 30.0 / 44.0 /* encoder gears */ /
+ 60.0 /* seconds per minute */ * 256.0 /* CPR */ * 4 /* edges per cycle */;
+
+// Class to send position messages with sensor readings to our loops.
+class SensorReader {
+ public:
+ SensorReader() {
+ // Set it to filter out anything shorter than 1/4 of the minimum pulse width
+ // we should ever see.
+ drivetrain_encoder_filter_.SetPeriodNanoSeconds(
+ static_cast<int>(1 / 4.0 /* built-in tolerance */ /
+ kMaxDrivetrainEncoderPulsesPerSecond * 1e9 +
+ 0.5));
+ }
+
+ // Drivetrain setters.
+ void set_drivetrain_left_encoder(::std::unique_ptr<Encoder> encoder) {
+ drivetrain_encoder_filter_.Add(encoder.get());
+ drivetrain_left_encoder_ = ::std::move(encoder);
+ }
+
+ void set_drivetrain_right_encoder(::std::unique_ptr<Encoder> encoder) {
+ drivetrain_encoder_filter_.Add(encoder.get());
+ drivetrain_right_encoder_ = ::std::move(encoder);
+ }
+
+ // Intake setters.
+ void set_intake_encoder(::std::unique_ptr<Encoder> encoder) {
+ intake_encoder_filter_.Add(encoder.get());
+ intake_encoder_.set_encoder(::std::move(encoder));
+ }
+
+ void set_intake_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
+ intake_encoder_.set_potentiometer(::std::move(potentiometer));
+ }
+
+ void set_intake_index(::std::unique_ptr<DigitalInput> index) {
+ intake_encoder_filter_.Add(index.get());
+ intake_encoder_.set_index(::std::move(index));
+ }
+
+ // Ball detector setter.
+ void set_ball_detector(::std::unique_ptr<AnalogInput> analog) {
+ ball_detector_ = ::std::move(analog);
+ }
+
+ // All of the DMA-related set_* calls must be made before this, and it doesn't
+ // hurt to do all of them.
+
+ void set_dma(::std::unique_ptr<DMA> dma) {
+ dma_synchronizer_.reset(
+ new ::frc971::wpilib::DMASynchronizer(::std::move(dma)));
+ dma_synchronizer_->Add(&intake_encoder_);
+ }
+
+ void operator()() {
+ ::aos::SetCurrentThreadName("SensorReader");
+
+ my_pid_ = getpid();
+ ds_ = &DriverStation::GetInstance();
+
+ dma_synchronizer_->Start();
+
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(4));
+
+ ::aos::SetCurrentThreadRealtimePriority(40);
+ while (run_) {
+ {
+ const int iterations = phased_loop.SleepUntilNext();
+ if (iterations != 1) {
+ LOG(WARNING, "SensorReader skipped %d iterations\n", iterations - 1);
+ }
+ }
+ RunIteration();
+ }
+ }
+
+ void RunIteration() {
+ ::frc971::wpilib::SendRobotState(my_pid_, ds_);
+
+ const auto intake_pot_offset =
+ y2016_bot3::constants::intake_zero.pot_offset;
+
+ {
+ auto drivetrain_message = drivetrain_queue.position.MakeMessage();
+ drivetrain_message->right_encoder =
+ drivetrain_translate(-drivetrain_right_encoder_->GetRaw());
+ drivetrain_message->left_encoder =
+ -drivetrain_translate(drivetrain_left_encoder_->GetRaw());
+ drivetrain_message->left_speed =
+ drivetrain_velocity_translate(drivetrain_left_encoder_->GetPeriod());
+ drivetrain_message->right_speed =
+ drivetrain_velocity_translate(drivetrain_right_encoder_->GetPeriod());
+
+ drivetrain_message.Send();
+ }
+
+ dma_synchronizer_->RunIteration();
+
+ {
+ auto intake_message = intake_queue.position.MakeMessage();
+ CopyPotAndIndexPosition(intake_encoder_, &intake_message->intake,
+ intake_translate, intake_pot_translate, false,
+ intake_pot_offset);
+
+ intake_message.Send();
+ }
+
+ {
+ auto ball_detector_message =
+ ::y2016_bot3::sensors::ball_detector.MakeMessage();
+ ball_detector_message->voltage = ball_detector_->GetVoltage();
+ LOG_STRUCT(DEBUG, "ball detector", *ball_detector_message);
+ ball_detector_message.Send();
+ }
+
+ {
+ auto auto_mode_message = ::y2016_bot3::actors::auto_mode.MakeMessage();
+ auto_mode_message->mode = 0;
+ LOG_STRUCT(DEBUG, "auto mode", *auto_mode_message);
+ auto_mode_message.Send();
+ }
+ }
+
+ void Quit() { run_ = false; }
+
+ private:
+ void CopyPotAndIndexPosition(
+ const ::frc971::wpilib::DMAEncoderAndPotentiometer &encoder,
+ ::frc971::PotAndIndexPosition *position,
+ ::std::function<double(int32_t)> encoder_translate,
+ ::std::function<double(double)> potentiometer_translate, bool reverse,
+ double pot_offset) {
+ const double multiplier = reverse ? -1.0 : 1.0;
+ position->encoder =
+ multiplier * encoder_translate(encoder.polled_encoder_value());
+ position->pot = multiplier * potentiometer_translate(
+ encoder.polled_potentiometer_voltage()) +
+ pot_offset;
+ position->latched_encoder =
+ multiplier * encoder_translate(encoder.last_encoder_value());
+ position->latched_pot =
+ multiplier *
+ potentiometer_translate(encoder.last_potentiometer_voltage()) +
+ pot_offset;
+ position->index_pulses = encoder.index_posedge_count();
+ }
+
+ int32_t my_pid_;
+ DriverStation *ds_;
+
+ ::std::unique_ptr<::frc971::wpilib::DMASynchronizer> dma_synchronizer_;
+
+ ::std::unique_ptr<Encoder> drivetrain_left_encoder_,
+ drivetrain_right_encoder_;
+
+ ::frc971::wpilib::DMAEncoderAndPotentiometer intake_encoder_;
+ ::std::unique_ptr<AnalogInput> ball_detector_;
+
+ ::std::atomic<bool> run_{true};
+ DigitalGlitchFilter drivetrain_encoder_filter_, intake_encoder_filter_;
+};
+
+class SolenoidWriter {
+ public:
+ SolenoidWriter(const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm)
+ : pcm_(pcm),
+ drivetrain_(".frc971.control_loops.drivetrain_queue.output"),
+ intake_(".y2016_bot3.control_loops.intake_queue.output") {}
+
+ void set_compressor(::std::unique_ptr<Compressor> compressor) {
+ compressor_ = ::std::move(compressor);
+ }
+
+ void set_traverse(::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
+ traverse_ = ::std::move(s);
+ }
+
+ void set_traverse_latch(
+ ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
+ traverse_latch_ = ::std::move(s);
+ }
+
+ void operator()() {
+ compressor_->Start();
+ ::aos::SetCurrentThreadName("Solenoids");
+ ::aos::SetCurrentThreadRealtimePriority(27);
+
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(20),
+ ::aos::time::Time::InMS(1));
+
+ while (run_) {
+ {
+ const int iterations = phased_loop.SleepUntilNext();
+ if (iterations != 1) {
+ LOG(DEBUG, "Solenoids skipped %d iterations\n", iterations - 1);
+ }
+ }
+
+ {
+ intake_.FetchLatest();
+ if (intake_.get()) {
+ LOG_STRUCT(DEBUG, "solenoids", *intake_);
+
+ traverse_->Set(intake_->traverse_down);
+ traverse_latch_->Set(intake_->traverse_unlatched);
+ }
+ }
+
+ {
+ ::frc971::wpilib::PneumaticsToLog to_log;
+ { to_log.compressor_on = compressor_->Enabled(); }
+
+ pcm_->Flush();
+ to_log.read_solenoids = pcm_->GetAll();
+ LOG_STRUCT(DEBUG, "pneumatics info", to_log);
+ }
+ }
+ }
+
+ void Quit() { run_ = false; }
+
+ private:
+ const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm_;
+
+ ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> traverse_,
+ traverse_latch_;
+ ::std::unique_ptr<Compressor> compressor_;
+
+ ::aos::Queue<::frc971::control_loops::DrivetrainQueue::Output> drivetrain_;
+ ::aos::Queue<::y2016_bot3::control_loops::IntakeQueue::Output> intake_;
+
+ ::std::atomic<bool> run_{true};
+};
+
+class DrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler {
+ public:
+ void set_drivetrain_left_talon(::std::unique_ptr<Talon> t) {
+ drivetrain_left_talon_ = ::std::move(t);
+ }
+
+ void set_drivetrain_right_talon(::std::unique_ptr<Talon> t) {
+ drivetrain_right_talon_ = ::std::move(t);
+ }
+
+ private:
+ virtual void Read() override {
+ ::frc971::control_loops::drivetrain_queue.output.FetchAnother();
+ }
+
+ virtual void Write() override {
+ auto &queue = ::frc971::control_loops::drivetrain_queue.output;
+ LOG_STRUCT(DEBUG, "will output", *queue);
+ drivetrain_left_talon_->Set(queue->left_voltage / 12.0);
+ drivetrain_right_talon_->Set(-queue->right_voltage / 12.0);
+ }
+
+ virtual void Stop() override {
+ LOG(WARNING, "drivetrain output too old\n");
+ drivetrain_left_talon_->Disable();
+ drivetrain_right_talon_->Disable();
+ }
+
+ ::std::unique_ptr<Talon> drivetrain_left_talon_, drivetrain_right_talon_;
+};
+
+class IntakeWriter : public ::frc971::wpilib::LoopOutputHandler {
+ public:
+ void set_intake_talon(::std::unique_ptr<Talon> t) {
+ intake_talon_ = ::std::move(t);
+ }
+
+ void set_top_rollers_talon(::std::unique_ptr<Talon> t) {
+ top_rollers_talon_ = ::std::move(t);
+ }
+
+ void set_bottom_rollers_talon(::std::unique_ptr<Talon> t) {
+ bottom_rollers_talon_ = ::std::move(t);
+ }
+
+ private:
+ virtual void Read() override {
+ ::y2016_bot3::control_loops::intake_queue.output.FetchAnother();
+ }
+
+ virtual void Write() override {
+ auto &queue = ::y2016_bot3::control_loops::intake_queue.output;
+ LOG_STRUCT(DEBUG, "will output", *queue);
+ intake_talon_->Set(::aos::Clip(queue->voltage_intake, -kMaxBringupPower,
+ kMaxBringupPower) /
+ 12.0);
+ top_rollers_talon_->Set(-queue->voltage_top_rollers / 12.0);
+ bottom_rollers_talon_->Set(-queue->voltage_bottom_rollers / 12.0);
+ }
+
+ virtual void Stop() override {
+ LOG(WARNING, "Intake output too old.\n");
+ intake_talon_->Disable();
+ }
+
+ ::std::unique_ptr<Talon> intake_talon_, top_rollers_talon_,
+ bottom_rollers_talon_;
+};
+
+class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
+ public:
+ ::std::unique_ptr<Encoder> make_encoder(int index) {
+ return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
+ Encoder::k4X);
+ }
+
+ void Run() override {
+ ::aos::InitNRT();
+ ::aos::SetCurrentThreadName("StartCompetition");
+
+ ::frc971::wpilib::JoystickSender joystick_sender;
+ ::std::thread joystick_thread(::std::ref(joystick_sender));
+
+ ::frc971::wpilib::PDPFetcher pdp_fetcher;
+ ::std::thread pdp_fetcher_thread(::std::ref(pdp_fetcher));
+ SensorReader reader;
+
+ reader.set_drivetrain_left_encoder(make_encoder(5));
+ reader.set_drivetrain_right_encoder(make_encoder(6));
+
+ reader.set_intake_encoder(make_encoder(0));
+ reader.set_intake_index(make_unique<DigitalInput>(0));
+ reader.set_intake_potentiometer(make_unique<AnalogInput>(0));
+
+ reader.set_ball_detector(make_unique<AnalogInput>(7));
+
+ reader.set_dma(make_unique<DMA>());
+ ::std::thread reader_thread(::std::ref(reader));
+
+ ::frc971::wpilib::GyroSender gyro_sender;
+ ::std::thread gyro_thread(::std::ref(gyro_sender));
+
+ DrivetrainWriter drivetrain_writer;
+ drivetrain_writer.set_drivetrain_left_talon(
+ ::std::unique_ptr<Talon>(new Talon(5)));
+ drivetrain_writer.set_drivetrain_right_talon(
+ ::std::unique_ptr<Talon>(new Talon(4)));
+ ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
+
+ IntakeWriter intake_writer;
+ intake_writer.set_intake_talon(::std::unique_ptr<Talon>(new Talon(3)));
+ intake_writer.set_top_rollers_talon(::std::unique_ptr<Talon>(new Talon(1)));
+ intake_writer.set_bottom_rollers_talon(
+ ::std::unique_ptr<Talon>(new Talon(0)));
+ ::std::thread intake_writer_thread(::std::ref(intake_writer));
+
+ ::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
+ new ::frc971::wpilib::BufferedPcm());
+ SolenoidWriter solenoid_writer(pcm);
+ solenoid_writer.set_traverse_latch(pcm->MakeSolenoid(2));
+ solenoid_writer.set_traverse(pcm->MakeSolenoid(3));
+
+ solenoid_writer.set_compressor(make_unique<Compressor>());
+
+ ::std::thread solenoid_thread(::std::ref(solenoid_writer));
+
+ // Wait forever. Not much else to do...
+ while (true) {
+ const int r = select(0, nullptr, nullptr, nullptr, nullptr);
+ if (r != 0) {
+ PLOG(WARNING, "infinite select failed");
+ } else {
+ PLOG(WARNING, "infinite select succeeded??\n");
+ }
+ }
+
+ LOG(ERROR, "Exiting WPILibRobot\n");
+
+ joystick_sender.Quit();
+ joystick_thread.join();
+ pdp_fetcher.Quit();
+ pdp_fetcher_thread.join();
+ reader.Quit();
+ reader_thread.join();
+ gyro_sender.Quit();
+ gyro_thread.join();
+
+ drivetrain_writer.Quit();
+ drivetrain_writer_thread.join();
+ intake_writer.Quit();
+ intake_writer_thread.join();
+ solenoid_writer.Quit();
+ solenoid_thread.join();
+
+ ::aos::Cleanup();
+ }
+};
+
+} // namespace wpilib
+} // namespace y2016_bot3
+
+AOS_ROBOT_CLASS(::y2016_bot3::wpilib::WPILibRobot);