Move 2015-specific code to its own folder.
Known issues:
-I didn't change the namespace for it, but I am open to discussion
on doing that in a separate change.
-There are a couple of files which should get split out into
year-specific and not-year-specific files to reduce how much needs
to get copied around each year still.
-The control loop python code doesn't yet generate code with the
right #include etc paths.
Change-Id: Iabf078e75107c283247f58a5ffceb4dbd6a0815f
diff --git a/y2015/control_loops/claw/claw.cc b/y2015/control_loops/claw/claw.cc
new file mode 100644
index 0000000..c1a734e
--- /dev/null
+++ b/y2015/control_loops/claw/claw.cc
@@ -0,0 +1,311 @@
+#include "y2015/control_loops/claw/claw.h"
+
+#include <algorithm>
+
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+
+#include "y2015/constants.h"
+#include "y2015/control_loops/claw/claw_motor_plant.h"
+#include "aos/common/util/trapezoid_profile.h"
+
+namespace frc971 {
+namespace control_loops {
+
+using ::aos::time::Time;
+
+constexpr double kZeroingVoltage = 4.0;
+
+void ClawCappedStateFeedbackLoop::CapU() {
+ mutable_U(0, 0) = ::std::min(mutable_U(0, 0), max_voltage_);
+ mutable_U(0, 0) = ::std::max(mutable_U(0, 0), -max_voltage_);
+}
+
+double ClawCappedStateFeedbackLoop::UnsaturateOutputGoalChange() {
+ // Compute K matrix to compensate for position errors.
+ double Kp = K(0, 0);
+
+ // Compute how much we need to change R in order to achieve the change in U
+ // that was observed.
+ return -(1.0 / Kp) * (U_uncapped() - U())(0, 0);
+}
+
+Claw::Claw(control_loops::ClawQueue *claw)
+ : aos::controls::ControlLoop<control_loops::ClawQueue>(claw),
+ last_piston_edge_(Time::Now()),
+ claw_loop_(new ClawCappedStateFeedbackLoop(MakeClawLoop())),
+ claw_estimator_(constants::GetValues().claw.zeroing),
+ profile_(::aos::controls::kLoopFrequency) {}
+
+void Claw::UpdateZeroingState() {
+ if (claw_estimator_.offset_ratio_ready() < 1.0) {
+ state_ = INITIALIZING;
+ } else if (!claw_estimator_.zeroed()) {
+ state_ = ZEROING;
+ } else {
+ state_ = RUNNING;
+ }
+}
+
+void Claw::Correct() {
+ Eigen::Matrix<double, 1, 1> Y;
+ Y << claw_position();
+ claw_loop_->Correct(Y);
+}
+
+void Claw::SetClawOffset(double offset) {
+ LOG(INFO, "Changing claw offset from %f to %f.\n", claw_offset_, offset);
+ const double doffset = offset - claw_offset_;
+
+ // Adjust the height. The derivative should not need to be updated since the
+ // speed is not changing.
+ claw_loop_->mutable_X_hat(0, 0) += doffset;
+
+ // Modify claw zeroing goal.
+ claw_goal_ += doffset;
+ // Update the cached offset value to the actual value.
+ claw_offset_ = offset;
+}
+
+double Claw::estimated_claw_position() const {
+ return current_position_.joint.encoder + claw_estimator_.offset();
+}
+
+double Claw::claw_position() const {
+ return current_position_.joint.encoder + claw_offset_;
+}
+
+constexpr double kClawZeroingVelocity = 0.2;
+
+double Claw::claw_zeroing_velocity() {
+ const auto &values = constants::GetValues();
+
+ // Zeroing will work as following. At startup, record the offset of the claw.
+ // Then, start moving the claw towards where the index pulse should be. We
+ // search around it a little, and if we don't find anything, we estop.
+ // Otherwise, we're done.
+
+ const double target_pos = values.claw.zeroing.measured_index_position;
+ // How far away we need to stay from the ends of the range while zeroing.
+ constexpr double zeroing_limit = 0.1375;
+ // Keep the zeroing range within the bounds of the mechanism.
+ const double zeroing_range =
+ ::std::min(target_pos - values.claw.wrist.lower_limit - zeroing_limit,
+ values.claw.zeroing_range);
+
+ if (claw_zeroing_velocity_ == 0) {
+ if (estimated_claw_position() > target_pos) {
+ claw_zeroing_velocity_ = -kClawZeroingVelocity;
+ } else {
+ claw_zeroing_velocity_ = kClawZeroingVelocity;
+ }
+ } else if (claw_zeroing_velocity_ > 0 &&
+ estimated_claw_position() > target_pos + zeroing_range) {
+ claw_zeroing_velocity_ = -kClawZeroingVelocity;
+ } else if (claw_zeroing_velocity_ < 0 &&
+ estimated_claw_position() < target_pos - zeroing_range) {
+ claw_zeroing_velocity_ = kClawZeroingVelocity;
+ }
+
+ return claw_zeroing_velocity_;
+}
+
+void Claw::RunIteration(const control_loops::ClawQueue::Goal *unsafe_goal,
+ const control_loops::ClawQueue::Position *position,
+ control_loops::ClawQueue::Output *output,
+ control_loops::ClawQueue::Status *status) {
+ const auto &values = constants::GetValues();
+
+ if (WasReset()) {
+ LOG(ERROR, "WPILib reset! Restarting.\n");
+ claw_estimator_.Reset();
+ state_ = UNINITIALIZED;
+ }
+
+ current_position_ = *position;
+
+ // Bool to track if we should turn the motor on or not.
+ bool disable = output == nullptr;
+ double claw_goal_velocity = 0.0;
+
+ claw_estimator_.UpdateEstimate(position->joint);
+
+ if (state_ != UNINITIALIZED) {
+ Correct();
+ }
+
+ switch (state_) {
+ case UNINITIALIZED:
+ LOG(INFO, "Uninitialized.\n");
+ // Startup. Assume that we are at the origin.
+ claw_offset_ = -position->joint.encoder;
+ claw_loop_->mutable_X_hat().setZero();
+ Correct();
+ state_ = INITIALIZING;
+ disable = true;
+ break;
+
+ case INITIALIZING:
+ LOG(INFO, "Waiting for accurate initial position.\n");
+ disable = true;
+ // Update state_ to accurately represent the state of the zeroing
+ // estimator.
+ UpdateZeroingState();
+
+ if (state_ != INITIALIZING) {
+ // Set the goals to where we are now.
+ claw_goal_ = claw_position();
+ }
+ break;
+
+ case ZEROING:
+ LOG(DEBUG, "Zeroing.\n");
+
+ // Update state_.
+ UpdateZeroingState();
+ if (claw_estimator_.zeroed()) {
+ LOG(INFO, "Zeroed!\n");
+ SetClawOffset(claw_estimator_.offset());
+ } else if (!disable) {
+ claw_goal_velocity = claw_zeroing_velocity();
+ claw_goal_ +=
+ claw_goal_velocity * ::aos::controls::kLoopFrequency.ToSeconds();
+ }
+
+ // Clear the current profile state if we are zeroing.
+ {
+ Eigen::Matrix<double, 2, 1> current;
+ current.setZero();
+ current << claw_goal_, claw_goal_velocity;
+ profile_.MoveCurrentState(current);
+ }
+ break;
+
+ case RUNNING:
+ LOG(DEBUG, "Running!\n");
+
+ // Update state_.
+ UpdateZeroingState();
+ if (unsafe_goal) {
+ // Pick a set of sane defaults if none are specified.
+ if (unsafe_goal->max_velocity != 0.0) {
+ profile_.set_maximum_velocity(unsafe_goal->max_velocity);
+ } else {
+ profile_.set_maximum_velocity(2.5);
+ }
+ if (unsafe_goal->max_acceleration != 0.0) {
+ profile_.set_maximum_acceleration(unsafe_goal->max_acceleration);
+ } else {
+ profile_.set_maximum_acceleration(4.0);
+ }
+
+ const double unfiltered_goal = ::std::max(
+ ::std::min(unsafe_goal->angle, values.claw.wrist.upper_limit),
+ values.claw.wrist.lower_limit);
+ ::Eigen::Matrix<double, 2, 1> goal_state =
+ profile_.Update(unfiltered_goal, unsafe_goal->angular_velocity);
+ claw_goal_ = goal_state(0, 0);
+ claw_goal_velocity = goal_state(1, 0);
+ }
+
+ if (state_ != RUNNING && state_ != ESTOP) {
+ state_ = UNINITIALIZED;
+ }
+ break;
+
+ case ESTOP:
+ LOG(ERROR, "Estop!\n");
+ disable = true;
+ break;
+ }
+
+ // Make sure goal and position do not exceed the hardware limits if we are
+ // RUNNING.
+ if (state_ == RUNNING) {
+ // Limit goal.
+ claw_goal_ = ::std::min(claw_goal_, values.claw.wrist.upper_limit);
+ claw_goal_ = ::std::max(claw_goal_, values.claw.wrist.lower_limit);
+
+ // Check position.
+ if (claw_position() >= values.claw.wrist.upper_hard_limit ||
+ claw_position() <= values.claw.wrist.lower_hard_limit) {
+ LOG(ERROR, "Claw at %f out of bounds [%f, %f].\n", claw_position(),
+ values.claw.wrist.lower_limit, values.claw.wrist.upper_limit);
+ }
+ }
+
+ // Set the goals.
+ claw_loop_->mutable_R() << claw_goal_, claw_goal_velocity;
+
+ const double max_voltage = (state_ == RUNNING) ? 12.0 : kZeroingVoltage;
+ claw_loop_->set_max_voltage(max_voltage);
+
+ if (state_ == ESTOP) {
+ disable = true;
+ }
+ claw_loop_->Update(disable);
+
+ if (state_ == INITIALIZING || state_ == ZEROING) {
+ if (claw_loop_->U() != claw_loop_->U_uncapped()) {
+ double deltaR = claw_loop_->UnsaturateOutputGoalChange();
+
+ // Move the claw goal by the amount observed.
+ LOG(WARNING, "Moving claw goal by %f to handle saturation.\n", deltaR);
+ claw_goal_ += deltaR;
+ }
+ }
+
+ if (output) {
+ output->voltage = claw_loop_->U(0, 0);
+ if (state_ != RUNNING) {
+ output->intake_voltage = 0.0;
+ output->rollers_closed = false;
+ } else {
+ if (unsafe_goal) {
+ output->intake_voltage = unsafe_goal->intake;
+ output->rollers_closed = unsafe_goal->rollers_closed;
+ } else {
+ output->intake_voltage = 0.0;
+ output->rollers_closed = false;
+ }
+ }
+ if (output->rollers_closed != last_rollers_closed_) {
+ last_piston_edge_ = Time::Now();
+ }
+ }
+
+ status->zeroed = state_ == RUNNING;
+ status->estopped = state_ == ESTOP;
+ status->state = state_;
+ zeroing::PopulateEstimatorState(claw_estimator_, &status->zeroing_state);
+
+ status->angle = claw_loop_->X_hat(0, 0);
+ status->angular_velocity = claw_loop_->X_hat(1, 0);
+
+ if (output) {
+ status->intake = output->intake_voltage;
+ } else {
+ status->intake = 0;
+ }
+ status->goal_angle = claw_goal_;
+ status->goal_velocity = claw_goal_velocity;
+
+ if (output) {
+ status->rollers_open =
+ !output->rollers_closed &&
+ (Time::Now() - last_piston_edge_ >= values.claw.piston_switch_time);
+ status->rollers_closed =
+ output->rollers_closed &&
+ (Time::Now() - last_piston_edge_ >= values.claw.piston_switch_time);
+ } else {
+ status->rollers_open = false;
+ status->rollers_closed = false;
+ }
+
+ if (output) {
+ last_rollers_closed_ = output->rollers_closed;
+ }
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/claw/claw.gyp b/y2015/control_loops/claw/claw.gyp
new file mode 100644
index 0000000..780f065
--- /dev/null
+++ b/y2015/control_loops/claw/claw.gyp
@@ -0,0 +1,89 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'replay_claw',
+ 'type': 'executable',
+ 'variables': {
+ 'no_rsync': 1,
+ },
+ 'sources': [
+ 'replay_claw.cc',
+ ],
+ 'dependencies': [
+ 'claw_queue',
+ '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+ '<(AOS)/linux_code/linux_code.gyp:init',
+ ],
+ },
+ {
+ 'target_name': 'claw_queue',
+ 'type': 'static_library',
+ 'sources': ['claw.q'],
+ 'variables': {
+ 'header_path': 'y2015/control_loops/claw',
+ },
+ 'dependencies': [
+ '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+
+ ],
+ 'includes': ['../../../aos/build/queues.gypi'],
+ },
+ {
+ 'target_name': 'claw_lib',
+ 'type': 'static_library',
+ 'sources': [
+ 'claw.cc',
+ 'claw_motor_plant.cc',
+ ],
+ 'dependencies': [
+ 'claw_queue',
+ '<(AOS)/common/controls/controls.gyp:control_loop',
+ '<(AOS)/common/common.gyp:time',
+ '<(AOS)/common/util/util.gyp:trapezoid_profile',
+ '<(DEPTH)/y2015/y2015.gyp:constants',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
+ ],
+ 'export_dependent_settings': [
+ 'claw_queue',
+ '<(AOS)/common/controls/controls.gyp:control_loop',
+ '<(AOS)/common/common.gyp:time',
+ '<(AOS)/common/util/util.gyp:trapezoid_profile',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
+ ],
+ },
+ {
+ 'target_name': 'claw_lib_test',
+ 'type': 'executable',
+ 'sources': [
+ 'claw_lib_test.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ 'claw_lib',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(AOS)/common/controls/controls.gyp:control_loop_test',
+ '<(AOS)/common/common.gyp:time',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:position_sensor_sim',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
+ ],
+ },
+ {
+ 'target_name': 'claw',
+ 'type': 'executable',
+ 'sources': [
+ 'claw_main.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/linux_code/linux_code.gyp:init',
+ 'claw_lib',
+ ],
+ },
+ ],
+}
diff --git a/y2015/control_loops/claw/claw.h b/y2015/control_loops/claw/claw.h
new file mode 100644
index 0000000..02e5398
--- /dev/null
+++ b/y2015/control_loops/claw/claw.h
@@ -0,0 +1,116 @@
+#ifndef Y2015_CONTROL_LOOPS_CLAW_H_
+#define Y2015_CONTROL_LOOPS_CLAW_H_
+
+#include <memory>
+
+#include "aos/common/controls/control_loop.h"
+#include "aos/common/time.h"
+#include "aos/common/util/trapezoid_profile.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2015/control_loops/claw/claw.q.h"
+#include "y2015/control_loops/claw/claw_motor_plant.h"
+#include "frc971/zeroing/zeroing.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+class ClawTest_DisabledGoal_Test;
+class ClawTest_GoalPositiveWindup_Test;
+class ClawTest_GoalNegativeWindup_Test;
+} // namespace testing
+
+class ClawCappedStateFeedbackLoop : public StateFeedbackLoop<2, 1, 1> {
+ public:
+ ClawCappedStateFeedbackLoop(StateFeedbackLoop<2, 1, 1> &&loop)
+ : StateFeedbackLoop<2, 1, 1>(::std::move(loop)), max_voltage_(12.0) {}
+
+ void set_max_voltage(double max_voltage) {
+ max_voltage_ = ::std::max(0.0, ::std::min(12.0, max_voltage));
+ }
+
+ void CapU() override;
+
+ // Returns the amount to change the position goal in order to no longer
+ // saturate the controller.
+ double UnsaturateOutputGoalChange();
+
+ private:
+ double max_voltage_;
+};
+
+class Claw : public aos::controls::ControlLoop<control_loops::ClawQueue> {
+ public:
+ enum State {
+ // Waiting to receive data before doing anything.
+ UNINITIALIZED = 0,
+ // Estimating the starting location.
+ INITIALIZING = 1,
+ // Moving to find an index pulse.
+ ZEROING = 2,
+ // Normal operation.
+ RUNNING = 3,
+ // Internal error caused the claw to abort.
+ ESTOP = 4,
+ };
+
+ int state() { return state_; }
+
+ explicit Claw(
+ control_loops::ClawQueue *claw_queue = &control_loops::claw_queue);
+
+ protected:
+ virtual void RunIteration(const control_loops::ClawQueue::Goal *goal,
+ const control_loops::ClawQueue::Position *position,
+ control_loops::ClawQueue::Output *output,
+ control_loops::ClawQueue::Status *status);
+
+ private:
+ friend class testing::ClawTest_DisabledGoal_Test;
+ friend class testing::ClawTest_GoalPositiveWindup_Test;
+ friend class testing::ClawTest_GoalNegativeWindup_Test;
+
+ // Sets state_ to the correct state given the current state of the zeroing
+ // estimator.
+ void UpdateZeroingState();
+ void SetClawOffset(double offset);
+ // Corrects the Observer with the current position.
+ void Correct();
+
+ // Getter for the current claw position.
+ double claw_position() const;
+ // Our best guess at the current position of the claw.
+ double estimated_claw_position() const;
+ // Returns the current zeroing velocity for the claw. If the subsystem is too
+ // far away from the center, it will switch directions.
+ double claw_zeroing_velocity();
+
+ State state_ = UNINITIALIZED;
+
+ // The time when we last changed the claw piston state.
+ ::aos::time::Time last_piston_edge_;
+
+ // The state feedback control loop to talk to.
+ ::std::unique_ptr<ClawCappedStateFeedbackLoop> claw_loop_;
+
+ // Latest position from queue.
+ control_loops::ClawQueue::Position current_position_;
+ // Zeroing estimator for claw.
+ zeroing::ZeroingEstimator claw_estimator_;
+
+ // The goal for the claw.
+ double claw_goal_ = 0.0;
+ // Current velocity to move at while zeroing.
+ double claw_zeroing_velocity_ = 0.0;
+ // Offsets from the encoder position to the absolute position.
+ double claw_offset_ = 0.0;
+
+ // Whether claw was closed last cycle.
+ bool last_rollers_closed_ = false;
+
+ ::aos::util::TrapezoidProfile profile_;
+};
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_CLAW_H_
diff --git a/y2015/control_loops/claw/claw.q b/y2015/control_loops/claw/claw.q
new file mode 100644
index 0000000..8da1c20
--- /dev/null
+++ b/y2015/control_loops/claw/claw.q
@@ -0,0 +1,81 @@
+package frc971.control_loops;
+
+import "aos/common/controls/control_loops.q";
+import "frc971/control_loops/control_loops.q";
+
+queue_group ClawQueue {
+ implements aos.control_loops.ControlLoop;
+
+ // All angles are in radians with 0 sticking straight out the front. Rotating
+ // up and into the robot is positive. Positive output voltage moves in the
+ // direction of positive encoder values.
+
+ message Goal {
+ // Angle of wrist joint.
+ double angle;
+ // Angular velocity of wrist.
+ float angular_velocity;
+ // Maximum profile velocity, or 0 for the default.
+ float max_velocity;
+ // Maximum profile acceleration, or 0 for the default.
+ float max_acceleration;
+ // Voltage of intake rollers. Positive means sucking in, negative means
+ // spitting out.
+ double intake;
+
+ // true to signal the rollers to close.
+ bool rollers_closed;
+ };
+
+ message Position {
+ PotAndIndexPosition joint;
+ };
+
+ message Output {
+ // Voltage for intake motors. Positive is sucking in, negative is spitting
+ // out.
+ double intake_voltage;
+ // Voltage for claw motor.
+ double voltage;
+
+ // true to signal the rollers to close.
+ bool rollers_closed;
+ };
+
+ message Status {
+ // Is claw zeroed?
+ bool zeroed;
+ // Did the claw estop?
+ bool estopped;
+ // The internal state of the claw state machine.
+ uint32_t state;
+ EstimatorState zeroing_state;
+
+ // Estimated angle of wrist joint.
+ double angle;
+ // Estimated angular velocity of wrist.
+ float angular_velocity;
+
+ // Goal angle of wrist joint.
+ double goal_angle;
+ float goal_velocity;
+ // Voltage of intake rollers. Positive means sucking in, negative means
+ // spitting out.
+ double intake;
+
+ // True iff there has been enough time since we actuated the rollers outward
+ // that they should be there.
+ bool rollers_open;
+ // True iff there has been enough time since we actuated the rollers closed
+ // that they should be there.
+ bool rollers_closed;
+ };
+
+ queue Goal goal;
+ queue Position position;
+ queue Output output;
+ queue Status status;
+};
+
+queue_group ClawQueue claw_queue;
+
diff --git a/y2015/control_loops/claw/claw_lib_test.cc b/y2015/control_loops/claw/claw_lib_test.cc
new file mode 100644
index 0000000..10fcc07
--- /dev/null
+++ b/y2015/control_loops/claw/claw_lib_test.cc
@@ -0,0 +1,347 @@
+#include <math.h>
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/queue.h"
+#include "aos/common/time.h"
+#include "aos/common/controls/control_loop_test.h"
+#include "y2015/control_loops/claw/claw.q.h"
+#include "y2015/control_loops/claw/claw.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "y2015/constants.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+
+using ::aos::time::Time;
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+
+// Class which simulates the claw and sends out queue messages with the
+// position.
+class ClawSimulation {
+ public:
+ // Constructs a claw simulation.
+ ClawSimulation()
+ : claw_plant_(new StateFeedbackPlant<2, 1, 1>(MakeClawPlant())),
+ pot_and_encoder_(constants::GetValues().claw.zeroing.index_difference),
+ claw_queue_(".frc971.control_loops.claw_queue", 0x9d7452fb,
+ ".frc971.control_loops.claw_queue.goal",
+ ".frc971.control_loops.claw_queue.position",
+ ".frc971.control_loops.claw_queue.output",
+ ".frc971.control_loops.claw_queue.status") {
+ InitializePosition(constants::GetValues().claw.wrist.lower_limit);
+ }
+
+ void InitializePosition(double start_pos) {
+ InitializePosition(start_pos,
+ constants::GetValues().claw.zeroing.measured_index_position);
+ }
+
+ void InitializePosition(double start_pos, double index_pos) {
+ InitializePosition(start_pos,
+ // This gives us a standard deviation of ~9 degrees on the pot noise.
+ constants::GetValues().claw.zeroing.index_difference / 10.0,
+ index_pos);
+ }
+
+ // Do specific initialization for the sensors.
+ void InitializePosition(double start_pos,
+ double pot_noise_stddev,
+ double index_pos) {
+ // Update internal state.
+ claw_plant_->mutable_X(0, 0) = start_pos;
+ // Zero velocity.
+ claw_plant_->mutable_X(1, 0) = 0.0;
+
+ pot_and_encoder_.Initialize(start_pos, pot_noise_stddev, index_pos);
+ }
+
+ // Sends a queue message with the position.
+ void SendPositionMessage() {
+ ::aos::ScopedMessagePtr<control_loops::ClawQueue::Position> position =
+ claw_queue_.position.MakeMessage();
+ pot_and_encoder_.GetSensorValues(&position->joint);
+ position.Send();
+ }
+
+ // Simulates for a single timestep.
+ void Simulate() {
+ EXPECT_TRUE(claw_queue_.output.FetchLatest());
+
+ // Feed voltages into physics simulation.
+ claw_plant_->mutable_U() << claw_queue_.output->voltage;
+ claw_plant_->Update();
+
+ const double wrist_angle = claw_plant_->Y(0, 0);
+
+ // TODO(danielp): Sanity checks.
+
+ pot_and_encoder_.MoveTo(wrist_angle);
+ }
+
+ private:
+ ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> claw_plant_;
+ PositionSensorSimulator pot_and_encoder_;
+
+ ClawQueue claw_queue_;
+};
+
+class ClawTest : public ::aos::testing::ControlLoopTest {
+ protected:
+ ClawTest()
+ : claw_queue_(".frc971.control_loops.claw_queue", 0x9d7452fb,
+ ".frc971.control_loops.claw_queue.goal",
+ ".frc971.control_loops.claw_queue.position",
+ ".frc971.control_loops.claw_queue.output",
+ ".frc971.control_loops.claw_queue.status"),
+ claw_(&claw_queue_),
+ claw_plant_() {
+ set_team_id(kTeamNumber);
+ }
+
+ void VerifyNearGoal() {
+ claw_queue_.goal.FetchLatest();
+ claw_queue_.status.FetchLatest();
+ EXPECT_NEAR(claw_queue_.goal->angle,
+ claw_queue_.status->angle,
+ 10.0);
+
+ EXPECT_TRUE(claw_queue_.status->zeroed);
+ EXPECT_FALSE(claw_queue_.status->estopped);
+ }
+
+ // Runs one iteration of the whole simulation.
+ void RunIteration(bool enabled = true) {
+ SendMessages(enabled);
+
+ claw_plant_.SendPositionMessage();
+ claw_.Iterate();
+ claw_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) {
+ RunIteration(enabled);
+ }
+ }
+
+ // 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.
+ ClawQueue claw_queue_;
+
+ // Create a control loop and simulation.
+ Claw claw_;
+ ClawSimulation claw_plant_;
+};
+
+// Tests that the loop does nothing when the goal is our lower limit.
+TEST_F(ClawTest, DoesNothing) {
+ const auto &values = constants::GetValues();
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(values.claw.wrist.lower_limit)
+ .Send());
+
+ RunForTime(Time::InSeconds(6));
+
+ // We should not have moved.
+ VerifyNearGoal();
+}
+
+// NOTE: Claw zeroing is a little annoying because we only hit one index pulse
+// in our entire range of motion.
+
+// Tests that the loop zeroing works with normal values.
+TEST_F(ClawTest, Zeroes) {
+ // It should zero itself if we run it for awhile.
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ RunForTime(Time::InSeconds(6));
+
+ ASSERT_TRUE(claw_queue_.status.FetchLatest());
+ EXPECT_TRUE(claw_queue_.status->zeroed);
+ EXPECT_EQ(Claw::RUNNING, claw_queue_.status->state);
+}
+
+// Tests that claw zeroing fails if the index pulse occurs too close to the end
+// of the range.
+TEST_F(ClawTest, BadIndexPosition) {
+ const auto values = constants::GetValues();
+ claw_plant_.InitializePosition(values.claw.wrist.lower_limit,
+ values.claw.wrist.upper_limit);
+
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ // The zeroing is going to take its sweet time on this one, so we had better
+ // run it for longer.
+ RunForTime(Time::InMS(12000));
+
+ ASSERT_TRUE(claw_queue_.status.FetchLatest());
+ EXPECT_FALSE(claw_queue_.status->zeroed);
+ EXPECT_FALSE(claw_queue_.status->estopped);
+}
+
+// Tests that we can reach a reasonable goal.
+TEST_F(ClawTest, ReachesGoal) {
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ RunForTime(Time::InSeconds(6));
+
+ VerifyNearGoal();
+}
+
+// Tests that it doesn't try to move past the physical range of the mechanism.
+TEST_F(ClawTest, RespectsRange) {
+ const auto &values = constants::GetValues();
+ // Upper limit
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(values.claw.wrist.upper_hard_limit + 5.0)
+ .Send());
+
+ RunForTime(Time::InSeconds(7));
+
+ claw_queue_.status.FetchLatest();
+ EXPECT_NEAR(values.claw.wrist.upper_limit,
+ claw_queue_.status->angle,
+ 2.0 * M_PI / 180.0);
+
+ // Lower limit.
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(values.claw.wrist.lower_hard_limit - 5.0)
+ .Send());
+
+ RunForTime(Time::InMS(6000));
+
+ claw_queue_.status.FetchLatest();
+ EXPECT_NEAR(values.claw.wrist.lower_limit,
+ claw_queue_.status->angle,
+ 2.0 * M_PI / 180.0);
+}
+
+// Tests that starting at the lower hardstop doesn't cause an abort.
+TEST_F(ClawTest, LowerHardstopStartup) {
+ claw_plant_.InitializePosition(
+ constants::GetValues().claw.wrist.lower_hard_limit);
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+ RunForTime(Time::InSeconds(6));
+
+ VerifyNearGoal();
+}
+
+// Tests that starting at the upper hardstop doesn't cause an abort.
+TEST_F(ClawTest, UpperHardstopStartup) {
+ claw_plant_.InitializePosition(
+ constants::GetValues().claw.wrist.upper_hard_limit);
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+ // Zeroing will take a long time here.
+ RunForTime(Time::InSeconds(15));
+
+ VerifyNearGoal();
+}
+
+
+// Tests that not having a goal doesn't break anything.
+TEST_F(ClawTest, NoGoal) {
+ RunForTime(Time::InMS(50));
+}
+
+// Tests that a WPILib reset results in rezeroing.
+TEST_F(ClawTest, WpilibReset) {
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ RunForTime(Time::InSeconds(6));
+ VerifyNearGoal();
+
+ SimulateSensorReset();
+ RunForTime(Time::InMS(100));
+ ASSERT_TRUE(claw_queue_.status.FetchLatest());
+ EXPECT_NE(Claw::RUNNING, claw_queue_.status->state);
+
+ // Once again, it's going to take us awhile to rezero since we moved away from
+ // our index pulse.
+ RunForTime(Time::InSeconds(6));
+ VerifyNearGoal();
+}
+
+// Tests that internal goals don't change while disabled.
+TEST_F(ClawTest, DisabledGoal) {
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ RunForTime(Time::InMS(100), false);
+ EXPECT_EQ(0.0, claw_.claw_goal_);
+
+ // Now make sure they move correctly.
+ RunForTime(Time::InMS(1000), true);
+ EXPECT_NE(0.0, claw_.claw_goal_);
+}
+
+// Tests that the claw zeroing goals don't wind up too far.
+TEST_F(ClawTest, GoalPositiveWindup) {
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ while (claw_.state() != Claw::ZEROING) {
+ RunIteration();
+ }
+
+ // Kick it.
+ RunForTime(Time::InMS(50));
+ const double orig_claw_goal = claw_.claw_goal_;
+ claw_.claw_goal_ += 100.0;
+
+ RunIteration();
+ EXPECT_NEAR(orig_claw_goal, claw_.claw_goal_, 0.10);
+
+ RunIteration();
+
+ EXPECT_EQ(claw_.claw_loop_->U(), claw_.claw_loop_->U_uncapped());
+}
+
+// Tests that the claw zeroing goals don't wind up too far.
+TEST_F(ClawTest, GoalNegativeWindup) {
+ ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .Send());
+
+ while (claw_.state() != Claw::ZEROING) {
+ RunIteration();
+ }
+
+ // Kick it.
+ RunForTime(Time::InMS(50));
+ double orig_claw_goal = claw_.claw_goal_;
+ claw_.claw_goal_ -= 100.0;
+
+ RunIteration();
+ EXPECT_NEAR(orig_claw_goal, claw_.claw_goal_, 0.10);
+
+ RunIteration();
+
+ EXPECT_EQ(claw_.claw_loop_->U(), claw_.claw_loop_->U_uncapped());
+}
+
+} // namespace testing
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/claw/claw_main.cc b/y2015/control_loops/claw/claw_main.cc
new file mode 100644
index 0000000..d1b869c
--- /dev/null
+++ b/y2015/control_loops/claw/claw_main.cc
@@ -0,0 +1,11 @@
+#include "y2015/control_loops/claw/claw.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+ ::aos::Init();
+ frc971::control_loops::Claw claw;
+ claw.Run();
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2015/control_loops/claw/claw_motor_plant.cc b/y2015/control_loops/claw/claw_motor_plant.cc
new file mode 100644
index 0000000..5f5c206
--- /dev/null
+++ b/y2015/control_loops/claw/claw_motor_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015/control_loops/claw/claw_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeClawPlantCoefficients() {
+ Eigen::Matrix<double, 2, 2> A;
+ A << 1.0, 0.00482455476758, 0.0, 0.930652495326;
+ Eigen::Matrix<double, 2, 1> B;
+ B << 6.97110924671e-05, 0.0275544125308;
+ Eigen::Matrix<double, 1, 2> C;
+ C << 1, 0;
+ 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<2, 1, 1>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<2, 1, 1> MakeClawController() {
+ Eigen::Matrix<double, 2, 1> L;
+ L << 0.998251427366, 26.9874526231;
+ Eigen::Matrix<double, 1, 2> K;
+ K << 74.4310031124, 4.72251126222;
+ Eigen::Matrix<double, 2, 2> A_inv;
+ A_inv << 1.0, -0.00518405612386, 0.0, 1.07451492907;
+ return StateFeedbackController<2, 1, 1>(L, K, A_inv, MakeClawPlantCoefficients());
+}
+
+StateFeedbackPlant<2, 1, 1> MakeClawPlant() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>> plants(1);
+ plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>(new StateFeedbackPlantCoefficients<2, 1, 1>(MakeClawPlantCoefficients()));
+ return StateFeedbackPlant<2, 1, 1>(&plants);
+}
+
+StateFeedbackLoop<2, 1, 1> MakeClawLoop() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 1, 1>>> controllers(1);
+ controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 1, 1>>(new StateFeedbackController<2, 1, 1>(MakeClawController()));
+ return StateFeedbackLoop<2, 1, 1>(&controllers);
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/claw/claw_motor_plant.h b/y2015/control_loops/claw/claw_motor_plant.h
new file mode 100644
index 0000000..6cb9cdb
--- /dev/null
+++ b/y2015/control_loops/claw/claw_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
+#define Y2015_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 1, 1> MakeClawPlantCoefficients();
+
+StateFeedbackController<2, 1, 1> MakeClawController();
+
+StateFeedbackPlant<2, 1, 1> MakeClawPlant();
+
+StateFeedbackLoop<2, 1, 1> MakeClawLoop();
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
diff --git a/y2015/control_loops/claw/replay_claw.cc b/y2015/control_loops/claw/replay_claw.cc
new file mode 100644
index 0000000..50673e4
--- /dev/null
+++ b/y2015/control_loops/claw/replay_claw.cc
@@ -0,0 +1,24 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2015/control_loops/claw/claw.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" claw 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<::frc971::control_loops::ClawQueue>
+ replayer(&::frc971::control_loops::claw_queue, "claw");
+ for (int i = 1; i < argc; ++i) {
+ replayer.ProcessFile(argv[i]);
+ }
+
+ ::aos::Cleanup();
+}
diff --git a/y2015/control_loops/drivetrain/drivetrain.cc b/y2015/control_loops/drivetrain/drivetrain.cc
new file mode 100644
index 0000000..22a5d48
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain.cc
@@ -0,0 +1,777 @@
+#include "y2015/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 "y2015/constants.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2015/control_loops/drivetrain/polydrivetrain_cim_plant.h"
+#include "y2015/control_loops/drivetrain/drivetrain.q.h"
+#include "frc971/queues/gyro.q.h"
+#include "frc971/shifter_hall_effect.h"
+
+// A consistent way to mark code that goes away without shifters. It's still
+// here because we will have shifters again in the future.
+#define HAVE_SHIFTERS 0
+
+using frc971::sensors::gyro_reading;
+
+namespace frc971 {
+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 =
+ DoCoerceGoal(pos_poly, LH, wh, drive_error, &is_inside_h);
+ const auto adjusted_pos_error_45 =
+ 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(
+ constants::GetValues().make_drivetrain_loop())),
+ 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 * constants::GetValues().turn_width) / 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();
+ }
+ ::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,
+ SHIFTING_UP,
+ SHIFTING_DOWN
+ };
+ // 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.9603 / 2.0;
+ static constexpr double kWheelRadius = 0.0515938;
+ // Resistance of the motor, divided by the number of motors.
+ static constexpr double kR = (12.0 / kStallCurrent / 2 + 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>(
+ constants::GetValues().make_v_drivetrain_loop())),
+ 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 bool IsInGear(Gear gear) { return gear == LOW || gear == HIGH; }
+
+ static double MotorSpeed(const constants::ShifterHallEffect &hall_effect,
+ double shifter_position, double velocity) {
+ // TODO(austin): G_high, G_low and kWheelRadius
+ const double avg_hall_effect =
+ (hall_effect.clear_high + hall_effect.clear_low) / 2.0;
+
+ if (shifter_position > avg_hall_effect) {
+ return velocity / constants::GetValues().high_gear_ratio / kWheelRadius;
+ } else {
+ return velocity / constants::GetValues().low_gear_ratio / kWheelRadius;
+ }
+ }
+
+ Gear ComputeGear(const constants::ShifterHallEffect &hall_effect,
+ double velocity, Gear current) {
+ const double low_omega = MotorSpeed(hall_effect, 0.0, ::std::abs(velocity));
+ const double high_omega =
+ MotorSpeed(hall_effect, 1.0, ::std::abs(velocity));
+
+ double high_torque = ((12.0 - high_omega / Kv) * Kt / kR);
+ double low_torque = ((12.0 - low_omega / Kv) * Kt / kR);
+ double high_power = high_torque * high_omega;
+ double low_power = low_torque * low_omega;
+
+ // TODO(aschuh): Do this right!
+ if ((current == HIGH || high_power > low_power + 160) &&
+ ::std::abs(velocity) > 0.14) {
+ return HIGH;
+ } else {
+ return LOW;
+ }
+ }
+
+ 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;
+
+ wheel_ = sin(angular_range * wheel) / sin(angular_range);
+ wheel_ = sin(angular_range * wheel_) / sin(angular_range);
+ wheel_ *= 2.3;
+ quickturn_ = quickturn;
+
+ static const double kThrottleDeadband = 0.05;
+ if (::std::abs(throttle) < kThrottleDeadband) {
+ throttle_ = 0;
+ } else {
+ throttle_ = copysign((::std::abs(throttle) - kThrottleDeadband) /
+ (1.0 - kThrottleDeadband), throttle);
+ }
+
+ // TODO(austin): Fix the upshift logic to include states.
+ Gear requested_gear;
+ if (false) {
+ const auto &values = constants::GetValues();
+ 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_;
+
+ Gear left_requested =
+ ComputeGear(values.left_drive, current_left_velocity, left_gear_);
+ Gear right_requested =
+ ComputeGear(values.right_drive, current_right_velocity, right_gear_);
+ requested_gear =
+ (left_requested == HIGH || right_requested == HIGH) ? HIGH : LOW;
+ } else {
+ requested_gear = highgear ? HIGH : LOW;
+ }
+
+ const Gear shift_up =
+ constants::GetValues().clutch_transmission ? HIGH : SHIFTING_UP;
+ const Gear shift_down =
+ constants::GetValues().clutch_transmission ? LOW : SHIFTING_DOWN;
+
+ if (left_gear_ != requested_gear) {
+ if (IsInGear(left_gear_)) {
+ if (requested_gear == HIGH) {
+ left_gear_ = shift_up;
+ } else {
+ left_gear_ = shift_down;
+ }
+ } else {
+ if (requested_gear == HIGH && left_gear_ == SHIFTING_DOWN) {
+ left_gear_ = SHIFTING_UP;
+ } else if (requested_gear == LOW && left_gear_ == SHIFTING_UP) {
+ left_gear_ = SHIFTING_DOWN;
+ }
+ }
+ }
+ if (right_gear_ != requested_gear) {
+ if (IsInGear(right_gear_)) {
+ if (requested_gear == HIGH) {
+ right_gear_ = shift_up;
+ } else {
+ right_gear_ = shift_down;
+ }
+ } else {
+ if (requested_gear == HIGH && right_gear_ == SHIFTING_DOWN) {
+ right_gear_ = SHIFTING_UP;
+ } else if (requested_gear == LOW && right_gear_ == SHIFTING_UP) {
+ right_gear_ = SHIFTING_DOWN;
+ }
+ }
+ }
+ }
+ void SetPosition(const DrivetrainQueue::Position *position) {
+ const auto &values = constants::GetValues();
+ if (position == NULL) {
+ ++stale_count_;
+ } else {
+ last_position_ = position_;
+ position_ = *position;
+ position_time_delta_ = (stale_count_ + 1) * 0.01;
+ stale_count_ = 0;
+ }
+
+#if HAVE_SHIFTERS
+ if (position) {
+ GearLogging gear_logging;
+ // Switch to the correct controller.
+ const double left_middle_shifter_position =
+ (values.left_drive.clear_high + values.left_drive.clear_low) / 2.0;
+ const double right_middle_shifter_position =
+ (values.right_drive.clear_high + values.right_drive.clear_low) / 2.0;
+
+ if (position->left_shifter_position < left_middle_shifter_position ||
+ left_gear_ == LOW) {
+ if (position->right_shifter_position < right_middle_shifter_position ||
+ right_gear_ == LOW) {
+ gear_logging.left_loop_high = false;
+ gear_logging.right_loop_high = false;
+ loop_->set_controller_index(gear_logging.controller_index = 0);
+ } else {
+ gear_logging.left_loop_high = false;
+ gear_logging.right_loop_high = true;
+ loop_->set_controller_index(gear_logging.controller_index = 1);
+ }
+ } else {
+ if (position->right_shifter_position < right_middle_shifter_position ||
+ right_gear_ == LOW) {
+ gear_logging.left_loop_high = true;
+ gear_logging.right_loop_high = false;
+ loop_->set_controller_index(gear_logging.controller_index = 2);
+ } else {
+ gear_logging.left_loop_high = true;
+ gear_logging.right_loop_high = true;
+ loop_->set_controller_index(gear_logging.controller_index = 3);
+ }
+ }
+
+ // TODO(austin): Constants.
+ if (position->left_shifter_position > values.left_drive.clear_high && left_gear_ == SHIFTING_UP) {
+ left_gear_ = HIGH;
+ }
+ if (position->left_shifter_position < values.left_drive.clear_low && left_gear_ == SHIFTING_DOWN) {
+ left_gear_ = LOW;
+ }
+ if (position->right_shifter_position > values.right_drive.clear_high && right_gear_ == SHIFTING_UP) {
+ right_gear_ = HIGH;
+ }
+ if (position->right_shifter_position < values.right_drive.clear_low && right_gear_ == SHIFTING_DOWN) {
+ right_gear_ = LOW;
+ }
+
+ gear_logging.left_state = left_gear_;
+ gear_logging.right_state = right_gear_;
+ LOG_STRUCT(DEBUG, "state", gear_logging);
+ }
+#else
+ (void) values;
+#endif
+ }
+
+ 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() {
+ const auto &values = constants::GetValues();
+ // TODO(austin): Observer for the current velocity instead of difference
+ // calculations.
+ ++counter_;
+#if HAVE_SHIFTERS
+ 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(values.left_drive, position_.left_shifter_position,
+ current_left_velocity);
+ const double right_motor_speed =
+ MotorSpeed(values.right_drive, position_.right_shifter_position,
+ current_right_velocity);
+
+ {
+ CIMLogging logging;
+
+ // Reset the CIM model to the current conditions to be ready for when we
+ // shift.
+ if (IsInGear(left_gear_)) {
+ logging.left_in_gear = true;
+ } else {
+ logging.left_in_gear = false;
+ }
+ logging.left_motor_speed = left_motor_speed;
+ logging.left_velocity = current_left_velocity;
+ if (IsInGear(right_gear_)) {
+ logging.right_in_gear = true;
+ } else {
+ logging.right_in_gear = false;
+ }
+ logging.right_motor_speed = right_motor_speed;
+ logging.right_velocity = current_right_velocity;
+
+ LOG_STRUCT(DEBUG, "currently", logging);
+ }
+#else
+ (void) values;
+#endif
+
+#if HAVE_SHIFTERS
+ if (IsInGear(left_gear_) && IsInGear(right_gear_)) {
+#else
+ {
+#endif
+ // 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() =
+ 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): Feed back?
+ loop_->mutable_X_hat() =
+ loop_->A() * loop_->X_hat() + loop_->B() * loop_->U();
+#if HAVE_SHIFTERS
+ } else {
+ // Any motor is not in gear. Speed match.
+ ::Eigen::Matrix<double, 1, 1> R_left;
+ ::Eigen::Matrix<double, 1, 1> R_right;
+ R_left(0, 0) = left_motor_speed;
+ R_right(0, 0) = right_motor_speed;
+
+ const double wiggle =
+ (static_cast<double>((counter_ % 20) / 10) - 0.5) * 5.0;
+
+ loop_->mutable_U(0, 0) = ::aos::Clip(
+ (R_left / Kv)(0, 0) + (IsInGear(left_gear_) ? 0 : wiggle),
+ -12.0, 12.0);
+ loop_->mutable_U(1, 0) = ::aos::Clip(
+ (R_right / Kv)(0, 0) + (IsInGear(right_gear_) ? 0 : wiggle),
+ -12.0, 12.0);
+ loop_->mutable_U() *= 12.0 / ::aos::robot_state->voltage_battery;
+#endif
+ }
+ }
+
+ 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 || left_gear_ == SHIFTING_UP;
+ output->right_high = right_gear_ == HIGH || right_gear_ == SHIFTING_UP;
+ }
+ }
+
+ 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;
+#if HAVE_SHIFTERS
+ bool highgear = goal->highgear;
+#endif
+
+ 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);
+#if HAVE_SHIFTERS
+ dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
+#else
+ dt_openloop.SetGoal(wheel, throttle, quickturn, false);
+#endif
+ }
+
+ 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) {
+ bool done = false;
+ if (goal) {
+ done = ((::std::abs(goal->left_goal -
+ dt_closedloop.GetEstimatedLeftEncoder()) <
+ constants::GetValues().drivetrain_done_distance) &&
+ (::std::abs(goal->right_goal -
+ dt_closedloop.GetEstimatedRightEncoder()) <
+ constants::GetValues().drivetrain_done_distance));
+ }
+ status->is_done = done;
+ status->robot_speed = dt_closedloop.GetEstimatedRobotSpeed();
+ status->filtered_left_position = dt_closedloop.GetEstimatedLeftEncoder();
+ status->filtered_right_position = dt_closedloop.GetEstimatedRightEncoder();
+
+ status->filtered_left_velocity = dt_closedloop.loop().X_hat(1, 0);
+ status->filtered_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 frc971
diff --git a/y2015/control_loops/drivetrain/drivetrain.gyp b/y2015/control_loops/drivetrain/drivetrain.gyp
new file mode 100644
index 0000000..4333258
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain.gyp
@@ -0,0 +1,103 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'replay_drivetrain',
+ 'type': 'executable',
+ 'variables': {
+ 'no_rsync': 1,
+ },
+ 'sources': [
+ 'replay_drivetrain.cc',
+ ],
+ 'dependencies': [
+ 'drivetrain_queue',
+ '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+ '<(AOS)/linux_code/linux_code.gyp:init',
+ ],
+ },
+ {
+ 'target_name': 'drivetrain_queue',
+ 'type': 'static_library',
+ 'sources': ['drivetrain.q'],
+ 'variables': {
+ 'header_path': 'y2015/control_loops/drivetrain',
+ },
+ 'dependencies': [
+ '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+ ],
+ 'includes': ['../../../aos/build/queues.gypi'],
+ },
+ {
+ 'target_name': 'polydrivetrain_plants',
+ 'type': 'static_library',
+ 'sources': [
+ 'polydrivetrain_dog_motor_plant.cc',
+ 'drivetrain_dog_motor_plant.cc',
+ ],
+ 'dependencies': [
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ ],
+ 'export_dependent_settings': [
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ ],
+ },
+ {
+ 'target_name': 'drivetrain_lib',
+ 'type': 'static_library',
+ 'sources': [
+ 'drivetrain.cc',
+ 'polydrivetrain_cim_plant.cc',
+ ],
+ 'dependencies': [
+ 'drivetrain_queue',
+ '<(AOS)/common/controls/controls.gyp:control_loop',
+ '<(DEPTH)/y2015/y2015.gyp:constants',
+ '<(AOS)/common/controls/controls.gyp:polytope',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+ '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+ '<(AOS)/common/util/util.gyp:log_interval',
+ '<(AOS)/common/logging/logging.gyp:queue_logging',
+ '<(AOS)/common/logging/logging.gyp:matrix_logging',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/controls/controls.gyp:polytope',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
+ '<(AOS)/common/controls/controls.gyp:control_loop',
+ 'drivetrain_queue',
+ ],
+ },
+ {
+ 'target_name': 'drivetrain_lib_test',
+ 'type': 'executable',
+ 'sources': [
+ 'drivetrain_lib_test.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ 'drivetrain_queue',
+ 'drivetrain_lib',
+ '<(AOS)/common/controls/controls.gyp:control_loop_test',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(DEPTH)/frc971/queues/queues.gyp:gyro',
+ '<(AOS)/common/common.gyp:queues',
+ ],
+ },
+ {
+ 'target_name': 'drivetrain',
+ 'type': 'executable',
+ 'sources': [
+ 'drivetrain_main.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/linux_code/linux_code.gyp:init',
+ 'drivetrain_lib',
+ 'drivetrain_queue',
+ ],
+ },
+ ],
+}
diff --git a/y2015/control_loops/drivetrain/drivetrain.h b/y2015/control_loops/drivetrain/drivetrain.h
new file mode 100644
index 0000000..8e8768e
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain.h
@@ -0,0 +1,43 @@
+#ifndef Y2015_CONTROL_LOOPS_DRIVETRAIN_H_
+#define Y2015_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 "y2015/control_loops/drivetrain/drivetrain.q.h"
+#include "aos/common/util/log_interval.h"
+
+namespace frc971 {
+namespace control_loops {
+
+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 frc971::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 frc971
+
+#endif // Y2015_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/y2015/control_loops/drivetrain/drivetrain.q b/y2015/control_loops/drivetrain/drivetrain.q
new file mode 100644
index 0000000..942c5b3
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain.q
@@ -0,0 +1,71 @@
+package frc971.control_loops;
+
+import "aos/common/controls/control_loops.q";
+
+struct GearLogging {
+ int8_t controller_index;
+ bool left_loop_high;
+ bool right_loop_high;
+ int8_t left_state;
+ int8_t right_state;
+};
+
+struct CIMLogging {
+ bool left_in_gear;
+ bool right_in_gear;
+ double left_motor_speed;
+ double right_motor_speed;
+ double left_velocity;
+ double right_velocity;
+};
+
+queue_group DrivetrainQueue {
+ implements aos.control_loops.ControlLoop;
+
+ message Goal {
+ double steering;
+ double throttle;
+ //bool highgear;
+ bool quickturn;
+ bool control_loop_driving;
+ double left_goal;
+ double left_velocity_goal;
+ double right_goal;
+ double right_velocity_goal;
+ };
+
+ message Position {
+ double left_encoder;
+ double right_encoder;
+ //double left_shifter_position;
+ //double right_shifter_position;
+ };
+
+ message Output {
+ double left_voltage;
+ double right_voltage;
+ bool left_high;
+ bool right_high;
+ };
+
+ message Status {
+ double robot_speed;
+ double filtered_left_position;
+ double filtered_right_position;
+ double filtered_left_velocity;
+ double filtered_right_velocity;
+
+ double uncapped_left_voltage;
+ double uncapped_right_voltage;
+ bool output_was_capped;
+
+ bool is_done;
+ };
+
+ queue Goal goal;
+ queue Position position;
+ queue Output output;
+ queue Status status;
+};
+
+queue_group DrivetrainQueue drivetrain_queue;
diff --git a/y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.cc b/y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..e2f5a9a
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
@@ -0,0 +1,133 @@
+#include "y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowLowPlantCoefficients() {
+ Eigen::Matrix<double, 4, 4> A;
+ A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
+ Eigen::Matrix<double, 4, 2> B;
+ B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
+ Eigen::Matrix<double, 2, 4> C;
+ C << 1, 0, 0, 0, 0, 0, 1, 0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients() {
+ Eigen::Matrix<double, 4, 4> A;
+ A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
+ Eigen::Matrix<double, 4, 2> B;
+ B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
+ Eigen::Matrix<double, 2, 4> C;
+ C << 1, 0, 0, 0, 0, 0, 1, 0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients() {
+ Eigen::Matrix<double, 4, 4> A;
+ A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
+ Eigen::Matrix<double, 4, 2> B;
+ B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
+ Eigen::Matrix<double, 2, 4> C;
+ C << 1, 0, 0, 0, 0, 0, 1, 0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients() {
+ Eigen::Matrix<double, 4, 4> A;
+ A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
+ Eigen::Matrix<double, 4, 2> B;
+ B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
+ Eigen::Matrix<double, 2, 4> C;
+ C << 1, 0, 0, 0, 0, 0, 1, 0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController() {
+ Eigen::Matrix<double, 4, 2> L;
+ L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
+ Eigen::Matrix<double, 2, 4> K;
+ K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
+ Eigen::Matrix<double, 4, 4> A_inv;
+ A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
+ return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController() {
+ Eigen::Matrix<double, 4, 2> L;
+ L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
+ Eigen::Matrix<double, 2, 4> K;
+ K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
+ Eigen::Matrix<double, 4, 4> A_inv;
+ A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
+ return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController() {
+ Eigen::Matrix<double, 4, 2> L;
+ L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
+ Eigen::Matrix<double, 2, 4> K;
+ K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
+ Eigen::Matrix<double, 4, 4> A_inv;
+ A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
+ return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController() {
+ Eigen::Matrix<double, 4, 2> L;
+ L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
+ Eigen::Matrix<double, 2, 4> K;
+ K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
+ Eigen::Matrix<double, 4, 4> A_inv;
+ A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
+ return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighHighPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(4);
+ plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowLowPlantCoefficients()));
+ plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowHighPlantCoefficients()));
+ plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighLowPlantCoefficients()));
+ plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighHighPlantCoefficients()));
+ return StateFeedbackPlant<4, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(4);
+ controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowLowController()));
+ controllers[1] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowHighController()));
+ controllers[2] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighLowController()));
+ controllers[3] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighHighController()));
+ return StateFeedbackLoop<4, 2, 2>(&controllers);
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.h b/y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..a2848be
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef Y2015_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define Y2015_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowLowPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController();
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController();
+
+StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop();
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2015/control_loops/drivetrain/drivetrain_lib_test.cc b/y2015/control_loops/drivetrain/drivetrain_lib_test.cc
new file mode 100644
index 0000000..d3869aa
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -0,0 +1,297 @@
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/network/team_number.h"
+#include "aos/common/queue_testutils.h"
+#include "aos/common/controls/polytope.h"
+#include "aos/common/controls/control_loop_test.h"
+
+#include "y2015/control_loops/drivetrain/drivetrain.q.h"
+#include "y2015/control_loops/drivetrain/drivetrain.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "frc971/control_loops/coerce_goal.h"
+#include "y2015/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "frc971/queues/gyro.q.h"
+
+
+namespace frc971 {
+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>(MakeDrivetrainPlant())),
+ my_drivetrain_queue_(".frc971.control_loops.drivetrain",
+ 0x8a8dde77, ".frc971.control_loops.drivetrain.goal",
+ ".frc971.control_loops.drivetrain.position",
+ ".frc971.control_loops.drivetrain.output",
+ ".frc971.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_(".frc971.control_loops.drivetrain",
+ 0x8a8dde77,
+ ".frc971.control_loops.drivetrain.goal",
+ ".frc971.control_loops.drivetrain.position",
+ ".frc971.control_loops.drivetrain.output",
+ ".frc971.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 frc971
diff --git a/y2015/control_loops/drivetrain/drivetrain_main.cc b/y2015/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..10a50f3
--- /dev/null
+++ b/y2015/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,11 @@
+#include "y2015/control_loops/drivetrain/drivetrain.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+ ::aos::Init();
+ frc971::control_loops::DrivetrainLoop drivetrain;
+ drivetrain.Run();
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2015/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/y2015/control_loops/drivetrain/polydrivetrain_cim_plant.cc
new file mode 100644
index 0000000..36ebb59
--- /dev/null
+++ b/y2015/control_loops/drivetrain/polydrivetrain_cim_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015/control_loops/drivetrain/polydrivetrain_cim_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+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 frc971
diff --git a/y2015/control_loops/drivetrain/polydrivetrain_cim_plant.h b/y2015/control_loops/drivetrain/polydrivetrain_cim_plant.h
new file mode 100644
index 0000000..1c445a7
--- /dev/null
+++ b/y2015/control_loops/drivetrain/polydrivetrain_cim_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+#define Y2015_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+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 frc971
+
+#endif // Y2015_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
new file mode 100644
index 0000000..811991c
--- /dev/null
+++ b/y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
@@ -0,0 +1,133 @@
+#include "y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients() {
+ Eigen::Matrix<double, 2, 2> A;
+ A << 0.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
+ Eigen::Matrix<double, 2, 2> B;
+ B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
+ 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.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
+ Eigen::Matrix<double, 2, 2> B;
+ B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
+ 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.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
+ Eigen::Matrix<double, 2, 2> B;
+ B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
+ 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.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
+ Eigen::Matrix<double, 2, 2> B;
+ B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
+ 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.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
+ Eigen::Matrix<double, 2, 2> K;
+ K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
+ Eigen::Matrix<double, 2, 2> A_inv;
+ A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
+ return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController() {
+ Eigen::Matrix<double, 2, 2> L;
+ L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
+ Eigen::Matrix<double, 2, 2> K;
+ K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
+ Eigen::Matrix<double, 2, 2> A_inv;
+ A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
+ return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowHighPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController() {
+ Eigen::Matrix<double, 2, 2> L;
+ L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
+ Eigen::Matrix<double, 2, 2> K;
+ K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
+ Eigen::Matrix<double, 2, 2> A_inv;
+ A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
+ return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighLowPlantCoefficients());
+}
+
+StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController() {
+ Eigen::Matrix<double, 2, 2> L;
+ L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
+ Eigen::Matrix<double, 2, 2> K;
+ K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
+ Eigen::Matrix<double, 2, 2> A_inv;
+ A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
+ 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 frc971
diff --git a/y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
new file mode 100644
index 0000000..5a99caf
--- /dev/null
+++ b/y2015/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
@@ -0,0 +1,32 @@
+#ifndef Y2015_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+#define Y2015_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+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 frc971
+
+#endif // Y2015_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/y2015/control_loops/drivetrain/replay_drivetrain.cc b/y2015/control_loops/drivetrain/replay_drivetrain.cc
new file mode 100644
index 0000000..030a945
--- /dev/null
+++ b/y2015/control_loops/drivetrain/replay_drivetrain.cc
@@ -0,0 +1,24 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2015/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<::frc971::control_loops::DrivetrainQueue>
+ replayer(&::frc971::control_loops::drivetrain_queue, "drivetrain");
+ for (int i = 1; i < argc; ++i) {
+ replayer.ProcessFile(argv[i]);
+ }
+
+ ::aos::Cleanup();
+}
diff --git a/y2015/control_loops/fridge/arm_motor_plant.cc b/y2015/control_loops/fridge/arm_motor_plant.cc
new file mode 100644
index 0000000..6e3205a
--- /dev/null
+++ b/y2015/control_loops/fridge/arm_motor_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015/control_loops/fridge/arm_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeArmPlantCoefficients() {
+ Eigen::Matrix<double, 4, 4> A;
+ A << 1.0, 0.00479642025454, 0.0, 0.0, 0.0, 0.919688585028, 0.0, 0.0, 0.0, 0.0, 0.999539771613, 0.00479566382645, 0.0, 0.0, -0.18154390621, 0.919241022297;
+ Eigen::Matrix<double, 4, 2> B;
+ B << 2.46496779984e-05, 2.46496779984e-05, 0.00972420175808, 0.00972420175808, 2.46477449538e-05, -2.46477449538e-05, 0.00972266818532, -0.00972266818532;
+ Eigen::Matrix<double, 2, 4> C;
+ C << 1, 0, 1, 0, 1, 0, -1, 0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<4, 2, 2> MakeArmController() {
+ Eigen::Matrix<double, 4, 2> L;
+ L << 0.759844292514, 0.759844292514, 54.2541762188, 54.2541762188, 0.759390396955, -0.759390396955, 54.1048167043, -54.1048167043;
+ Eigen::Matrix<double, 2, 4> K;
+ K << 320.979606093, 21.0129517955, 884.233784759, 36.3637782119, 320.979606095, 21.0129517956, -884.233784749, -36.3637782119;
+ Eigen::Matrix<double, 4, 4> A_inv;
+ A_inv << 1.0, -0.00521526561559, 0.0, 0.0, 0.0, 1.08732457517, 0.0, 0.0, 0.0, 0.0, 0.999513354044, -0.00521444313273, 0.0, 0.0, 0.197397150694, 1.08682415753;
+ return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeArmPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeArmPlant() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(1);
+ plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeArmPlantCoefficients()));
+ return StateFeedbackPlant<4, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeArmLoop() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(1);
+ controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeArmController()));
+ return StateFeedbackLoop<4, 2, 2>(&controllers);
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/fridge/arm_motor_plant.h b/y2015/control_loops/fridge/arm_motor_plant.h
new file mode 100644
index 0000000..3bf8d09
--- /dev/null
+++ b/y2015/control_loops/fridge/arm_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_CONTROL_LOOPS_FRIDGE_ARM_MOTOR_PLANT_H_
+#define Y2015_CONTROL_LOOPS_FRIDGE_ARM_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeArmPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeArmController();
+
+StateFeedbackPlant<4, 2, 2> MakeArmPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeArmLoop();
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_FRIDGE_ARM_MOTOR_PLANT_H_
diff --git a/y2015/control_loops/fridge/elevator_motor_plant.cc b/y2015/control_loops/fridge/elevator_motor_plant.cc
new file mode 100644
index 0000000..995d838
--- /dev/null
+++ b/y2015/control_loops/fridge/elevator_motor_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015/control_loops/fridge/elevator_motor_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeElevatorPlantCoefficients() {
+ Eigen::Matrix<double, 4, 4> A;
+ A << 1.0, 0.00435668193669, 0.0, 0.0, 0.0, 0.754212786054, 0.0, 0.0, 0.0, 0.0, 0.997194498569, 0.00435222083164, 0.0, 0.0, -1.07131589702, 0.751658962986;
+ Eigen::Matrix<double, 4, 2> B;
+ B << 3.82580284276e-05, 3.82580284276e-05, 0.0146169286307, 0.0146169286307, 3.82387898839e-05, -3.82387898839e-05, 0.0146019613563, -0.0146019613563;
+ Eigen::Matrix<double, 2, 4> C;
+ C << 1, 0, 1, 0, 1, 0, -1, 0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<4, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<4, 2, 2> MakeElevatorController() {
+ Eigen::Matrix<double, 4, 2> L;
+ L << 0.677106393027, 0.677106393027, 35.5375738607, 35.5375738607, 0.674426730777, -0.674426730777, 34.7138874344, -34.7138874344;
+ Eigen::Matrix<double, 2, 4> K;
+ K << 321.310606763, 11.7674534233, 601.047935717, 12.6977148843, 321.310606764, 11.7674534233, -601.047935716, -12.6977148843;
+ Eigen::Matrix<double, 4, 4> A_inv;
+ A_inv << 1.0, -0.00577646258091, 0.0, 0.0, 0.0, 1.32588576923, 0.0, 0.0, 0.0, 0.0, 0.996613922337, -0.00577054766522, 0.0, 0.0, 1.42044250221, 1.32216599481;
+ return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeElevatorPlantCoefficients());
+}
+
+StateFeedbackPlant<4, 2, 2> MakeElevatorPlant() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(1);
+ plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeElevatorPlantCoefficients()));
+ return StateFeedbackPlant<4, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<4, 2, 2> MakeElevatorLoop() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(1);
+ controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeElevatorController()));
+ return StateFeedbackLoop<4, 2, 2>(&controllers);
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/fridge/elevator_motor_plant.h b/y2015/control_loops/fridge/elevator_motor_plant.h
new file mode 100644
index 0000000..e68e6d7
--- /dev/null
+++ b/y2015/control_loops/fridge/elevator_motor_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_CONTROL_LOOPS_FRIDGE_ELEVATOR_MOTOR_PLANT_H_
+#define Y2015_CONTROL_LOOPS_FRIDGE_ELEVATOR_MOTOR_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<4, 2, 2> MakeElevatorPlantCoefficients();
+
+StateFeedbackController<4, 2, 2> MakeElevatorController();
+
+StateFeedbackPlant<4, 2, 2> MakeElevatorPlant();
+
+StateFeedbackLoop<4, 2, 2> MakeElevatorLoop();
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_FRIDGE_ELEVATOR_MOTOR_PLANT_H_
diff --git a/y2015/control_loops/fridge/fridge.cc b/y2015/control_loops/fridge/fridge.cc
new file mode 100644
index 0000000..083baf2
--- /dev/null
+++ b/y2015/control_loops/fridge/fridge.cc
@@ -0,0 +1,720 @@
+#include "y2015/control_loops/fridge/fridge.h"
+
+#include <cmath>
+
+#include "aos/common/controls/control_loops.q.h"
+#include "aos/common/logging/logging.h"
+
+#include "y2015/control_loops/fridge/elevator_motor_plant.h"
+#include "y2015/control_loops/fridge/integral_arm_plant.h"
+#include "frc971/control_loops/voltage_cap/voltage_cap.h"
+#include "frc971/zeroing/zeroing.h"
+
+#include "y2015/constants.h"
+
+namespace frc971 {
+namespace control_loops {
+
+namespace {
+constexpr double kZeroingVoltage = 4.0;
+constexpr double kElevatorZeroingVelocity = 0.10;
+// What speed we move to our safe height at.
+constexpr double kElevatorSafeHeightVelocity = 0.3;
+constexpr double kArmZeroingVelocity = 0.20;
+} // namespace
+
+template <int S>
+void CappedStateFeedbackLoop<S>::CapU() {
+ VoltageCap(max_voltage_, this->U(0, 0), this->U(1, 0), &this->mutable_U(0, 0),
+ &this->mutable_U(1, 0));
+}
+
+template <int S>
+Eigen::Matrix<double, 2, 1>
+CappedStateFeedbackLoop<S>::UnsaturateOutputGoalChange() {
+ // Compute the K matrix used to compensate for position errors.
+ Eigen::Matrix<double, 2, 2> Kp;
+ Kp.setZero();
+ Kp.col(0) = this->K().col(0);
+ Kp.col(1) = this->K().col(2);
+
+ Eigen::Matrix<double, 2, 2> Kp_inv = Kp.inverse();
+
+ // Compute how much we need to change R in order to achieve the change in U
+ // that was observed.
+ Eigen::Matrix<double, 2, 1> deltaR =
+ -Kp_inv * (this->U_uncapped() - this->U());
+ return deltaR;
+}
+
+Fridge::Fridge(control_loops::FridgeQueue *fridge)
+ : aos::controls::ControlLoop<control_loops::FridgeQueue>(fridge),
+ arm_loop_(new CappedStateFeedbackLoop<5>(
+ StateFeedbackLoop<5, 2, 2>(MakeIntegralArmLoop()))),
+ elevator_loop_(new CappedStateFeedbackLoop<4>(
+ StateFeedbackLoop<4, 2, 2>(MakeElevatorLoop()))),
+ left_arm_estimator_(constants::GetValues().fridge.left_arm_zeroing),
+ right_arm_estimator_(constants::GetValues().fridge.right_arm_zeroing),
+ left_elevator_estimator_(constants::GetValues().fridge.left_elev_zeroing),
+ right_elevator_estimator_(
+ constants::GetValues().fridge.right_elev_zeroing),
+ last_profiling_type_(ProfilingType::ANGLE_HEIGHT_PROFILING),
+ kinematics_(constants::GetValues().fridge.arm_length,
+ constants::GetValues().fridge.elevator.upper_limit,
+ constants::GetValues().fridge.elevator.lower_limit,
+ constants::GetValues().fridge.arm.upper_limit,
+ constants::GetValues().fridge.arm.lower_limit),
+ arm_profile_(::aos::controls::kLoopFrequency),
+ elevator_profile_(::aos::controls::kLoopFrequency),
+ x_profile_(::aos::controls::kLoopFrequency),
+ y_profile_(::aos::controls::kLoopFrequency) {}
+
+void Fridge::UpdateZeroingState() {
+ if (left_elevator_estimator_.offset_ratio_ready() < 1.0 ||
+ right_elevator_estimator_.offset_ratio_ready() < 1.0 ||
+ left_arm_estimator_.offset_ratio_ready() < 1.0 ||
+ right_arm_estimator_.offset_ratio_ready() < 1.0) {
+ state_ = INITIALIZING;
+ } else if (!left_elevator_estimator_.zeroed() ||
+ !right_elevator_estimator_.zeroed()) {
+ state_ = ZEROING_ELEVATOR;
+ } else if (!left_arm_estimator_.zeroed() || !right_arm_estimator_.zeroed()) {
+ state_ = ZEROING_ARM;
+ } else {
+ state_ = RUNNING;
+ }
+}
+
+void Fridge::Correct() {
+ {
+ Eigen::Matrix<double, 2, 1> Y;
+ Y << left_elevator(), right_elevator();
+ elevator_loop_->Correct(Y);
+ }
+
+ {
+ Eigen::Matrix<double, 2, 1> Y;
+ Y << left_arm(), right_arm();
+ arm_loop_->Correct(Y);
+ }
+}
+
+void Fridge::SetElevatorOffset(double left_offset, double right_offset) {
+ LOG(INFO, "Changing Elevator offset from %f, %f to %f, %f\n",
+ left_elevator_offset_, right_elevator_offset_, left_offset, right_offset);
+ double left_doffset = left_offset - left_elevator_offset_;
+ double right_doffset = right_offset - right_elevator_offset_;
+
+ // Adjust the average height and height difference between the two sides.
+ // The derivatives of both should not need to be updated since the speeds
+ // haven't changed.
+ // The height difference is calculated as left - right, not right - left.
+ elevator_loop_->mutable_X_hat(0, 0) += (left_doffset + right_doffset) / 2;
+ elevator_loop_->mutable_X_hat(2, 0) += (left_doffset - right_doffset) / 2;
+
+ // Modify the zeroing goal.
+ elevator_goal_ += (left_doffset + right_doffset) / 2;
+
+ // Update the cached offset values to the actual values.
+ left_elevator_offset_ = left_offset;
+ right_elevator_offset_ = right_offset;
+}
+
+void Fridge::SetArmOffset(double left_offset, double right_offset) {
+ LOG(INFO, "Changing Arm offset from %f, %f to %f, %f\n", left_arm_offset_,
+ right_arm_offset_, left_offset, right_offset);
+ double left_doffset = left_offset - left_arm_offset_;
+ double right_doffset = right_offset - right_arm_offset_;
+
+ // Adjust the average angle and angle difference between the two sides.
+ // The derivatives of both should not need to be updated since the speeds
+ // haven't changed.
+ arm_loop_->mutable_X_hat(0, 0) += (left_doffset + right_doffset) / 2;
+ arm_loop_->mutable_X_hat(2, 0) += (left_doffset - right_doffset) / 2;
+
+ // Modify the zeroing goal.
+ arm_goal_ += (left_doffset + right_doffset) / 2;
+
+ // Update the cached offset values to the actual values.
+ left_arm_offset_ = left_offset;
+ right_arm_offset_ = right_offset;
+}
+
+double Fridge::estimated_left_elevator() {
+ return current_position_.elevator.left.encoder +
+ left_elevator_estimator_.offset();
+}
+double Fridge::estimated_right_elevator() {
+ return current_position_.elevator.right.encoder +
+ right_elevator_estimator_.offset();
+}
+
+double Fridge::estimated_elevator() {
+ return (estimated_left_elevator() + estimated_right_elevator()) / 2.0;
+}
+
+double Fridge::estimated_left_arm() {
+ return current_position_.arm.left.encoder + left_arm_estimator_.offset();
+}
+double Fridge::estimated_right_arm() {
+ return current_position_.arm.right.encoder + right_arm_estimator_.offset();
+}
+double Fridge::estimated_arm() {
+ return (estimated_left_arm() + estimated_right_arm()) / 2.0;
+}
+
+double Fridge::left_elevator() {
+ return current_position_.elevator.left.encoder + left_elevator_offset_;
+}
+double Fridge::right_elevator() {
+ return current_position_.elevator.right.encoder + right_elevator_offset_;
+}
+
+double Fridge::elevator() { return (left_elevator() + right_elevator()) / 2.0; }
+
+double Fridge::left_arm() {
+ return current_position_.arm.left.encoder + left_arm_offset_;
+}
+double Fridge::right_arm() {
+ return current_position_.arm.right.encoder + right_arm_offset_;
+}
+double Fridge::arm() { return (left_arm() + right_arm()) / 2.0; }
+
+double Fridge::elevator_zeroing_velocity() {
+ double average_elevator =
+ (constants::GetValues().fridge.elevator.lower_limit +
+ constants::GetValues().fridge.elevator.upper_limit) /
+ 2.0;
+
+ const double pulse_width = ::std::max(
+ constants::GetValues().fridge.left_elev_zeroing.index_difference,
+ constants::GetValues().fridge.right_elev_zeroing.index_difference);
+
+ if (elevator_zeroing_velocity_ == 0) {
+ if (estimated_elevator() > average_elevator) {
+ elevator_zeroing_velocity_ = -kElevatorZeroingVelocity;
+ } else {
+ elevator_zeroing_velocity_ = kElevatorZeroingVelocity;
+ }
+ } else if (elevator_zeroing_velocity_ > 0 &&
+ estimated_elevator() > average_elevator + 1.1 * pulse_width) {
+ elevator_zeroing_velocity_ = -kElevatorZeroingVelocity;
+ } else if (elevator_zeroing_velocity_ < 0 &&
+ estimated_elevator() < average_elevator - 1.1 * pulse_width) {
+ elevator_zeroing_velocity_ = kElevatorZeroingVelocity;
+ }
+ return elevator_zeroing_velocity_;
+}
+
+double Fridge::UseUnlessZero(double target_value, double default_value) {
+ if (target_value != 0.0) {
+ return target_value;
+ } else {
+ return default_value;
+ }
+}
+
+double Fridge::arm_zeroing_velocity() {
+ const double average_arm = (constants::GetValues().fridge.arm.lower_limit +
+ constants::GetValues().fridge.arm.upper_limit) /
+ 2.0;
+ const double pulse_width = ::std::max(
+ constants::GetValues().fridge.right_arm_zeroing.index_difference,
+ constants::GetValues().fridge.left_arm_zeroing.index_difference);
+
+ if (arm_zeroing_velocity_ == 0) {
+ if (estimated_arm() > average_arm) {
+ arm_zeroing_velocity_ = -kArmZeroingVelocity;
+ } else {
+ arm_zeroing_velocity_ = kArmZeroingVelocity;
+ }
+ } else if (arm_zeroing_velocity_ > 0.0 &&
+ estimated_arm() > average_arm + 1.1 * pulse_width) {
+ arm_zeroing_velocity_ = -kArmZeroingVelocity;
+ } else if (arm_zeroing_velocity_ < 0.0 && estimated_arm() < average_arm) {
+ arm_zeroing_velocity_ = kArmZeroingVelocity;
+ }
+ return arm_zeroing_velocity_;
+}
+
+void Fridge::RunIteration(const control_loops::FridgeQueue::Goal *unsafe_goal,
+ const control_loops::FridgeQueue::Position *position,
+ control_loops::FridgeQueue::Output *output,
+ control_loops::FridgeQueue::Status *status) {
+ if (WasReset()) {
+ LOG(ERROR, "WPILib reset, restarting\n");
+ left_elevator_estimator_.Reset();
+ right_elevator_estimator_.Reset();
+ left_arm_estimator_.Reset();
+ right_arm_estimator_.Reset();
+ state_ = UNINITIALIZED;
+ }
+
+ // Get a reference to the constants struct since we use it so often in this
+ // code.
+ const auto &values = constants::GetValues();
+
+ // Bool to track if we should turn the motors on or not.
+ bool disable = output == nullptr;
+
+ // Save the current position so it can be used easily in the class.
+ current_position_ = *position;
+
+ left_elevator_estimator_.UpdateEstimate(position->elevator.left);
+ right_elevator_estimator_.UpdateEstimate(position->elevator.right);
+ left_arm_estimator_.UpdateEstimate(position->arm.left);
+ right_arm_estimator_.UpdateEstimate(position->arm.right);
+
+ if (state_ != UNINITIALIZED) {
+ Correct();
+ }
+
+ // Zeroing will work as follows:
+ // At startup, record the offset of the two halves of the two subsystems.
+ // Then, start moving the elevator towards the center until both halves are
+ // zeroed.
+ // Then, start moving the claw towards the center until both halves are
+ // zeroed.
+ // Then, done!
+
+ // We'll then need code to do sanity checking on values.
+
+ // Now, we need to figure out which way to go.
+
+ switch (state_) {
+ case UNINITIALIZED:
+ LOG(DEBUG, "Uninitialized\n");
+ // Startup. Assume that we are at the origin everywhere.
+ // This records the encoder offset between the two sides of the elevator.
+ left_elevator_offset_ = -position->elevator.left.encoder;
+ right_elevator_offset_ = -position->elevator.right.encoder;
+ left_arm_offset_ = -position->arm.left.encoder;
+ right_arm_offset_ = -position->arm.right.encoder;
+ elevator_loop_->mutable_X_hat().setZero();
+ arm_loop_->mutable_X_hat().setZero();
+ LOG(INFO, "Initializing arm offsets to %f, %f\n", left_arm_offset_,
+ right_arm_offset_);
+ LOG(INFO, "Initializing elevator offsets to %f, %f\n",
+ left_elevator_offset_, right_elevator_offset_);
+ Correct();
+ state_ = INITIALIZING;
+ disable = true;
+ break;
+
+ case INITIALIZING:
+ LOG(DEBUG, "Waiting for accurate initial position.\n");
+ disable = true;
+ // Update state_ to accurately represent the state of the zeroing
+ // estimators.
+ UpdateZeroingState();
+ if (state_ != INITIALIZING) {
+ // Set the goals to where we are now.
+ elevator_goal_ = elevator();
+ arm_goal_ = arm();
+ }
+ break;
+
+ case ZEROING_ELEVATOR:
+ LOG(DEBUG, "Zeroing elevator\n");
+
+ // Update state_ to accurately represent the state of the zeroing
+ // estimators.
+ UpdateZeroingState();
+ if (left_elevator_estimator_.zeroed() &&
+ right_elevator_estimator_.zeroed()) {
+ SetElevatorOffset(left_elevator_estimator_.offset(),
+ right_elevator_estimator_.offset());
+ LOG(DEBUG, "Zeroed the elevator!\n");
+
+ if (elevator() < values.fridge.arm_zeroing_height &&
+ state_ != INITIALIZING) {
+ // Move the elevator to a safe height before we start zeroing the arm,
+ // so that we don't crash anything.
+ LOG(DEBUG, "Moving elevator to safe height.\n");
+ if (elevator_goal_ < values.fridge.arm_zeroing_height) {
+ elevator_goal_ += kElevatorSafeHeightVelocity *
+ ::aos::controls::kLoopFrequency.ToSeconds();
+ elevator_goal_velocity_ = kElevatorSafeHeightVelocity;
+ state_ = ZEROING_ELEVATOR;
+ } else {
+ // We want it stopped at whatever height it's currently set to.
+ elevator_goal_velocity_ = 0;
+ }
+ }
+ } else if (!disable) {
+ elevator_goal_velocity_ = elevator_zeroing_velocity();
+ elevator_goal_ += elevator_goal_velocity_ *
+ ::aos::controls::kLoopFrequency.ToSeconds();
+ }
+
+ // Bypass motion profiles while we are zeroing.
+ // This is also an important step right after the elevator is zeroed and
+ // we reach into the elevator's state matrix and change it based on the
+ // newly-obtained offset.
+ {
+ Eigen::Matrix<double, 2, 1> current;
+ current.setZero();
+ current << elevator_goal_, elevator_goal_velocity_;
+ elevator_profile_.MoveCurrentState(current);
+ }
+ break;
+
+ case ZEROING_ARM:
+ LOG(DEBUG, "Zeroing the arm\n");
+
+ if (elevator() < values.fridge.arm_zeroing_height - 0.10 ||
+ elevator_goal_ < values.fridge.arm_zeroing_height) {
+ LOG(INFO,
+ "Going back to ZEROING_ELEVATOR until it gets high enough to "
+ "safely zero the arm\n");
+ state_ = ZEROING_ELEVATOR;
+ break;
+ }
+
+ // Update state_ to accurately represent the state of the zeroing
+ // estimators.
+ UpdateZeroingState();
+ if (left_arm_estimator_.zeroed() && right_arm_estimator_.zeroed()) {
+ SetArmOffset(left_arm_estimator_.offset(),
+ right_arm_estimator_.offset());
+ LOG(DEBUG, "Zeroed the arm!\n");
+ } else if (!disable) {
+ arm_goal_velocity_ = arm_zeroing_velocity();
+ arm_goal_ +=
+ arm_goal_velocity_ * ::aos::controls::kLoopFrequency.ToSeconds();
+ }
+
+ // Bypass motion profiles while we are zeroing.
+ // This is also an important step right after the arm is zeroed and
+ // we reach into the arm's state matrix and change it based on the
+ // newly-obtained offset.
+ {
+ Eigen::Matrix<double, 2, 1> current;
+ current.setZero();
+ current << arm_goal_, arm_goal_velocity_;
+ arm_profile_.MoveCurrentState(current);
+ }
+ break;
+
+ case RUNNING:
+ LOG(DEBUG, "Running!\n");
+ if (unsafe_goal) {
+ // Handle the case where we switch between the types of profiling.
+ ProfilingType new_profiling_type =
+ static_cast<ProfilingType>(unsafe_goal->profiling_type);
+
+ if (last_profiling_type_ != new_profiling_type) {
+ // Reset the height/angle profiles.
+ Eigen::Matrix<double, 2, 1> current;
+ current.setZero();
+ current << arm_goal_, arm_goal_velocity_;
+ arm_profile_.MoveCurrentState(current);
+ current << elevator_goal_, elevator_goal_velocity_;
+ elevator_profile_.MoveCurrentState(current);
+
+ // Reset the x/y profiles.
+ aos::util::ElevatorArmKinematics::KinematicResult x_y_result;
+ kinematics_.ForwardKinematic(elevator_goal_, arm_goal_,
+ elevator_goal_velocity_,
+ arm_goal_velocity_, &x_y_result);
+ current << x_y_result.fridge_x, x_y_result.fridge_x_velocity;
+ x_profile_.MoveCurrentState(current);
+ current << x_y_result.fridge_h, x_y_result.fridge_h_velocity;
+ y_profile_.MoveCurrentState(current);
+
+ last_profiling_type_ = new_profiling_type;
+ }
+
+ if (new_profiling_type == ProfilingType::ANGLE_HEIGHT_PROFILING) {
+ // Pick a set of sane arm defaults if none are specified.
+ arm_profile_.set_maximum_velocity(
+ UseUnlessZero(unsafe_goal->max_angular_velocity, 1.0));
+ arm_profile_.set_maximum_acceleration(
+ UseUnlessZero(unsafe_goal->max_angular_acceleration, 3.0));
+ elevator_profile_.set_maximum_velocity(
+ UseUnlessZero(unsafe_goal->max_velocity, 0.50));
+ elevator_profile_.set_maximum_acceleration(
+ UseUnlessZero(unsafe_goal->max_acceleration, 2.0));
+
+ // Use the profiles to limit the arm's movements.
+ const double unfiltered_arm_goal = ::std::max(
+ ::std::min(unsafe_goal->angle, values.fridge.arm.upper_limit),
+ values.fridge.arm.lower_limit);
+ ::Eigen::Matrix<double, 2, 1> arm_goal_state = arm_profile_.Update(
+ unfiltered_arm_goal, unsafe_goal->angular_velocity);
+ arm_goal_ = arm_goal_state(0, 0);
+ arm_goal_velocity_ = arm_goal_state(1, 0);
+
+ // Use the profiles to limit the elevator's movements.
+ const double unfiltered_elevator_goal =
+ ::std::max(::std::min(unsafe_goal->height,
+ values.fridge.elevator.upper_limit),
+ values.fridge.elevator.lower_limit);
+ ::Eigen::Matrix<double, 2, 1> elevator_goal_state =
+ elevator_profile_.Update(unfiltered_elevator_goal,
+ unsafe_goal->velocity);
+ elevator_goal_ = elevator_goal_state(0, 0);
+ elevator_goal_velocity_ = elevator_goal_state(1, 0);
+ } else if (new_profiling_type == ProfilingType::X_Y_PROFILING) {
+ // Use x/y profiling
+ aos::util::ElevatorArmKinematics::KinematicResult kinematic_result;
+
+ x_profile_.set_maximum_velocity(
+ UseUnlessZero(unsafe_goal->max_x_velocity, 0.5));
+ x_profile_.set_maximum_acceleration(
+ UseUnlessZero(unsafe_goal->max_x_acceleration, 2.0));
+ y_profile_.set_maximum_velocity(
+ UseUnlessZero(unsafe_goal->max_y_velocity, 0.50));
+ y_profile_.set_maximum_acceleration(
+ UseUnlessZero(unsafe_goal->max_y_acceleration, 2.0));
+
+ // Limit the goals before we update the profiles.
+ kinematics_.InverseKinematic(
+ unsafe_goal->x, unsafe_goal->y, unsafe_goal->x_velocity,
+ unsafe_goal->y_velocity, &kinematic_result);
+
+ // Use the profiles to limit the x movements.
+ ::Eigen::Matrix<double, 2, 1> x_goal_state = x_profile_.Update(
+ kinematic_result.fridge_x, kinematic_result.fridge_x_velocity);
+
+ // Use the profiles to limit the y movements.
+ ::Eigen::Matrix<double, 2, 1> y_goal_state = y_profile_.Update(
+ kinematic_result.fridge_h, kinematic_result.fridge_h_velocity);
+
+ // Convert x/y goal states into arm/elevator goals.
+ // The inverse kinematics functions automatically perform range
+ // checking and adjust the results so that they're always valid.
+ kinematics_.InverseKinematic(x_goal_state(0, 0), y_goal_state(0, 0),
+ x_goal_state(1, 0), y_goal_state(1, 0),
+ &kinematic_result);
+
+ // Store the appropriate inverse kinematic results in the
+ // arm/elevator goals.
+ arm_goal_ = kinematic_result.arm_angle;
+ arm_goal_velocity_ = kinematic_result.arm_velocity;
+
+ elevator_goal_ = kinematic_result.elevator_height;
+ elevator_goal_velocity_ = kinematic_result.arm_velocity;
+ } else {
+ LOG(ERROR, "Unknown profiling_type: %d\n",
+ unsafe_goal->profiling_type);
+ }
+ }
+
+ // Update state_ to accurately represent the state of the zeroing
+ // estimators.
+ UpdateZeroingState();
+
+ if (state_ != RUNNING && state_ != ESTOP) {
+ state_ = UNINITIALIZED;
+ }
+ break;
+
+ case ESTOP:
+ LOG(ERROR, "Estop\n");
+ disable = true;
+ break;
+ }
+
+ // Commence death if either left/right tracking error gets too big. This
+ // should run immediately after the SetArmOffset and SetElevatorOffset
+ // functions to double-check that the hardware is in a sane state.
+ if (::std::abs(left_arm() - right_arm()) >=
+ values.max_allowed_left_right_arm_difference) {
+ LOG(ERROR, "The arms are too far apart. |%f - %f| > %f\n", left_arm(),
+ right_arm(), values.max_allowed_left_right_arm_difference);
+
+ // Indicate an ESTOP condition and stop the motors.
+ if (output) {
+ state_ = ESTOP;
+ }
+ disable = true;
+ }
+
+ if (::std::abs(left_elevator() - right_elevator()) >=
+ values.max_allowed_left_right_elevator_difference) {
+ LOG(ERROR, "The elevators are too far apart. |%f - %f| > %f\n",
+ left_elevator(), right_elevator(),
+ values.max_allowed_left_right_elevator_difference);
+
+ // Indicate an ESTOP condition and stop the motors.
+ if (output) {
+ state_ = ESTOP;
+ }
+ disable = true;
+ }
+
+ // Limit the goals so we can't exceed the hardware limits if we are RUNNING.
+ if (state_ == RUNNING) {
+ // Limit the arm goal to min/max allowable angles.
+ if (arm_goal_ >= values.fridge.arm.upper_limit) {
+ LOG(WARNING, "Arm goal above limit, %f > %f\n", arm_goal_,
+ values.fridge.arm.upper_limit);
+ arm_goal_ = values.fridge.arm.upper_limit;
+ }
+ if (arm_goal_ <= values.fridge.arm.lower_limit) {
+ LOG(WARNING, "Arm goal below limit, %f < %f\n", arm_goal_,
+ values.fridge.arm.lower_limit);
+ arm_goal_ = values.fridge.arm.lower_limit;
+ }
+
+ // Limit the elevator goal to min/max allowable heights.
+ if (elevator_goal_ >= values.fridge.elevator.upper_limit) {
+ LOG(WARNING, "Elevator goal above limit, %f > %f\n", elevator_goal_,
+ values.fridge.elevator.upper_limit);
+ elevator_goal_ = values.fridge.elevator.upper_limit;
+ }
+ if (elevator_goal_ <= values.fridge.elevator.lower_limit) {
+ LOG(WARNING, "Elevator goal below limit, %f < %f\n", elevator_goal_,
+ values.fridge.elevator.lower_limit);
+ elevator_goal_ = values.fridge.elevator.lower_limit;
+ }
+ }
+
+ // Check the lower level hardware limit as well.
+ if (state_ == RUNNING) {
+ if (left_arm() >= values.fridge.arm.upper_hard_limit ||
+ left_arm() <= values.fridge.arm.lower_hard_limit) {
+ LOG(ERROR, "Left arm at %f out of bounds [%f, %f], ESTOPing\n",
+ left_arm(), values.fridge.arm.lower_hard_limit,
+ values.fridge.arm.upper_hard_limit);
+ if (output) {
+ state_ = ESTOP;
+ }
+ }
+
+ if (right_arm() >= values.fridge.arm.upper_hard_limit ||
+ right_arm() <= values.fridge.arm.lower_hard_limit) {
+ LOG(ERROR, "Right arm at %f out of bounds [%f, %f], ESTOPing\n",
+ right_arm(), values.fridge.arm.lower_hard_limit,
+ values.fridge.arm.upper_hard_limit);
+ if (output) {
+ state_ = ESTOP;
+ }
+ }
+
+ if (left_elevator() >= values.fridge.elevator.upper_hard_limit) {
+ LOG(ERROR, "Left elevator at %f out of bounds [%f, %f], ESTOPing\n",
+ left_elevator(), values.fridge.elevator.lower_hard_limit,
+ values.fridge.elevator.upper_hard_limit);
+ if (output) {
+ state_ = ESTOP;
+ }
+ }
+
+ if (right_elevator() >= values.fridge.elevator.upper_hard_limit) {
+ LOG(ERROR, "Right elevator at %f out of bounds [%f, %f], ESTOPing\n",
+ right_elevator(), values.fridge.elevator.lower_hard_limit,
+ values.fridge.elevator.upper_hard_limit);
+ if (output) {
+ state_ = ESTOP;
+ }
+ }
+ }
+
+ // Set the goals.
+ arm_loop_->mutable_R() << arm_goal_, arm_goal_velocity_, 0.0, 0.0, 0.0;
+ elevator_loop_->mutable_R() << elevator_goal_, elevator_goal_velocity_, 0.0,
+ 0.0;
+
+ const double max_voltage = state_ == RUNNING ? 12.0 : kZeroingVoltage;
+ arm_loop_->set_max_voltage(max_voltage);
+ elevator_loop_->set_max_voltage(max_voltage);
+
+ if (state_ == ESTOP) {
+ disable = true;
+ }
+ arm_loop_->Update(disable);
+ elevator_loop_->Update(disable);
+
+ if (state_ == INITIALIZING || state_ == ZEROING_ELEVATOR ||
+ state_ == ZEROING_ARM) {
+ if (arm_loop_->U() != arm_loop_->U_uncapped()) {
+ Eigen::Matrix<double, 2, 1> deltaR =
+ arm_loop_->UnsaturateOutputGoalChange();
+
+ // Move the average arm goal by the amount observed.
+ LOG(WARNING, "Moving arm goal by %f to handle saturation\n",
+ deltaR(0, 0));
+ arm_goal_ += deltaR(0, 0);
+ }
+
+ if (elevator_loop_->U() != elevator_loop_->U_uncapped()) {
+ Eigen::Matrix<double, 2, 1> deltaR =
+ elevator_loop_->UnsaturateOutputGoalChange();
+
+ // Move the average elevator goal by the amount observed.
+ LOG(WARNING, "Moving elevator goal by %f to handle saturation\n",
+ deltaR(0, 0));
+ elevator_goal_ += deltaR(0, 0);
+ }
+ }
+
+ if (output) {
+ output->left_arm = arm_loop_->U(0, 0);
+ output->right_arm = arm_loop_->U(1, 0);
+ output->left_elevator = elevator_loop_->U(0, 0);
+ output->right_elevator = elevator_loop_->U(1, 0);
+ if (unsafe_goal) {
+ output->grabbers = unsafe_goal->grabbers;
+ } else {
+ output->grabbers.top_front = false;
+ output->grabbers.top_back = false;
+ output->grabbers.bottom_front = false;
+ output->grabbers.bottom_back = false;
+ }
+ }
+
+ // TODO(austin): Populate these fully.
+ status->zeroed = state_ == RUNNING;
+
+ status->angle = arm_loop_->X_hat(0, 0);
+ status->angular_velocity = arm_loop_->X_hat(1, 0);
+ status->height = elevator_loop_->X_hat(0, 0);
+ status->velocity = elevator_loop_->X_hat(1, 0);
+
+ status->goal_angle = arm_goal_;
+ status->goal_angular_velocity = arm_goal_velocity_;
+ status->goal_height = elevator_goal_;
+ status->goal_velocity = elevator_goal_velocity_;
+
+ // Populate the same status, but in X/Y co-ordinates.
+ aos::util::ElevatorArmKinematics::KinematicResult x_y_status;
+ kinematics_.ForwardKinematic(status->height, status->angle,
+ status->velocity, status->angular_velocity,
+ &x_y_status);
+ status->x = x_y_status.fridge_x;
+ status->y = x_y_status.fridge_h;
+ status->x_velocity = x_y_status.fridge_x_velocity;
+ status->y_velocity = x_y_status.fridge_h_velocity;
+
+ kinematics_.ForwardKinematic(status->goal_height, status->goal_angle,
+ status->goal_velocity, status->goal_angular_velocity,
+ &x_y_status);
+ status->goal_x = x_y_status.fridge_x;
+ status->goal_y = x_y_status.fridge_h;
+ status->goal_x_velocity = x_y_status.fridge_x_velocity;
+ status->goal_y_velocity = x_y_status.fridge_h_velocity;
+
+ if (unsafe_goal) {
+ status->grabbers = unsafe_goal->grabbers;
+ } else {
+ status->grabbers.top_front = false;
+ status->grabbers.top_back = false;
+ status->grabbers.bottom_front = false;
+ status->grabbers.bottom_back = false;
+ }
+ zeroing::PopulateEstimatorState(left_arm_estimator_, &status->left_arm_state);
+ zeroing::PopulateEstimatorState(right_arm_estimator_,
+ &status->right_arm_state);
+ zeroing::PopulateEstimatorState(left_elevator_estimator_,
+ &status->left_elevator_state);
+ zeroing::PopulateEstimatorState(right_elevator_estimator_,
+ &status->right_elevator_state);
+ status->estopped = (state_ == ESTOP);
+ status->state = state_;
+ last_state_ = state_;
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/fridge/fridge.gyp b/y2015/control_loops/fridge/fridge.gyp
new file mode 100644
index 0000000..76844c4
--- /dev/null
+++ b/y2015/control_loops/fridge/fridge.gyp
@@ -0,0 +1,89 @@
+{
+ 'targets': [
+ {
+ 'target_name': 'replay_fridge',
+ 'type': 'executable',
+ 'variables': {
+ 'no_rsync': 1,
+ },
+ 'sources': [
+ 'replay_fridge.cc',
+ ],
+ 'dependencies': [
+ 'fridge_queue',
+ '<(AOS)/common/controls/controls.gyp:replay_control_loop',
+ '<(AOS)/linux_code/linux_code.gyp:init',
+ ],
+ },
+ {
+ 'target_name': 'fridge_queue',
+ 'type': 'static_library',
+ 'sources': ['fridge.q'],
+ 'variables': {
+ 'header_path': 'y2015/control_loops/fridge',
+ },
+ 'dependencies': [
+ '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+ '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
+ ],
+ 'export_dependent_settings': [
+ '<(AOS)/common/controls/controls.gyp:control_loop_queues',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
+ '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
+ ],
+ 'includes': ['../../../aos/build/queues.gypi'],
+ },
+ {
+ 'target_name': 'fridge_lib',
+ 'type': 'static_library',
+ 'sources': [
+ 'fridge.cc',
+ 'integral_arm_plant.cc',
+ 'elevator_motor_plant.cc',
+ ],
+ 'dependencies': [
+ 'fridge_queue',
+ '<(AOS)/common/controls/controls.gyp:control_loop',
+ '<(AOS)/common/util/util.gyp:trapezoid_profile',
+ '<(DEPTH)/y2015/y2015.gyp:constants',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(DEPTH)/frc971/control_loops/voltage_cap/voltage_cap.gyp:voltage_cap',
+ ],
+ 'export_dependent_settings': [
+ 'fridge_queue',
+ '<(AOS)/common/controls/controls.gyp:control_loop',
+ '<(AOS)/common/util/util.gyp:trapezoid_profile',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ ],
+ },
+ {
+ 'target_name': 'fridge_lib_test',
+ 'type': 'executable',
+ 'sources': [
+ 'fridge_lib_test.cc',
+ 'arm_motor_plant.cc',
+ ],
+ 'dependencies': [
+ '<(EXTERNALS):gtest',
+ 'fridge_lib',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
+ '<(AOS)/common/controls/controls.gyp:control_loop_test',
+ '<(AOS)/common/common.gyp:time',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:position_sensor_sim',
+ '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
+ ],
+ },
+ {
+ 'target_name': 'fridge',
+ 'type': 'executable',
+ 'sources': [
+ 'fridge_main.cc',
+ ],
+ 'dependencies': [
+ '<(AOS)/linux_code/linux_code.gyp:init',
+ 'fridge_lib',
+ ],
+ },
+ ],
+}
diff --git a/y2015/control_loops/fridge/fridge.h b/y2015/control_loops/fridge/fridge.h
new file mode 100644
index 0000000..0448e09
--- /dev/null
+++ b/y2015/control_loops/fridge/fridge.h
@@ -0,0 +1,172 @@
+#ifndef Y2015_CONTROL_LOOPS_FRIDGE_H_
+#define Y2015_CONTROL_LOOPS_FRIDGE_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 "y2015/control_loops/fridge/fridge.q.h"
+#include "frc971/zeroing/zeroing.h"
+#include "y2015/util/kinematics.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+class FridgeTest_DisabledGoalTest_Test;
+class FridgeTest_ArmGoalPositiveWindupTest_Test;
+class FridgeTest_ElevatorGoalPositiveWindupTest_Test;
+class FridgeTest_ArmGoalNegativeWindupTest_Test;
+class FridgeTest_ElevatorGoalNegativeWindupTest_Test;
+class FridgeTest_SafeArmZeroing_Test;
+} // namespace testing
+
+template<int S>
+class CappedStateFeedbackLoop : public StateFeedbackLoop<S, 2, 2> {
+ public:
+ CappedStateFeedbackLoop(StateFeedbackLoop<S, 2, 2> &&loop)
+ : StateFeedbackLoop<S, 2, 2>(::std::move(loop)), max_voltage_(12.0) {}
+
+ void set_max_voltage(double max_voltage) {
+ max_voltage_ = ::std::max(0.0, ::std::min(12.0, max_voltage));
+ }
+
+ void CapU() override;
+
+ // Returns the amount to change the position goals (average and difference) in
+ // order to no longer saturate the controller.
+ Eigen::Matrix<double, 2, 1> UnsaturateOutputGoalChange();
+
+ private:
+ double max_voltage_;
+};
+
+class Fridge
+ : public aos::controls::ControlLoop<control_loops::FridgeQueue> {
+ public:
+ explicit Fridge(
+ control_loops::FridgeQueue *fridge_queue = &control_loops::fridge_queue);
+
+ enum State {
+ // Waiting to receive data before doing anything.
+ UNINITIALIZED = 0,
+ // Estimating the starting location.
+ INITIALIZING = 1,
+ // Moving the elevator to find an index pulse.
+ ZEROING_ELEVATOR = 2,
+ // Moving the arm to find an index pulse.
+ ZEROING_ARM = 3,
+ // All good!
+ RUNNING = 4,
+ // Internal error caused the fridge to abort.
+ ESTOP = 5,
+ };
+
+ enum class ProfilingType : int32_t {
+ // Use angle/height to specify the fridge goal.
+ ANGLE_HEIGHT_PROFILING = 0,
+ // Use x/y co-ordinates to specify the fridge goal.
+ X_Y_PROFILING = 1,
+ };
+
+ State state() const { return state_; }
+
+ protected:
+ void RunIteration(const control_loops::FridgeQueue::Goal *goal,
+ const control_loops::FridgeQueue::Position *position,
+ control_loops::FridgeQueue::Output *output,
+ control_loops::FridgeQueue::Status *status) override;
+
+ private:
+ friend class testing::FridgeTest_DisabledGoalTest_Test;
+ friend class testing::FridgeTest_ElevatorGoalPositiveWindupTest_Test;
+ friend class testing::FridgeTest_ArmGoalPositiveWindupTest_Test;
+ friend class testing::FridgeTest_ElevatorGoalNegativeWindupTest_Test;
+ friend class testing::FridgeTest_ArmGoalNegativeWindupTest_Test;
+ friend class testing::FridgeTest_SafeArmZeroing_Test;
+
+ // Sets state_ to the correct state given the current state of the zeroing
+ // estimators.
+ void UpdateZeroingState();
+
+ void SetElevatorOffset(double left_offset, double right_offset);
+ void SetArmOffset(double left_offset, double right_offset);
+
+ // Getters for the current elevator positions.
+ double left_elevator();
+ double right_elevator();
+ double elevator();
+
+ // Getters for the current arm positions.
+ double left_arm();
+ double right_arm();
+ double arm();
+
+ // Our best guess at the current position of the elevator.
+ double estimated_left_elevator();
+ double estimated_right_elevator();
+ double estimated_elevator();
+
+ // Our best guess at the current position of the arm.
+ double estimated_left_arm();
+ double estimated_right_arm();
+ double estimated_arm();
+
+ // Returns the current zeroing velocity for either subsystem.
+ // If the subsystem is too far away from the center, these will switch
+ // directions.
+ double elevator_zeroing_velocity();
+ double arm_zeroing_velocity();
+
+ // Corrects the Observer with the current position.
+ void Correct();
+
+ double UseUnlessZero(double target_value, double default_value);
+
+ // The state feedback control loop or loops to talk to.
+ ::std::unique_ptr<CappedStateFeedbackLoop<5>> arm_loop_;
+ ::std::unique_ptr<CappedStateFeedbackLoop<4>> elevator_loop_;
+
+ zeroing::ZeroingEstimator left_arm_estimator_;
+ zeroing::ZeroingEstimator right_arm_estimator_;
+ zeroing::ZeroingEstimator left_elevator_estimator_;
+ zeroing::ZeroingEstimator right_elevator_estimator_;
+
+ // Offsets from the encoder position to the absolute position. Add these to
+ // the encoder position to get the absolute position.
+ double left_elevator_offset_ = 0.0;
+ double right_elevator_offset_ = 0.0;
+ double left_arm_offset_ = 0.0;
+ double right_arm_offset_ = 0.0;
+
+ // Current velocity to move at while zeroing.
+ double elevator_zeroing_velocity_ = 0.0;
+ double arm_zeroing_velocity_ = 0.0;
+
+ // The goals for the elevator and arm.
+ double elevator_goal_ = 0.0;
+ double arm_goal_ = 0.0;
+
+ double arm_goal_velocity_ = 0.0;
+ double elevator_goal_velocity_ = 0.0;
+
+ State state_ = UNINITIALIZED;
+ State last_state_ = UNINITIALIZED;
+
+ control_loops::FridgeQueue::Position current_position_;
+
+ ProfilingType last_profiling_type_;
+ aos::util::ElevatorArmKinematics kinematics_;
+
+ aos::util::TrapezoidProfile arm_profile_;
+ aos::util::TrapezoidProfile elevator_profile_;
+
+ aos::util::TrapezoidProfile x_profile_;
+ aos::util::TrapezoidProfile y_profile_;
+};
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_FRIDGE_H_
+
diff --git a/y2015/control_loops/fridge/fridge.q b/y2015/control_loops/fridge/fridge.q
new file mode 100644
index 0000000..257374d
--- /dev/null
+++ b/y2015/control_loops/fridge/fridge.q
@@ -0,0 +1,152 @@
+package frc971.control_loops;
+
+import "aos/common/controls/control_loops.q";
+import "frc971/control_loops/control_loops.q";
+
+// Represents states for all of the box-grabbing pistons.
+// true is grabbed and false is retracted for all of them.
+struct GrabberPistons {
+ bool top_front;
+ bool top_back;
+ bool bottom_front;
+ bool bottom_back;
+};
+
+queue_group FridgeQueue {
+ implements aos.control_loops.ControlLoop;
+
+ // All angles are in radians with 0 sticking straight up.
+ // Rotating up and into the robot (towards the back
+ // where boxes are placed) is positive. Positive output voltage moves all
+ // mechanisms in the direction with positive sensor values.
+
+ // Elevator heights are the vertical distance (in meters) from a defined zero.
+ // In this case, zero is where the portion of the carriage that Spencer
+ // removed lines up with the bolt.
+
+ // X/Y positions are distances (in meters) the fridge is away from its origin
+ // position. Origin is considered at a height of zero and an angle of zero.
+ // Positive X positions are towards the front of the robot and negative X is
+ // towards the back of the robot (which is where we score).
+ // Y is positive going up and negative when it goes below the origin.
+
+ message Goal {
+ // Profile type.
+ // Set to 0 for angle/height profiling.
+ // Set to 1 for x/y profiling.
+ int32_t profiling_type;
+
+ // Angle of the arm.
+ double angle;
+ // Height of the elevator.
+ double height;
+
+ // Angular velocity of the arm.
+ float angular_velocity;
+ // Linear velocity of the elevator.
+ float velocity;
+
+ // Maximum arm profile angular velocity or 0 for the default.
+ float max_angular_velocity;
+ // Maximum elevator profile velocity or 0 for the default.
+ float max_velocity;
+
+ // Maximum arm profile acceleration or 0 for the default.
+ float max_angular_acceleration;
+ // Maximum elevator profile acceleration or 0 for the default.
+ float max_acceleration;
+
+ // X position of the fridge.
+ double x;
+ // Y position of the fridge.
+ double y;
+
+ // Velocity of the x position of the fridge.
+ float x_velocity;
+ // Velocity of the y position of the fridge.
+ float y_velocity;
+
+ // Maximum x profile velocity or 0 for the default.
+ float max_x_velocity;
+ // Maximum y profile velocity or 0 for the default.
+ float max_y_velocity;
+
+ // Maximum x profile acceleration or 0 for the default.
+ float max_x_acceleration;
+ // Maximum y profile acceleration or 0 for the default.
+ float max_y_acceleration;
+
+ // TODO(austin): Do I need acceleration here too?
+
+ GrabberPistons grabbers;
+ };
+
+ message Position {
+ PotAndIndexPair arm;
+ PotAndIndexPair elevator;
+ };
+
+ message Status {
+ // Are both the arm and elevator zeroed?
+ bool zeroed;
+
+ // Estimated angle of the arm.
+ double angle;
+ // Estimated angular velocity of the arm.
+ float angular_velocity;
+ // Estimated height of the elevator.
+ double height;
+ // Estimated velocity of the elvator.
+ float velocity;
+ // state of the grabber pistons
+ GrabberPistons grabbers;
+
+ // Goal angle and velocity of the arm.
+ double goal_angle;
+ float goal_angular_velocity;
+ // Goal height and velocity of the elevator.
+ double goal_height;
+ float goal_velocity;
+
+ // Estimated X/Y position of the fridge.
+ // These are translated directly from the height/angle statuses.
+ double x;
+ double y;
+ float x_velocity;
+ float y_velocity;
+
+ // X/Y goals of the fridge.
+ // These are translated directly from the height/angle goals.
+ double goal_x;
+ double goal_y;
+ float goal_x_velocity;
+ float goal_y_velocity;
+
+ // If true, we have aborted.
+ bool estopped;
+
+ // The internal state of the state machine.
+ int32_t state;
+
+ EstimatorState left_elevator_state;
+ EstimatorState right_elevator_state;
+ EstimatorState left_arm_state;
+ EstimatorState right_arm_state;
+ };
+
+ message Output {
+ double left_arm;
+ double right_arm;
+ double left_elevator;
+ double right_elevator;
+
+ GrabberPistons grabbers;
+ };
+
+ queue Goal goal;
+ queue Position position;
+ queue Output output;
+ queue Status status;
+};
+
+queue_group FridgeQueue fridge_queue;
diff --git a/y2015/control_loops/fridge/fridge_lib_test.cc b/y2015/control_loops/fridge/fridge_lib_test.cc
new file mode 100644
index 0000000..7719fb4
--- /dev/null
+++ b/y2015/control_loops/fridge/fridge_lib_test.cc
@@ -0,0 +1,735 @@
+#include "y2015/control_loops/fridge/fridge.h"
+
+#include <math.h>
+#include <unistd.h>
+
+#include <memory>
+
+#include "gtest/gtest.h"
+#include "aos/common/queue.h"
+#include "aos/common/time.h"
+#include "aos/common/commonmath.h"
+#include "aos/common/controls/control_loop_test.h"
+#include "y2015/util/kinematics.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "y2015/control_loops/fridge/arm_motor_plant.h"
+#include "y2015/control_loops/fridge/elevator_motor_plant.h"
+#include "y2015/control_loops/fridge/fridge.q.h"
+#include "y2015/constants.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+
+using ::aos::time::Time;
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+// Class which simulates the fridge and sends out queue messages with the
+// position.
+class FridgeSimulation {
+ public:
+ static constexpr double kNoiseScalar = 0.1;
+ // Constructs a simulation.
+ FridgeSimulation()
+ : arm_plant_(new StateFeedbackPlant<4, 2, 2>(MakeArmPlant())),
+ elevator_plant_(new StateFeedbackPlant<4, 2, 2>(MakeElevatorPlant())),
+ left_arm_pot_encoder_(
+ constants::GetValues().fridge.left_arm_zeroing.index_difference),
+ right_arm_pot_encoder_(
+ constants::GetValues().fridge.right_arm_zeroing.index_difference),
+ left_elevator_pot_encoder_(
+ constants::GetValues().fridge.left_elev_zeroing.index_difference),
+ right_elevator_pot_encoder_(
+ constants::GetValues().fridge.right_elev_zeroing.index_difference),
+ fridge_queue_(".frc971.control_loops.fridge_queue", 0xe4e05855,
+ ".frc971.control_loops.fridge_queue.goal",
+ ".frc971.control_loops.fridge_queue.position",
+ ".frc971.control_loops.fridge_queue.output",
+ ".frc971.control_loops.fridge_queue.status") {
+ // Initialize the elevator.
+ InitializeElevatorPosition(
+ constants::GetValues().fridge.elevator.lower_limit);
+ // Initialize the arm.
+ InitializeArmPosition(0.0);
+ }
+
+ void InitializeElevatorPosition(double start_pos) {
+ InitializeElevatorPosition(start_pos, start_pos);
+ }
+
+ void InitializeElevatorPosition(double left_start_pos,
+ double right_start_pos) {
+ InitializeElevatorPosition(
+ left_start_pos, right_start_pos,
+ kNoiseScalar *
+ constants::GetValues().fridge.right_elev_zeroing.index_difference);
+ }
+
+ void InitializeElevatorPosition(double left_start_pos, double right_start_pos,
+ double pot_noise_stddev) {
+ // Update the internal state of the elevator plant.
+ elevator_plant_->mutable_X(0, 0) = (left_start_pos + right_start_pos) / 2.0;
+ elevator_plant_->mutable_X(1, 0) = 0.0;
+ elevator_plant_->mutable_X(2, 0) = (left_start_pos - right_start_pos) / 2.0;
+ elevator_plant_->mutable_X(3, 0) = 0.0;
+
+ right_elevator_pot_encoder_.Initialize(right_start_pos, pot_noise_stddev);
+ left_elevator_pot_encoder_.Initialize(left_start_pos, pot_noise_stddev);
+ elevator_initial_difference_ = left_start_pos - right_start_pos;
+ }
+
+ void InitializeArmPosition(double start_pos) {
+ InitializeArmPosition(start_pos, start_pos);
+ }
+
+ void InitializeArmPosition(double left_start_pos, double right_start_pos) {
+ InitializeArmPosition(
+ left_start_pos, right_start_pos,
+ kNoiseScalar *
+ constants::GetValues().fridge.right_arm_zeroing.index_difference);
+ }
+ void InitializeArmPosition(double left_start_pos, double right_start_pos,
+ double pot_noise_stddev) {
+ // Update the internal state of the arm plant.
+ arm_plant_->mutable_X(0, 0) = (left_start_pos + right_start_pos) / 2.0;
+ arm_plant_->mutable_X(1, 0) = 0.0;
+ arm_plant_->mutable_X(2, 0) = (left_start_pos - right_start_pos) / 2.0;
+ arm_plant_->mutable_X(3, 0) = 0.0;
+
+ left_arm_pot_encoder_.Initialize(left_start_pos, pot_noise_stddev);
+ right_arm_pot_encoder_.Initialize(right_start_pos, pot_noise_stddev);
+ arm_initial_difference_ = left_start_pos - right_start_pos;
+ }
+
+ // Changes the left-right calculations in the limit checks to measure absolute
+ // differences instead of differences relative to the starting offset.
+ void ErrorOnAbsoluteDifference() {
+ arm_initial_difference_ = 0.0;
+ elevator_initial_difference_ = 0.0;
+ }
+
+ // Sends a queue message with the position.
+ void SendPositionMessage() {
+ ::aos::ScopedMessagePtr<control_loops::FridgeQueue::Position> position =
+ fridge_queue_.position.MakeMessage();
+
+ left_arm_pot_encoder_.GetSensorValues(&position->arm.left);
+ right_arm_pot_encoder_.GetSensorValues(&position->arm.right);
+ left_elevator_pot_encoder_.GetSensorValues(&position->elevator.left);
+ right_elevator_pot_encoder_.GetSensorValues(&position->elevator.right);
+
+ position.Send();
+ }
+
+ // Sets the difference between the commanded and applied power for the arm.
+ // This lets us test that the integrator for the arm works.
+ void set_arm_power_error(double arm_power_error) {
+ arm_power_error_ = arm_power_error;
+ }
+ // Simulates for a single timestep.
+ void Simulate() {
+ EXPECT_TRUE(fridge_queue_.output.FetchLatest());
+
+ // Feed voltages into physics simulation.
+ if (arm_power_error_ != 0.0) {
+ arm_plant_->mutable_U() << ::aos::Clip(
+ fridge_queue_.output->left_arm + arm_power_error_, -12, 12),
+ ::aos::Clip(fridge_queue_.output->right_arm + arm_power_error_, -12,
+ 12);
+ } else {
+ arm_plant_->mutable_U() << fridge_queue_.output->left_arm,
+ fridge_queue_.output->right_arm;
+ }
+ elevator_plant_->mutable_U() << fridge_queue_.output->left_elevator,
+ fridge_queue_.output->right_elevator;
+
+ // Use the plant to generate the next physical state given the voltages to
+ // the motors.
+ arm_plant_->Update();
+ elevator_plant_->Update();
+
+ const double left_arm_angle = arm_plant_->Y(0, 0);
+ const double right_arm_angle = arm_plant_->Y(1, 0);
+ const double left_elevator_height = elevator_plant_->Y(0, 0);
+ const double right_elevator_height = elevator_plant_->Y(1, 0);
+
+ // TODO (phil) Do some sanity tests on the arm angles and the elevator
+ // heights. For example, we need to make sure that both sides are within a
+ // certain distance of each other and they haven't crashed into the top or
+ // the bottom.
+
+ // Use the physical state to simulate sensor readings.
+ left_arm_pot_encoder_.MoveTo(left_arm_angle);
+ right_arm_pot_encoder_.MoveTo(right_arm_angle);
+ left_elevator_pot_encoder_.MoveTo(left_elevator_height);
+ right_elevator_pot_encoder_.MoveTo(right_elevator_height);
+
+ // Verify that the arm and elevator sides don't change much from their
+ // initial difference. Use the initial difference instead of the absolute
+ // difference to handle starting too far apart to test e-stopping.
+ EXPECT_NEAR(left_arm_angle - right_arm_angle, arm_initial_difference_,
+ 5.0 * M_PI / 180.0);
+ EXPECT_NEAR(left_elevator_height - right_elevator_height,
+ elevator_initial_difference_, 0.0254);
+
+ // Validate that the arm is within range.
+ EXPECT_GE(left_arm_angle,
+ constants::GetValues().fridge.arm.lower_hard_limit);
+ EXPECT_GE(right_arm_angle,
+ constants::GetValues().fridge.arm.lower_hard_limit);
+ EXPECT_LE(left_arm_angle,
+ constants::GetValues().fridge.arm.upper_hard_limit);
+ EXPECT_LE(right_arm_angle,
+ constants::GetValues().fridge.arm.upper_hard_limit);
+
+ // Validate that the elevator is within range.
+ EXPECT_GE(left_elevator_height,
+ constants::GetValues().fridge.elevator.lower_hard_limit);
+ EXPECT_GE(right_elevator_height,
+ constants::GetValues().fridge.elevator.lower_hard_limit);
+ EXPECT_LE(left_elevator_height,
+ constants::GetValues().fridge.elevator.upper_hard_limit);
+ EXPECT_LE(right_elevator_height,
+ constants::GetValues().fridge.elevator.upper_hard_limit);
+ }
+
+ private:
+ ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> arm_plant_;
+ ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> elevator_plant_;
+
+ PositionSensorSimulator left_arm_pot_encoder_;
+ PositionSensorSimulator right_arm_pot_encoder_;
+ PositionSensorSimulator left_elevator_pot_encoder_;
+ PositionSensorSimulator right_elevator_pot_encoder_;
+
+ FridgeQueue fridge_queue_;
+
+ double elevator_initial_difference_ = 0.0;
+ double arm_initial_difference_ = 0.0;
+ double arm_power_error_ = 0.0;
+};
+
+class FridgeTest : public ::aos::testing::ControlLoopTest {
+ protected:
+ FridgeTest()
+ : fridge_queue_(".frc971.control_loops.fridge_queue", 0xe4e05855,
+ ".frc971.control_loops.fridge_queue.goal",
+ ".frc971.control_loops.fridge_queue.position",
+ ".frc971.control_loops.fridge_queue.output",
+ ".frc971.control_loops.fridge_queue.status"),
+ fridge_(&fridge_queue_),
+ fridge_plant_(),
+ kinematics_(constants::GetValues().fridge.arm_length,
+ constants::GetValues().fridge.elevator.upper_limit,
+ constants::GetValues().fridge.elevator.lower_limit,
+ constants::GetValues().fridge.arm.upper_limit,
+ constants::GetValues().fridge.arm.lower_limit) {
+ set_team_id(kTeamNumber);
+ }
+
+ void VerifyNearGoal() {
+ fridge_queue_.goal.FetchLatest();
+ fridge_queue_.status.FetchLatest();
+ EXPECT_TRUE(fridge_queue_.goal.get() != nullptr);
+ EXPECT_TRUE(fridge_queue_.status.get() != nullptr);
+ if (fridge_queue_.goal->profiling_type == 0) {
+ EXPECT_NEAR(fridge_queue_.goal->angle, fridge_queue_.status->angle,
+ 0.001);
+ EXPECT_NEAR(fridge_queue_.goal->height, fridge_queue_.status->height,
+ 0.001);
+ } else if (fridge_queue_.goal->profiling_type == 1) {
+ aos::util::ElevatorArmKinematics::KinematicResult x_y_status;
+ kinematics_.ForwardKinematic(fridge_queue_.status->height,
+ fridge_queue_.status->angle, 0.0, 0.0, &x_y_status);
+ EXPECT_NEAR(fridge_queue_.goal->x, x_y_status.fridge_x, 0.001);
+ EXPECT_NEAR(fridge_queue_.goal->y, x_y_status.fridge_h, 0.001);
+ } else {
+ // Unhandled profiling type.
+ EXPECT_TRUE(false);
+ }
+ }
+
+ // Runs one iteration of the whole simulation and checks that separation
+ // remains reasonable.
+ void RunIteration(bool enabled = true) {
+ SendMessages(enabled);
+
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_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) {
+ RunIteration(enabled);
+ }
+ }
+
+ // 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.
+ FridgeQueue fridge_queue_;
+
+ // Create a control loop and simulation.
+ Fridge fridge_;
+ FridgeSimulation fridge_plant_;
+
+ aos::util::ElevatorArmKinematics kinematics_;
+};
+
+// Tests that the loop does nothing when the goal is zero.
+TEST_F(FridgeTest, DoesNothing) {
+ // Set the goals to the starting values. This should theoretically guarantee
+ // that the controller does nothing.
+ const auto &values = constants::GetValues();
+ ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
+ .angle(0.0)
+ .height(values.fridge.elevator.lower_limit)
+ .max_velocity(20)
+ .max_acceleration(20)
+ .max_angular_velocity(20)
+ .max_angular_acceleration(20)
+ .Send());
+
+ // Run a few iterations.
+ RunForTime(Time::InSeconds(5));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop can reach a goal.
+TEST_F(FridgeTest, ReachesXYGoal) {
+ // Set a reasonable goal.
+ const auto &values = constants::GetValues();
+ const double soft_limit = values.fridge.elevator.lower_limit;
+ const double height = soft_limit + 0.4;
+ const double angle = M_PI / 6.0;
+
+ aos::util::ElevatorArmKinematics::KinematicResult x_y_goals;
+ kinematics_.ForwardKinematic(height, angle, 0.0, 0.0, &x_y_goals);
+
+ ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
+ .profiling_type(1)
+ .x(x_y_goals.fridge_x)
+ .y(x_y_goals.fridge_h)
+ .max_x_velocity(20)
+ .max_y_velocity(20)
+ .max_x_acceleration(20)
+ .max_y_acceleration(20)
+ .Send());
+
+ // Give it a lot of time to get there.
+ RunForTime(Time::InSeconds(5));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop can reach a goal.
+TEST_F(FridgeTest, ReachesGoal) {
+ // Set a reasonable goal.
+ const auto &values = constants::GetValues();
+ const double soft_limit = values.fridge.elevator.lower_limit;
+ ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
+ .angle(M_PI / 4.0)
+ .height(soft_limit + 0.5)
+ .max_velocity(20)
+ .max_acceleration(20)
+ .max_angular_velocity(20)
+ .max_angular_acceleration(20)
+ .Send());
+
+ // Give it a lot of time to get there.
+ RunForTime(Time::InSeconds(5));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop doesn't try and go beyond the physical range of the
+// mechanisms.
+TEST_F(FridgeTest, RespectsRange) {
+ // Put the arm up to get it out of the way.
+ // We're going to send the elevator to -5, which should be significantly too
+ // low.
+ ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
+ .angle(M_PI)
+ .height(-5.0)
+ .max_velocity(20)
+ .max_acceleration(20)
+ .max_angular_velocity(20)
+ .max_angular_acceleration(20)
+ .Send());
+
+ RunForTime(Time::InSeconds(10));
+
+ // Check that we are near our soft limit.
+ fridge_queue_.status.FetchLatest();
+ const auto &values = constants::GetValues();
+ EXPECT_NEAR(values.fridge.elevator.lower_limit, fridge_queue_.status->height,
+ 0.001);
+ EXPECT_NEAR(values.fridge.arm.upper_limit, fridge_queue_.status->angle,
+ 0.001);
+
+ // Put the arm down to get it out of the way.
+ // We're going to give the elevator some ridiculously high goal.
+ ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
+ .angle(-M_PI)
+ .height(50.0)
+ .max_velocity(20)
+ .max_acceleration(20)
+ .max_angular_velocity(20)
+ .max_angular_acceleration(20)
+ .Send());
+
+ RunForTime(Time::InSeconds(10));
+
+ // Check that we are near our soft limit.
+ fridge_queue_.status.FetchLatest();
+ EXPECT_NEAR(values.fridge.elevator.upper_limit, fridge_queue_.status->height,
+ 0.001);
+ EXPECT_NEAR(values.fridge.arm.lower_limit, fridge_queue_.status->angle,
+ 0.001);
+}
+
+// Tests that the loop zeroes when run for a while.
+TEST_F(FridgeTest, ZeroTest) {
+ fridge_queue_.goal.MakeWithBuilder()
+ .angle(0.0)
+ .height(0.5)
+ .max_velocity(20)
+ .max_acceleration(20)
+ .max_angular_velocity(20)
+ .max_angular_acceleration(20)
+ .Send();
+ RunForTime(Time::InSeconds(5));
+
+ VerifyNearGoal();
+}
+
+// Tests that starting at the lower hardstops doesn't cause an abort.
+TEST_F(FridgeTest, LowerHardstopStartup) {
+ fridge_plant_.InitializeElevatorPosition(
+ constants::GetValues().fridge.elevator.lower_hard_limit,
+ constants::GetValues().fridge.elevator.lower_hard_limit);
+ fridge_plant_.InitializeArmPosition(
+ constants::GetValues().fridge.arm.lower_hard_limit,
+ constants::GetValues().fridge.arm.lower_hard_limit);
+ fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
+ // We have to wait for it to put the elevator in a safe position as well.
+ RunForTime(Time::InMS(8000));
+
+ VerifyNearGoal();
+}
+
+// Tests that starting at the upper hardstops doesn't cause an abort.
+TEST_F(FridgeTest, UpperHardstopStartup) {
+ fridge_plant_.InitializeElevatorPosition(
+ constants::GetValues().fridge.elevator.upper_hard_limit,
+ constants::GetValues().fridge.elevator.upper_hard_limit);
+ fridge_plant_.InitializeArmPosition(
+ constants::GetValues().fridge.arm.upper_hard_limit,
+ constants::GetValues().fridge.arm.upper_hard_limit);
+ fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
+ RunForTime(Time::InMS(5000));
+
+ VerifyNearGoal();
+}
+
+// Tests that starting with an initial arm difference triggers an ESTOP.
+TEST_F(FridgeTest, ArmFarApartEstop) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
+
+ do {
+ fridge_plant_.InitializeArmPosition(
+ constants::GetValues().fridge.arm.lower_limit,
+ constants::GetValues().fridge.arm.lower_limit + 0.2);
+ SendMessages(true);
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_plant_.Simulate();
+ TickTime();
+ } while (fridge_.state() == Fridge::INITIALIZING);
+
+ EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
+
+ // TODO(austin): We should estop earlier once Phil's code to detect issues
+ // before the index pulse is merged.
+ while (fridge_.state() != Fridge::RUNNING &&
+ fridge_.state() != Fridge::ESTOP) {
+ SendMessages(true);
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_plant_.Simulate();
+ TickTime();
+ }
+
+ EXPECT_EQ(Fridge::ESTOP, fridge_.state());
+}
+
+// Tests that starting with an initial elevator difference triggers an ESTOP.
+TEST_F(FridgeTest, ElevatorFarApartEstop) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
+
+ do {
+ fridge_plant_.InitializeElevatorPosition(
+ constants::GetValues().fridge.elevator.lower_limit,
+ constants::GetValues().fridge.elevator.lower_limit + 0.1);
+ SendMessages(true);
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_plant_.Simulate();
+ TickTime();
+ } while (fridge_.state() == Fridge::INITIALIZING);
+
+ EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
+
+ // TODO(austin): We should estop earlier once Phil's code to detect issues
+ // before the index pulse is merged.
+ while (fridge_.state() != Fridge::RUNNING &&
+ fridge_.state() != Fridge::ESTOP) {
+ SendMessages(true);
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_plant_.Simulate();
+ TickTime();
+ }
+
+ EXPECT_EQ(Fridge::ESTOP, fridge_.state());
+}
+
+// Tests that starting with an initial elevator difference converges back to 0
+// error when zeroed.
+TEST_F(FridgeTest, ElevatorFixError) {
+ fridge_queue_.goal.MakeWithBuilder()
+ .angle(0.0)
+ .height(0.2)
+ .max_velocity(20)
+ .max_acceleration(20)
+ .Send();
+
+ do {
+ fridge_plant_.InitializeElevatorPosition(
+ constants::GetValues().fridge.elevator.lower_limit,
+ constants::GetValues().fridge.elevator.lower_limit + 0.01);
+ fridge_plant_.ErrorOnAbsoluteDifference();
+ SendMessages(true);
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_plant_.Simulate();
+ TickTime();
+ } while (fridge_.state() == Fridge::INITIALIZING);
+
+ EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
+
+ RunForTime(Time::InSeconds(5));
+ VerifyNearGoal();
+}
+
+// Tests that starting with an initial arm difference converges back to 0
+// error when zeroed.
+TEST_F(FridgeTest, ArmFixError) {
+ fridge_queue_.goal.MakeWithBuilder()
+ .angle(0.0)
+ .height(0.2)
+ .max_angular_velocity(20)
+ .max_angular_acceleration(20)
+ .Send();
+
+ do {
+ fridge_plant_.InitializeArmPosition(0.0, 0.02);
+ fridge_plant_.ErrorOnAbsoluteDifference();
+ SendMessages(true);
+ fridge_plant_.SendPositionMessage();
+ fridge_.Iterate();
+ fridge_plant_.Simulate();
+ TickTime();
+ } while (fridge_.state() == Fridge::INITIALIZING);
+
+ EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
+
+ RunForTime(Time::InSeconds(5));
+ VerifyNearGoal();
+}
+
+// Tests that resetting WPILib results in a rezero.
+TEST_F(FridgeTest, ResetTest) {
+ fridge_plant_.InitializeElevatorPosition(
+ constants::GetValues().fridge.elevator.upper_hard_limit,
+ constants::GetValues().fridge.elevator.upper_hard_limit);
+ fridge_plant_.InitializeArmPosition(
+ constants::GetValues().fridge.arm.upper_hard_limit,
+ constants::GetValues().fridge.arm.upper_hard_limit);
+ fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
+ RunForTime(Time::InMS(5000));
+
+ EXPECT_EQ(Fridge::RUNNING, fridge_.state());
+ VerifyNearGoal();
+ SimulateSensorReset();
+ RunForTime(Time::InMS(100));
+ EXPECT_NE(Fridge::RUNNING, fridge_.state());
+ RunForTime(Time::InMS(6000));
+ EXPECT_EQ(Fridge::RUNNING, fridge_.state());
+ VerifyNearGoal();
+}
+
+// Tests that the internal goals don't change while disabled.
+TEST_F(FridgeTest, DisabledGoalTest) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
+
+ RunForTime(Time::InMS(100), false);
+ EXPECT_EQ(0.0, fridge_.elevator_goal_);
+ EXPECT_EQ(0.0, fridge_.arm_goal_);
+
+ // Now make sure they move correctly
+ RunForTime(Time::InMS(4000), true);
+ EXPECT_NE(0.0, fridge_.elevator_goal_);
+ EXPECT_NE(0.0, fridge_.arm_goal_);
+}
+
+// Tests that the elevator zeroing goals don't wind up too far.
+TEST_F(FridgeTest, ElevatorGoalPositiveWindupTest) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
+
+ while (fridge_.state() != Fridge::ZEROING_ELEVATOR) {
+ RunIteration();
+ }
+
+ // Kick it.
+ RunForTime(Time::InMS(50));
+ double orig_fridge_goal = fridge_.elevator_goal_;
+ fridge_.elevator_goal_ += 100.0;
+
+ RunIteration();
+ EXPECT_NEAR(orig_fridge_goal, fridge_.elevator_goal_, 0.05);
+
+ RunIteration();
+
+ EXPECT_EQ(fridge_.elevator_loop_->U(), fridge_.elevator_loop_->U_uncapped());
+}
+
+// Tests that the arm zeroing goals don't wind up too far.
+TEST_F(FridgeTest, ArmGoalPositiveWindupTest) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
+
+ int i = 0;
+ while (fridge_.state() != Fridge::ZEROING_ARM) {
+ RunIteration();
+ ++i;
+ ASSERT_LE(i, 10000);
+ }
+
+ // Kick it.
+ RunForTime(Time::InMS(50));
+ double orig_fridge_goal = fridge_.arm_goal_;
+ fridge_.arm_goal_ += 100.0;
+
+ RunIteration();
+ EXPECT_NEAR(orig_fridge_goal, fridge_.arm_goal_, 0.05);
+
+ RunIteration();
+
+ EXPECT_EQ(fridge_.arm_loop_->U(), fridge_.arm_loop_->U_uncapped());
+}
+
+// Tests that the elevator zeroing goals don't wind up too far.
+TEST_F(FridgeTest, ElevatorGoalNegativeWindupTest) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
+
+ while (fridge_.state() != Fridge::ZEROING_ELEVATOR) {
+ RunIteration();
+ }
+
+ // Kick it.
+ RunForTime(Time::InMS(50));
+ double orig_fridge_goal = fridge_.elevator_goal_;
+ fridge_.elevator_goal_ -= 100.0;
+
+ RunIteration();
+ EXPECT_NEAR(orig_fridge_goal, fridge_.elevator_goal_, 0.05);
+
+ RunIteration();
+
+ EXPECT_EQ(fridge_.elevator_loop_->U(), fridge_.elevator_loop_->U_uncapped());
+}
+
+// Tests that the arm zeroing goals don't wind up too far.
+TEST_F(FridgeTest, ArmGoalNegativeWindupTest) {
+ fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
+
+ while (fridge_.state() != Fridge::ZEROING_ARM) {
+ RunIteration();
+ }
+
+ // Kick it.
+ RunForTime(Time::InMS(50));
+ double orig_fridge_goal = fridge_.arm_goal_;
+ fridge_.arm_goal_ -= 100.0;
+
+ RunIteration();
+ EXPECT_NEAR(orig_fridge_goal, fridge_.arm_goal_, 0.05);
+
+ RunIteration();
+
+ EXPECT_EQ(fridge_.arm_loop_->U(), fridge_.arm_loop_->U_uncapped());
+}
+
+// Tests that the loop zeroes when run for a while.
+TEST_F(FridgeTest, ZeroNoGoal) {
+ RunForTime(Time::InSeconds(5));
+
+ EXPECT_EQ(Fridge::RUNNING, fridge_.state());
+}
+
+// Tests that if we start at the bottom, the elevator moves to a safe height
+// before zeroing the arm.
+TEST_F(FridgeTest, SafeArmZeroing) {
+ auto &values = constants::GetValues();
+ fridge_plant_.InitializeElevatorPosition(
+ values.fridge.elevator.lower_hard_limit);
+ fridge_plant_.InitializeArmPosition(M_PI / 4.0);
+
+ const auto start_time = Time::Now();
+ double last_arm_goal = fridge_.arm_goal_;
+ while (Time::Now() < start_time + Time::InMS(4000)) {
+ RunIteration();
+
+ if (fridge_.state() != Fridge::ZEROING_ELEVATOR) {
+ // Wait until we are zeroing the elevator.
+ continue;
+ }
+
+ fridge_queue_.status.FetchLatest();
+ ASSERT_TRUE(fridge_queue_.status.get() != nullptr);
+ if (fridge_queue_.status->height > values.fridge.arm_zeroing_height) {
+ // We had better not be trying to zero the arm...
+ EXPECT_EQ(last_arm_goal, fridge_.arm_goal_);
+ last_arm_goal = fridge_.arm_goal_;
+ }
+ }
+}
+
+// Tests that the arm integrator works.
+TEST_F(FridgeTest, ArmIntegratorTest) {
+ fridge_plant_.InitializeArmPosition(
+ (constants::GetValues().fridge.arm.lower_hard_limit +
+ constants::GetValues().fridge.arm.lower_hard_limit) /
+ 2.0);
+ fridge_plant_.set_arm_power_error(1.0);
+ fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
+
+ RunForTime(Time::InMS(8000));
+
+ VerifyNearGoal();
+}
+
+// Phil:
+// TODO(austin): Check that we e-stop if encoder index pulse is not n
+// revolutions away from last one. (got extra counts from noise, etc).
+// TODO(austin): Check that we e-stop if pot disagrees too much with encoder
+// after we are zeroed.
+
+} // namespace testing
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/fridge/fridge_main.cc b/y2015/control_loops/fridge/fridge_main.cc
new file mode 100644
index 0000000..e0fd6ea
--- /dev/null
+++ b/y2015/control_loops/fridge/fridge_main.cc
@@ -0,0 +1,11 @@
+#include "y2015/control_loops/fridge/fridge.h"
+
+#include "aos/linux_code/init.h"
+
+int main() {
+ ::aos::Init();
+ frc971::control_loops::Fridge fridge;
+ fridge.Run();
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2015/control_loops/fridge/integral_arm_plant.cc b/y2015/control_loops/fridge/integral_arm_plant.cc
new file mode 100644
index 0000000..da269d7
--- /dev/null
+++ b/y2015/control_loops/fridge/integral_arm_plant.cc
@@ -0,0 +1,49 @@
+#include "y2015/control_loops/fridge/integral_arm_plant.h"
+
+#include <vector>
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<5, 2, 2> MakeIntegralArmPlantCoefficients() {
+ Eigen::Matrix<double, 5, 5> A;
+ A << 1.0, 0.00479642025454, 0.0, 0.0, 4.92993559969e-05, 0.0, 0.919688585028, 0.0, 0.0, 0.0194484035162, 0.0, 0.0, 0.999539771613, 0.00479566382645, 0.0, 0.0, 0.0, -0.18154390621, 0.919241022297, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0;
+ Eigen::Matrix<double, 5, 2> B;
+ B << 2.46496779984e-05, 2.46496779984e-05, 0.00972420175808, 0.00972420175808, 2.46477449538e-05, -2.46477449538e-05, 0.00972266818532, -0.00972266818532, 0.0, 0.0;
+ Eigen::Matrix<double, 2, 5> C;
+ C << 1.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, -1.0, 0.0, 0.0;
+ Eigen::Matrix<double, 2, 2> D;
+ D << 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<5, 2, 2>(A, B, C, D, U_max, U_min);
+}
+
+StateFeedbackController<5, 2, 2> MakeIntegralArmController() {
+ Eigen::Matrix<double, 5, 2> L;
+ L << 0.461805946837, 0.461805946837, 5.83483983392, 5.83483983392, 0.429725467802, -0.429725467802, 0.18044816586, -0.18044816586, 31.0623964848, 31.0623964848;
+ Eigen::Matrix<double, 2, 5> K;
+ K << 320.979606093, 21.0129517955, 884.233784759, 36.3637782119, 1.0, 320.979606095, 21.0129517956, -884.233784749, -36.3637782119, 1.0;
+ Eigen::Matrix<double, 5, 5> A_inv;
+ A_inv << 1.0, -0.00521526561559, 0.0, 0.0, 5.21292341391e-05, 0.0, 1.08732457517, 0.0, 0.0, -0.0211467270909, 0.0, 0.0, 0.999513354044, -0.00521444313273, 0.0, 0.0, 0.0, 0.197397150694, 1.08682415753, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0;
+ return StateFeedbackController<5, 2, 2>(L, K, A_inv, MakeIntegralArmPlantCoefficients());
+}
+
+StateFeedbackPlant<5, 2, 2> MakeIntegralArmPlant() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<5, 2, 2>>> plants(1);
+ plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<5, 2, 2>>(new StateFeedbackPlantCoefficients<5, 2, 2>(MakeIntegralArmPlantCoefficients()));
+ return StateFeedbackPlant<5, 2, 2>(&plants);
+}
+
+StateFeedbackLoop<5, 2, 2> MakeIntegralArmLoop() {
+ ::std::vector< ::std::unique_ptr<StateFeedbackController<5, 2, 2>>> controllers(1);
+ controllers[0] = ::std::unique_ptr<StateFeedbackController<5, 2, 2>>(new StateFeedbackController<5, 2, 2>(MakeIntegralArmController()));
+ return StateFeedbackLoop<5, 2, 2>(&controllers);
+}
+
+} // namespace control_loops
+} // namespace frc971
diff --git a/y2015/control_loops/fridge/integral_arm_plant.h b/y2015/control_loops/fridge/integral_arm_plant.h
new file mode 100644
index 0000000..80a4876
--- /dev/null
+++ b/y2015/control_loops/fridge/integral_arm_plant.h
@@ -0,0 +1,20 @@
+#ifndef Y2015_CONTROL_LOOPS_FRIDGE_INTEGRAL_ARM_PLANT_H_
+#define Y2015_CONTROL_LOOPS_FRIDGE_INTEGRAL_ARM_PLANT_H_
+
+#include "frc971/control_loops/state_feedback_loop.h"
+
+namespace frc971 {
+namespace control_loops {
+
+StateFeedbackPlantCoefficients<5, 2, 2> MakeIntegralArmPlantCoefficients();
+
+StateFeedbackController<5, 2, 2> MakeIntegralArmController();
+
+StateFeedbackPlant<5, 2, 2> MakeIntegralArmPlant();
+
+StateFeedbackLoop<5, 2, 2> MakeIntegralArmLoop();
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // Y2015_CONTROL_LOOPS_FRIDGE_INTEGRAL_ARM_PLANT_H_
diff --git a/y2015/control_loops/fridge/replay_fridge.cc b/y2015/control_loops/fridge/replay_fridge.cc
new file mode 100644
index 0000000..65cc98a
--- /dev/null
+++ b/y2015/control_loops/fridge/replay_fridge.cc
@@ -0,0 +1,24 @@
+#include "aos/common/controls/replay_control_loop.h"
+#include "aos/linux_code/init.h"
+
+#include "y2015/control_loops/fridge/fridge.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" fridge 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<::frc971::control_loops::FridgeQueue>
+ replayer(&::frc971::control_loops::fridge_queue, "fridge");
+ for (int i = 1; i < argc; ++i) {
+ replayer.ProcessFile(argv[i]);
+ }
+
+ ::aos::Cleanup();
+}
diff --git a/y2015/control_loops/python/arm.py b/y2015/control_loops/python/arm.py
new file mode 100755
index 0000000..e17990a
--- /dev/null
+++ b/y2015/control_loops/python/arm.py
@@ -0,0 +1,409 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import polytope
+import polydrivetrain
+import numpy
+import math
+import sys
+import matplotlib
+from matplotlib import pylab
+
+
+class Arm(control_loop.ControlLoop):
+ def __init__(self, name="Arm", mass=None):
+ super(Arm, self).__init__(name)
+ # Stall Torque in N m
+ self.stall_torque = 0.476
+ # Stall Current in Amps
+ self.stall_current = 80.730
+ # Free Speed in RPM
+ self.free_speed = 13906.0
+ # Free Current in Amps
+ self.free_current = 5.820
+ # Mass of the arm
+ if mass is None:
+ self.mass = 13.0
+ else:
+ self.mass = mass
+
+ # 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 = (44.0 / 12.0) * (54.0 / 14.0) * (54.0 / 14.0) * (44.0 / 20.0) * (72.0 / 16.0)
+ # Fridge arm length
+ self.r = 32 * 0.0254
+ # Control loop time step
+ self.dt = 0.005
+
+ # Arm moment of inertia
+ self.J = self.r * self.mass
+
+ # Arm left/right spring constant (N*m / radian)
+ self.spring = 100.0
+
+ # State is [average position, average velocity,
+ # position difference/2, velocity difference/2]
+ # Position difference is 1 - 2
+ # Input is [Voltage 1, Voltage 2]
+
+ self.C1 = self.spring / (self.J * 0.5)
+ self.C2 = self.Kt * self.G / (self.J * 0.5 * self.R)
+ self.C3 = self.G * self.G * self.Kt / (self.R * self.J * 0.5 * self.Kv)
+
+ self.A_continuous = numpy.matrix(
+ [[0, 1, 0, 0],
+ [0, -self.C3, 0, 0],
+ [0, 0, 0, 1],
+ [0, 0, -self.C1 * 2.0, -self.C3]])
+
+ print 'Full speed is', self.C2 / self.C3 * 12.0
+
+ print 'Stall arm difference is', 12.0 * self.C2 / self.C1
+ print 'Stall arm difference first principles is', self.stall_torque * self.G / self.spring
+
+ print '5 degrees of arm error is', self.spring / self.r * (math.pi * 5.0 / 180.0)
+
+ # Start with the unmodified input
+ self.B_continuous = numpy.matrix(
+ [[0, 0],
+ [self.C2 / 2.0, self.C2 / 2.0],
+ [0, 0],
+ [self.C2 / 2.0, -self.C2 / 2.0]])
+
+ self.C = numpy.matrix([[1, 0, 1, 0],
+ [1, 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)
+
+ controlability = controls.ctrb(self.A, self.B);
+ print 'Rank of augmented controlability matrix.', numpy.linalg.matrix_rank(
+ controlability)
+
+ q_pos = 0.02
+ q_vel = 0.300
+ q_pos_diff = 0.005
+ q_vel_diff = 0.13
+ 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_diff ** 2.0)), 0.0],
+ [0.0, 0.0, 0.0, (1.0 / (q_vel_diff ** 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)
+ print 'Controller'
+ print self.K
+
+ print 'Controller Poles'
+ print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+ self.rpl = 0.20
+ self.ipl = 0.05
+ self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+ self.rpl + 1j * self.ipl,
+ self.rpl - 1j * self.ipl,
+ self.rpl - 1j * self.ipl])
+
+ # 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], [12.0]])
+ self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+ print 'Observer (Converted to a KF)', numpy.linalg.inv(self.A) * self.L
+
+ self.InitializeState()
+
+
+class IntegralArm(Arm):
+ def __init__(self, name="IntegralArm", mass=None):
+ super(IntegralArm, self).__init__(name=name, mass=mass)
+
+ self.A_continuous_unaugmented = self.A_continuous
+ self.A_continuous = numpy.matrix(numpy.zeros((5, 5)))
+ self.A_continuous[0:4, 0:4] = self.A_continuous_unaugmented
+ self.A_continuous[1, 4] = self.C2
+
+ # Start with the unmodified input
+ self.B_continuous_unaugmented = self.B_continuous
+ self.B_continuous = numpy.matrix(numpy.zeros((5, 2)))
+ self.B_continuous[0:4, 0:2] = self.B_continuous_unaugmented
+
+ self.C_unaugmented = self.C
+ self.C = numpy.matrix(numpy.zeros((2, 5)))
+ self.C[0:2, 0:4] = self.C_unaugmented
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+ print 'A cont', self.A_continuous
+ print 'B cont', self.B_continuous
+ print 'A discrete', self.A
+
+ q_pos = 0.08
+ q_vel = 0.40
+
+ q_pos_diff = 0.08
+ q_vel_diff = 0.40
+ q_voltage = 6.0
+ self.Q = numpy.matrix([[(q_pos ** 2.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, (q_pos_diff ** 2.0), 0.0, 0.0],
+ [0.0, 0.0, 0.0, (q_vel_diff ** 2.0), 0.0],
+ [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0)]])
+
+ r_volts = 0.05
+ self.R = numpy.matrix([[(r_volts ** 2.0), 0.0],
+ [0.0, (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)
+
+ self.U_max = numpy.matrix([[12.0], [12.0]])
+ self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+ self.K_unaugmented = self.K
+ self.K = numpy.matrix(numpy.zeros((2, 5)));
+ self.K[0:2, 0:4] = self.K_unaugmented
+ self.K[0, 4] = 1;
+ self.K[1, 4] = 1;
+ print 'Kal', self.KalmanGain
+ self.L = self.A * self.KalmanGain
+
+ self.InitializeState()
+
+
+def CapU(U):
+ if U[0, 0] - U[1, 0] > 24:
+ return numpy.matrix([[12], [-12]])
+ elif U[0, 0] - U[1, 0] < -24:
+ return numpy.matrix([[-12], [12]])
+ else:
+ max_u = max(U[0, 0], U[1, 0])
+ min_u = min(U[0, 0], U[1, 0])
+ if max_u > 12:
+ return U - (max_u - 12)
+ if min_u < -12:
+ return U - (min_u + 12)
+ return U
+
+
+def run_test(arm, initial_X, goal, max_separation_error=0.01,
+ show_graph=True, iterations=200, controller_arm=None,
+ observer_arm=None):
+ """Runs the arm plant with an initial condition and goal.
+
+ The tests themselves are not terribly sophisticated; I just test for
+ whether the goal has been reached and whether the separation goes
+ outside of the initial and goal values by more than max_separation_error.
+ Prints out something for a failure of either condition and returns
+ False if tests fail.
+ Args:
+ arm: arm object to use.
+ initial_X: starting state.
+ goal: goal state.
+ show_graph: Whether or not to display a graph showing the changing
+ states and voltages.
+ iterations: Number of timesteps to run the model for.
+ controller_arm: arm object to get K from, or None if we should
+ use arm.
+ observer_arm: arm object to use for the observer, or None if we should
+ use the actual state.
+ """
+
+ arm.X = initial_X
+
+ if controller_arm is None:
+ controller_arm = arm
+
+ if observer_arm is not None:
+ observer_arm.X_hat = initial_X + 0.01
+ observer_arm.X_hat = initial_X
+
+ # Various lists for graphing things.
+ t = []
+ x_avg = []
+ x_sep = []
+ x_hat_avg = []
+ x_hat_sep = []
+ v_avg = []
+ v_sep = []
+ u_left = []
+ u_right = []
+
+ sep_plot_gain = 100.0
+
+ for i in xrange(iterations):
+ X_hat = arm.X
+ if observer_arm is not None:
+ X_hat = observer_arm.X_hat
+ x_hat_avg.append(observer_arm.X_hat[0, 0])
+ x_hat_sep.append(observer_arm.X_hat[2, 0] * sep_plot_gain)
+ U = controller_arm.K * (goal - X_hat)
+ U = CapU(U)
+ x_avg.append(arm.X[0, 0])
+ v_avg.append(arm.X[1, 0])
+ x_sep.append(arm.X[2, 0] * sep_plot_gain)
+ v_sep.append(arm.X[3, 0])
+ if observer_arm is not None:
+ observer_arm.PredictObserver(U)
+ arm.Update(U)
+ if observer_arm is not None:
+ observer_arm.Y = arm.Y
+ observer_arm.CorrectObserver(U)
+
+ t.append(i * arm.dt)
+ u_left.append(U[0, 0])
+ u_right.append(U[1, 0])
+
+ print numpy.linalg.inv(arm.A)
+ print "delta time is ", arm.dt
+ print "Velocity at t=0 is ", x_avg[0], v_avg[0], x_sep[0], v_sep[0]
+ print "Velocity at t=1+dt is ", x_avg[1], v_avg[1], x_sep[1], v_sep[1]
+
+ if show_graph:
+ pylab.subplot(2, 1, 1)
+ pylab.plot(t, x_avg, label='x avg')
+ pylab.plot(t, x_sep, label='x sep')
+ if observer_arm is not None:
+ pylab.plot(t, x_hat_avg, label='x_hat avg')
+ pylab.plot(t, x_hat_sep, label='x_hat sep')
+ pylab.legend()
+
+ pylab.subplot(2, 1, 2)
+ pylab.plot(t, u_left, label='u left')
+ pylab.plot(t, u_right, label='u right')
+ pylab.legend()
+ pylab.show()
+
+
+def run_integral_test(arm, initial_X, goal, observer_arm, disturbance,
+ max_separation_error=0.01, show_graph=True,
+ iterations=400):
+ """Runs the integral control arm plant with an initial condition and goal.
+
+ The tests themselves are not terribly sophisticated; I just test for
+ whether the goal has been reached and whether the separation goes
+ outside of the initial and goal values by more than max_separation_error.
+ Prints out something for a failure of either condition and returns
+ False if tests fail.
+ Args:
+ arm: arm object to use.
+ initial_X: starting state.
+ goal: goal state.
+ observer_arm: arm object to use for the observer.
+ show_graph: Whether or not to display a graph showing the changing
+ states and voltages.
+ iterations: Number of timesteps to run the model for.
+ disturbance: Voltage missmatch between controller and model.
+ """
+
+ arm.X = initial_X
+
+ # Various lists for graphing things.
+ t = []
+ x_avg = []
+ x_sep = []
+ x_hat_avg = []
+ x_hat_sep = []
+ v_avg = []
+ v_sep = []
+ u_left = []
+ u_right = []
+ u_error = []
+
+ sep_plot_gain = 100.0
+
+ unaugmented_goal = goal
+ goal = numpy.matrix(numpy.zeros((5, 1)))
+ goal[0:4, 0] = unaugmented_goal
+
+ for i in xrange(iterations):
+ X_hat = observer_arm.X_hat[0:4]
+
+ x_hat_avg.append(observer_arm.X_hat[0, 0])
+ x_hat_sep.append(observer_arm.X_hat[2, 0] * sep_plot_gain)
+
+ U = observer_arm.K * (goal - observer_arm.X_hat)
+ u_error.append(observer_arm.X_hat[4,0])
+ U = CapU(U)
+ x_avg.append(arm.X[0, 0])
+ v_avg.append(arm.X[1, 0])
+ x_sep.append(arm.X[2, 0] * sep_plot_gain)
+ v_sep.append(arm.X[3, 0])
+
+ observer_arm.PredictObserver(U)
+
+ arm.Update(U + disturbance)
+ observer_arm.Y = arm.Y
+ observer_arm.CorrectObserver(U)
+
+ t.append(i * arm.dt)
+ u_left.append(U[0, 0])
+ u_right.append(U[1, 0])
+
+ print 'End is', observer_arm.X_hat[4, 0]
+
+ if show_graph:
+ pylab.subplot(2, 1, 1)
+ pylab.plot(t, x_avg, label='x avg')
+ pylab.plot(t, x_sep, label='x sep')
+ if observer_arm is not None:
+ pylab.plot(t, x_hat_avg, label='x_hat avg')
+ pylab.plot(t, x_hat_sep, label='x_hat sep')
+ pylab.legend()
+
+ pylab.subplot(2, 1, 2)
+ pylab.plot(t, u_left, label='u left')
+ pylab.plot(t, u_right, label='u right')
+ pylab.plot(t, u_error, label='u error')
+ pylab.legend()
+ pylab.show()
+
+
+def main(argv):
+ loaded_mass = 25
+ #loaded_mass = 0
+ arm = Arm(mass=13 + loaded_mass)
+ #arm_controller = Arm(mass=13 + 15)
+ #observer_arm = Arm(mass=13 + 15)
+ #observer_arm = None
+
+ integral_arm = IntegralArm(mass=13 + loaded_mass)
+ integral_arm.X_hat[0, 0] += 0.02
+ integral_arm.X_hat[2, 0] += 0.02
+ integral_arm.X_hat[4] = 0
+
+ # Test moving the arm with constant separation.
+ initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+ R = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
+ run_integral_test(arm, initial_X, R, integral_arm, disturbance=2)
+
+ # Write the generated constants out to a file.
+ if len(argv) != 5:
+ print "Expected .h file name and .cc file name for the arm and augmented arm."
+ else:
+ arm = Arm("Arm", mass=13)
+ loop_writer = control_loop.ControlLoopWriter("Arm", [arm])
+ if argv[1][-3:] == '.cc':
+ loop_writer.Write(argv[2], argv[1])
+ else:
+ loop_writer.Write(argv[1], argv[2])
+
+ integral_arm = IntegralArm("IntegralArm", mass=13)
+ loop_writer = control_loop.ControlLoopWriter("IntegralArm", [integral_arm])
+ if argv[3][-3:] == '.cc':
+ loop_writer.Write(argv[4], argv[3])
+ else:
+ loop_writer.Write(argv[3], argv[4])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2015/control_loops/python/claw.py b/y2015/control_loops/python/claw.py
new file mode 100755
index 0000000..4ca50e9
--- /dev/null
+++ b/y2015/control_loops/python/claw.py
@@ -0,0 +1,211 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import polytope
+import polydrivetrain
+import numpy
+import sys
+import matplotlib
+from matplotlib import pylab
+
+class Claw(control_loop.ControlLoop):
+ def __init__(self, name="Claw", mass=None):
+ super(Claw, self).__init__(name)
+ # Stall Torque in N m
+ self.stall_torque = 0.476
+ # Stall Current in Amps
+ self.stall_current = 80.730
+ # Free Speed in RPM
+ self.free_speed = 13906.0
+ # Free Current in Amps
+ self.free_current = 5.820
+ # Mass of the claw
+ if mass is None:
+ self.mass = 5.0
+ else:
+ self.mass = mass
+
+ # 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 / 14.0) * (72.0 / 18.0)
+ # Claw length
+ self.r = 18 * 0.0254
+
+ self.J = self.r * self.mass
+
+ # 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)
+
+ controlability = controls.ctrb(self.A, self.B);
+
+ print "Free speed is", self.free_speed * numpy.pi * 2.0 / 60.0 / self.G
+
+ q_pos = 0.15
+ q_vel = 2.5
+ 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)
+
+ print 'K', self.K
+ print 'Poles are', 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])
+
+ print 'L is', self.L
+
+ q_pos = 0.05
+ q_vel = 2.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)
+
+ print 'Kal', self.KalmanGain
+ self.L = self.A * self.KalmanGain
+ print 'KalL is', 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()
+
+
+def run_test(claw, initial_X, goal, max_separation_error=0.01,
+ show_graph=True, iterations=200, controller_claw=None,
+ observer_claw=None):
+ """Runs the claw plant with an initial condition and goal.
+
+ The tests themselves are not terribly sophisticated; I just test for
+ whether the goal has been reached and whether the separation goes
+ outside of the initial and goal values by more than max_separation_error.
+ Prints out something for a failure of either condition and returns
+ False if tests fail.
+ Args:
+ claw: claw object to use.
+ initial_X: starting state.
+ goal: goal state.
+ show_graph: Whether or not to display a graph showing the changing
+ states and voltages.
+ iterations: Number of timesteps to run the model for.
+ controller_claw: claw object to get K from, or None if we should
+ use claw.
+ observer_claw: claw object to use for the observer, or None if we should
+ use the actual state.
+ """
+
+ claw.X = initial_X
+
+ if controller_claw is None:
+ controller_claw = claw
+
+ if observer_claw is not None:
+ observer_claw.X_hat = initial_X + 0.01
+ observer_claw.X_hat = initial_X
+
+ # Various lists for graphing things.
+ t = []
+ x = []
+ v = []
+ x_hat = []
+ u = []
+
+ sep_plot_gain = 100.0
+
+ for i in xrange(iterations):
+ X_hat = claw.X
+ if observer_claw is not None:
+ X_hat = observer_claw.X_hat
+ x_hat.append(observer_claw.X_hat[0, 0])
+ U = controller_claw.K * (goal - X_hat)
+ U[0, 0] = numpy.clip(U[0, 0], -12, 12)
+ x.append(claw.X[0, 0])
+ v.append(claw.X[1, 0])
+ if observer_claw is not None:
+ observer_claw.PredictObserver(U)
+ claw.Update(U)
+ if observer_claw is not None:
+ observer_claw.Y = claw.Y
+ observer_claw.CorrectObserver(U)
+
+ t.append(i * claw.dt)
+ u.append(U[0, 0])
+
+ if show_graph:
+ pylab.subplot(2, 1, 1)
+ pylab.plot(t, x, label='x')
+ if observer_claw is not None:
+ pylab.plot(t, x_hat, label='x_hat')
+ pylab.legend()
+
+ pylab.subplot(2, 1, 2)
+ pylab.plot(t, u, label='u')
+ pylab.legend()
+ pylab.show()
+
+
+def main(argv):
+ loaded_mass = 0
+ #loaded_mass = 0
+ claw = Claw(mass=4 + loaded_mass)
+ claw_controller = Claw(mass=5 + 0)
+ observer_claw = Claw(mass=5 + 0)
+ #observer_claw = None
+
+ # Test moving the claw with constant separation.
+ initial_X = numpy.matrix([[0.0], [0.0]])
+ R = numpy.matrix([[1.0], [0.0]])
+ run_test(claw, initial_X, R, controller_claw=claw_controller,
+ observer_claw=observer_claw)
+
+ # Write the generated constants out to a file.
+ if len(argv) != 3:
+ print "Expected .h file name and .cc file name for the claw."
+ else:
+ claw = Claw("Claw")
+ loop_writer = control_loop.ControlLoopWriter("Claw", [claw])
+ if argv[1][-3:] == '.cc':
+ loop_writer.Write(argv[2], argv[1])
+ else:
+ loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2015/control_loops/python/drivetrain.py b/y2015/control_loops/python/drivetrain.py
new file mode 100755
index 0000000..8ed62d6
--- /dev/null
+++ b/y2015/control_loops/python/drivetrain.py
@@ -0,0 +1,242 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import numpy
+import sys
+from matplotlib import pylab
+
+
+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.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
+ # Control loop time step
+ self.dt = 0.005
+
+ # State feedback matrices
+ self.A_continuous = numpy.matrix(
+ [[-self.Kt / self.Kv / (self.J * self.R)]])
+ self.B_continuous = numpy.matrix(
+ [[self.Kt / (self.J * self.R)]])
+ 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)
+ # Stall Torque in N m
+ self.stall_torque = 2.42
+ # Stall Current in Amps
+ self.stall_current = 133.0
+ # Free Speed in RPM. Used number from last year.
+ self.free_speed = 4650.0
+ # Free Current in Amps
+ self.free_current = 2.7
+ # Moment of inertia of the drivetrain in kg m^2
+ # Just borrowed from last year.
+ self.J = 10
+ # Mass of the robot, in kg.
+ self.m = 68
+ # Radius of the robot, in meters (from last year).
+ self.rb = 0.9603 / 2.0
+ # Radius of the wheels, in meters.
+ self.r = .0515938
+ # Resistance of the motor, divided by the number of motors.
+ self.R = 12.0 / self.stall_current / 2
+ # 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 ratios
+ self.G_const = 28.0 / 50.0 * 20.0 / 64.0
+
+ self.G_low = self.G_const
+ self.G_high = self.G_const
+
+ 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.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)
+
+ # 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]])
+
+ #print "THE NUMBER I WANT" + 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])
+ print self.K
+ q_pos = 0.07
+ q_vel = 1.0
+ 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)
+ print self.A
+ print self.B
+ print self.K
+ print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+ 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()
+
+def main(argv):
+ # Simulate the response of the system to a step input.
+ drivetrain = Drivetrain()
+ 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])
+
+ #pylab.plot(range(100), simulated_left)
+ #pylab.plot(range(100), simulated_right)
+ #pylab.show()
+
+ # Simulate forwards motion.
+ 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])
+
+ #pylab.plot(range(100), close_loop_left)
+ #pylab.plot(range(100), close_loop_right)
+ #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])
+
+ #pylab.plot(range(100), close_loop_left)
+ #pylab.plot(range(100), close_loop_right)
+ #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])
+
+ #pylab.plot(range(100), close_loop_left)
+ #pylab.plot(range(100), close_loop_right)
+ #pylab.show()
+
+ # Write the generated constants out to a file.
+ print "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)
+
+ if len(argv) != 5:
+ print "Expected .h file name and .cc file name"
+ else:
+ dog_loop_writer = control_loop.ControlLoopWriter(
+ "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
+ drivetrain_high_low, drivetrain_high_high])
+ if argv[1][-3:] == '.cc':
+ dog_loop_writer.Write(argv[2], argv[1])
+ else:
+ dog_loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2015/control_loops/python/elevator.py b/y2015/control_loops/python/elevator.py
new file mode 100755
index 0000000..fba72c8
--- /dev/null
+++ b/y2015/control_loops/python/elevator.py
@@ -0,0 +1,246 @@
+#!/usr/bin/python
+
+import control_loop
+import controls
+import polytope
+import polydrivetrain
+import numpy
+import sys
+import matplotlib
+from matplotlib import pylab
+
+class Elevator(control_loop.ControlLoop):
+ def __init__(self, name="Elevator", mass=None):
+ super(Elevator, self).__init__(name)
+ # Stall Torque in N m
+ self.stall_torque = 0.476
+ # Stall Current in Amps
+ self.stall_current = 80.730
+ # Free Speed in RPM
+ self.free_speed = 13906.0
+ # Free Current in Amps
+ self.free_current = 5.820
+ # Mass of the elevator
+ if mass is None:
+ self.mass = 13.0
+ else:
+ self.mass = mass
+
+ # 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) * (84.0 / 14.0)
+ # Pulley diameter
+ self.r = 32 * 0.005 / numpy.pi / 2.0
+ # Control loop time step
+ self.dt = 0.005
+
+ # Elevator left/right spring constant (N/m)
+ self.spring = 800.0
+
+ # State is [average position, average velocity,
+ # position difference/2, velocity difference/2]
+ # Input is [V_left, V_right]
+
+ C1 = self.spring / (self.mass * 0.5)
+ C2 = self.Kt * self.G / (self.mass * 0.5 * self.r * self.R)
+ C3 = self.G * self.G * self.Kt / (
+ self.R * self.r * self.r * self.mass * 0.5 * self.Kv)
+
+ self.A_continuous = numpy.matrix(
+ [[0, 1, 0, 0],
+ [0, -C3, 0, 0],
+ [0, 0, 0, 1],
+ [0, 0, -C1 * 2.0, -C3]])
+
+ print "Full speed is", C2 / C3 * 12.0
+
+ # Start with the unmodified input
+ self.B_continuous = numpy.matrix(
+ [[0, 0],
+ [C2 / 2.0, C2 / 2.0],
+ [0, 0],
+ [C2 / 2.0, -C2 / 2.0]])
+
+ self.C = numpy.matrix([[1, 0, 1, 0],
+ [1, 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)
+
+ print self.A
+
+ controlability = controls.ctrb(self.A, self.B);
+ print "Rank of augmented controlability matrix.", numpy.linalg.matrix_rank(
+ controlability)
+
+ q_pos = 0.02
+ q_vel = 0.400
+ q_pos_diff = 0.01
+ q_vel_diff = 0.45
+ 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_diff ** 2.0)), 0.0],
+ [0.0, 0.0, 0.0, (1.0 / (q_vel_diff ** 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)
+ print self.K
+
+ print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+ self.rpl = 0.20
+ self.ipl = 0.05
+ self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+ self.rpl + 1j * self.ipl,
+ self.rpl - 1j * self.ipl,
+ self.rpl - 1j * self.ipl])
+
+ # 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], [12.0]])
+ self.U_min = numpy.matrix([[-12.0], [-12.0]])
+
+ self.InitializeState()
+
+
+def CapU(U):
+ if U[0, 0] - U[1, 0] > 24:
+ return numpy.matrix([[12], [-12]])
+ elif U[0, 0] - U[1, 0] < -24:
+ return numpy.matrix([[-12], [12]])
+ else:
+ max_u = max(U[0, 0], U[1, 0])
+ min_u = min(U[0, 0], U[1, 0])
+ if max_u > 12:
+ return U - (max_u - 12)
+ if min_u < -12:
+ return U - (min_u + 12)
+ return U
+
+
+def run_test(elevator, initial_X, goal, max_separation_error=0.01,
+ show_graph=True, iterations=200, controller_elevator=None,
+ observer_elevator=None):
+ """Runs the elevator plant with an initial condition and goal.
+
+ The tests themselves are not terribly sophisticated; I just test for
+ whether the goal has been reached and whether the separation goes
+ outside of the initial and goal values by more than max_separation_error.
+ Prints out something for a failure of either condition and returns
+ False if tests fail.
+ Args:
+ elevator: elevator object to use.
+ initial_X: starting state.
+ goal: goal state.
+ show_graph: Whether or not to display a graph showing the changing
+ states and voltages.
+ iterations: Number of timesteps to run the model for.
+ controller_elevator: elevator object to get K from, or None if we should
+ use elevator.
+ observer_elevator: elevator object to use for the observer, or None if we
+ should use the actual state.
+ """
+
+ elevator.X = initial_X
+
+ if controller_elevator is None:
+ controller_elevator = elevator
+
+ if observer_elevator is not None:
+ observer_elevator.X_hat = initial_X + 0.01
+ observer_elevator.X_hat = initial_X
+
+ # Various lists for graphing things.
+ t = []
+ x_avg = []
+ x_sep = []
+ x_hat_avg = []
+ x_hat_sep = []
+ v_avg = []
+ v_sep = []
+ u_left = []
+ u_right = []
+
+ sep_plot_gain = 100.0
+
+ for i in xrange(iterations):
+ X_hat = elevator.X
+ if observer_elevator is not None:
+ X_hat = observer_elevator.X_hat
+ x_hat_avg.append(observer_elevator.X_hat[0, 0])
+ x_hat_sep.append(observer_elevator.X_hat[2, 0] * sep_plot_gain)
+ U = controller_elevator.K * (goal - X_hat)
+ U = CapU(U)
+ x_avg.append(elevator.X[0, 0])
+ v_avg.append(elevator.X[1, 0])
+ x_sep.append(elevator.X[2, 0] * sep_plot_gain)
+ v_sep.append(elevator.X[3, 0])
+ if observer_elevator is not None:
+ observer_elevator.PredictObserver(U)
+ elevator.Update(U)
+ if observer_elevator is not None:
+ observer_elevator.Y = elevator.Y
+ observer_elevator.CorrectObserver(U)
+
+ t.append(i * elevator.dt)
+ u_left.append(U[0, 0])
+ u_right.append(U[1, 0])
+
+ print numpy.linalg.inv(elevator.A)
+ print "delta time is ", elevator.dt
+ print "Velocity at t=0 is ", x_avg[0], v_avg[0], x_sep[0], v_sep[0]
+ print "Velocity at t=1+dt is ", x_avg[1], v_avg[1], x_sep[1], v_sep[1]
+
+ if show_graph:
+ pylab.subplot(2, 1, 1)
+ pylab.plot(t, x_avg, label='x avg')
+ pylab.plot(t, x_sep, label='x sep')
+ if observer_elevator is not None:
+ pylab.plot(t, x_hat_avg, label='x_hat avg')
+ pylab.plot(t, x_hat_sep, label='x_hat sep')
+ pylab.legend()
+
+ pylab.subplot(2, 1, 2)
+ pylab.plot(t, u_left, label='u left')
+ pylab.plot(t, u_right, label='u right')
+ pylab.legend()
+ pylab.show()
+
+
+def main(argv):
+ loaded_mass = 25
+ #loaded_mass = 0
+ elevator = Elevator(mass=13 + loaded_mass)
+ elevator_controller = Elevator(mass=13 + 15)
+ observer_elevator = Elevator(mass=13 + 15)
+ #observer_elevator = None
+
+ # Test moving the elevator with constant separation.
+ initial_X = numpy.matrix([[0.0], [0.0], [0.01], [0.0]])
+ #initial_X = numpy.matrix([[0.0], [0.0], [0.00], [0.0]])
+ R = numpy.matrix([[1.0], [0.0], [0.0], [0.0]])
+ run_test(elevator, initial_X, R, controller_elevator=elevator_controller,
+ observer_elevator=observer_elevator)
+
+ # Write the generated constants out to a file.
+ if len(argv) != 3:
+ print "Expected .h file name and .cc file name for the elevator."
+ else:
+ elevator = Elevator("Elevator")
+ loop_writer = control_loop.ControlLoopWriter("Elevator", [elevator])
+ if argv[1][-3:] == '.cc':
+ loop_writer.Write(argv[2], argv[1])
+ else:
+ loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2015/control_loops/python/polydrivetrain.py b/y2015/control_loops/python/polydrivetrain.py
new file mode 100755
index 0000000..a62c8c8
--- /dev/null
+++ b/y2015/control_loops/python/polydrivetrain.py
@@ -0,0 +1,504 @@
+#!/usr/bin/python
+
+import numpy
+import sys
+import polytope
+import drivetrain
+import control_loop
+import controls
+from matplotlib import pylab
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+
+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.01
+ 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.6, 0.6])
+ 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.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.01
+
+ self.R = 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.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().R)
+ low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
+ self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
+ 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):
+ print gear_name, 'Not in gear.'
+ 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.'
+ return VelocityDrivetrain.SHIFTING_UP
+ else:
+ print gear_name, 'Shifting down.'
+ 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 False:
+ 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])
+
+ steering *= 2.3
+ if True or 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:
+ print '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 True or 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)
+
+ 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
+
+
+def main(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])
+
+ if argv[1][-3:] == '.cc':
+ dog_loop_writer.Write(argv[2], argv[1])
+ else:
+ dog_loop_writer.Write(argv[1], argv[2])
+
+ 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
+
+ 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
+
+ print "K is", vdrivetrain.CurrentDrivetrain().K
+
+ if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
+ print "Left is high"
+ else:
+ print "Left is low"
+ if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
+ print "Right is high"
+ else:
+ print "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)
+
+ 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.
+
+ # 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/y2015/control_loops/python/polydrivetrain_test.py b/y2015/control_loops/python/polydrivetrain_test.py
new file mode 100755
index 0000000..434cdca
--- /dev/null
+++ b/y2015/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/y2015/control_loops/python/shooter.py b/y2015/control_loops/python/shooter.py
new file mode 100755
index 0000000..69f2599
--- /dev/null
+++ b/y2015/control_loops/python/shooter.py
@@ -0,0 +1,254 @@
+#!/usr/bin/python
+
+import control_loop
+import numpy
+import sys
+from matplotlib import pylab
+
+class SprungShooter(control_loop.ControlLoop):
+ def __init__(self, name="RawSprungShooter"):
+ super(SprungShooter, self).__init__(name)
+ # Stall Torque in N m
+ self.stall_torque = .4982
+ # Stall Current in Amps
+ self.stall_current = 85
+ # Free Speed in RPM
+ self.free_speed = 19300.0
+ # Free Current in Amps
+ self.free_current = 1.2
+ # Effective mass of the shooter in kg.
+ # This rough estimate should about include the effect of the masses
+ # of the gears. If this number is too low, the eigen values of self.A
+ # will start to become extremely small.
+ self.J = 200
+ # Resistance of the motor, divided by the number of motors.
+ self.R = 12.0 / self.stall_current / 2.0
+ # 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
+ # Spring constant for the springs, N/m
+ self.Ks = 2800.0
+ # Maximum extension distance (Distance from the 0 force point on the
+ # spring to the latch position.)
+ self.max_extension = 0.32385
+ # Gear ratio multiplied by radius of final sprocket.
+ self.G = 10.0 / 40.0 * 20.0 / 54.0 * 24.0 / 54.0 * 20.0 / 84.0 * 16.0 * (3.0 / 8.0) / (2.0 * numpy.pi) * 0.0254
+
+ # Control loop time step
+ self.dt = 0.01
+
+ # State feedback matrices
+ self.A_continuous = numpy.matrix(
+ [[0, 1],
+ [-self.Ks / self.J,
+ -self.Kt / self.Kv / (self.J * self.G * self.G * self.R)]])
+ self.B_continuous = numpy.matrix(
+ [[0],
+ [self.Kt / (self.J * self.G * self.R)]])
+ 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)
+
+ self.PlaceControllerPoles([0.45, 0.45])
+
+ self.rpl = .05
+ self.ipl = 0.008
+ self.PlaceObserverPoles([self.rpl,
+ self.rpl])
+
+ self.U_max = numpy.matrix([[12.0]])
+ self.U_min = numpy.matrix([[-12.0]])
+
+ self.InitializeState()
+
+
+class Shooter(SprungShooter):
+ def __init__(self, name="RawShooter"):
+ super(Shooter, self).__init__(name)
+
+ # State feedback matrices
+ self.A_continuous = numpy.matrix(
+ [[0, 1],
+ [0, -self.Kt / self.Kv / (self.J * self.G * self.G * self.R)]])
+ self.B_continuous = numpy.matrix(
+ [[0],
+ [self.Kt / (self.J * self.G * self.R)]])
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ self.PlaceControllerPoles([0.45, 0.45])
+
+ self.rpl = .05
+ self.ipl = 0.008
+ self.PlaceObserverPoles([self.rpl,
+ self.rpl])
+
+ self.U_max = numpy.matrix([[12.0]])
+ self.U_min = numpy.matrix([[-12.0]])
+
+ self.InitializeState()
+
+
+class SprungShooterDeltaU(SprungShooter):
+ def __init__(self, name="SprungShooter"):
+ super(SprungShooterDeltaU, self).__init__(name)
+ A_unaugmented = self.A
+ B_unaugmented = self.B
+
+ self.A = numpy.matrix([[0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0],
+ [0.0, 0.0, 1.0]])
+ self.A[0:2, 0:2] = A_unaugmented
+ self.A[0:2, 2] = B_unaugmented
+
+ self.B = numpy.matrix([[0.0],
+ [0.0],
+ [1.0]])
+
+ self.C = numpy.matrix([[1.0, 0.0, 0.0]])
+ self.D = numpy.matrix([[0.0]])
+
+ self.PlaceControllerPoles([0.50, 0.35, 0.80])
+
+ print "K"
+ print self.K
+ print "Placed controller poles are"
+ print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+ self.rpl = .05
+ self.ipl = 0.008
+ self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+ self.rpl - 1j * self.ipl, 0.90])
+ print "Placed observer poles are"
+ print numpy.linalg.eig(self.A - self.L * self.C)[0]
+
+ self.U_max = numpy.matrix([[12.0]])
+ self.U_min = numpy.matrix([[-12.0]])
+
+ self.InitializeState()
+
+
+class ShooterDeltaU(Shooter):
+ def __init__(self, name="Shooter"):
+ super(ShooterDeltaU, self).__init__(name)
+ A_unaugmented = self.A
+ B_unaugmented = self.B
+
+ self.A = numpy.matrix([[0.0, 0.0, 0.0],
+ [0.0, 0.0, 0.0],
+ [0.0, 0.0, 1.0]])
+ self.A[0:2, 0:2] = A_unaugmented
+ self.A[0:2, 2] = B_unaugmented
+
+ self.B = numpy.matrix([[0.0],
+ [0.0],
+ [1.0]])
+
+ self.C = numpy.matrix([[1.0, 0.0, 0.0]])
+ self.D = numpy.matrix([[0.0]])
+
+ self.PlaceControllerPoles([0.55, 0.45, 0.80])
+
+ print "K"
+ print self.K
+ print "Placed controller poles are"
+ print numpy.linalg.eig(self.A - self.B * self.K)[0]
+
+ self.rpl = .05
+ self.ipl = 0.008
+ self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
+ self.rpl - 1j * self.ipl, 0.90])
+ print "Placed observer poles are"
+ print numpy.linalg.eig(self.A - self.L * self.C)[0]
+
+ self.U_max = numpy.matrix([[12.0]])
+ self.U_min = numpy.matrix([[-12.0]])
+
+ self.InitializeState()
+
+
+def ClipDeltaU(shooter, old_voltage, delta_u):
+ old_u = old_voltage
+ new_u = numpy.clip(old_u + delta_u, shooter.U_min, shooter.U_max)
+ return new_u - old_u
+
+def main(argv):
+ # Simulate the response of the system to a goal.
+ sprung_shooter = SprungShooterDeltaU()
+ raw_sprung_shooter = SprungShooter()
+ close_loop_x = []
+ close_loop_u = []
+ goal_position = -0.3
+ R = numpy.matrix([[goal_position], [0.0], [-sprung_shooter.A[1, 0] / sprung_shooter.A[1, 2] * goal_position]])
+ voltage = numpy.matrix([[0.0]])
+ for _ in xrange(500):
+ U = sprung_shooter.K * (R - sprung_shooter.X_hat)
+ U = ClipDeltaU(sprung_shooter, voltage, U)
+ sprung_shooter.Y = raw_sprung_shooter.Y + 0.01
+ sprung_shooter.UpdateObserver(U)
+ voltage += U;
+ raw_sprung_shooter.Update(voltage)
+ close_loop_x.append(raw_sprung_shooter.X[0, 0] * 10)
+ close_loop_u.append(voltage[0, 0])
+
+ pylab.plot(range(500), close_loop_x)
+ pylab.plot(range(500), close_loop_u)
+ pylab.show()
+
+ shooter = ShooterDeltaU()
+ raw_shooter = Shooter()
+ close_loop_x = []
+ close_loop_u = []
+ goal_position = -0.3
+ R = numpy.matrix([[goal_position], [0.0], [-shooter.A[1, 0] / shooter.A[1, 2] * goal_position]])
+ voltage = numpy.matrix([[0.0]])
+ for _ in xrange(500):
+ U = shooter.K * (R - shooter.X_hat)
+ U = ClipDeltaU(shooter, voltage, U)
+ shooter.Y = raw_shooter.Y + 0.01
+ shooter.UpdateObserver(U)
+ voltage += U;
+ raw_shooter.Update(voltage)
+ close_loop_x.append(raw_shooter.X[0, 0] * 10)
+ close_loop_u.append(voltage[0, 0])
+
+ pylab.plot(range(500), close_loop_x)
+ pylab.plot(range(500), close_loop_u)
+ pylab.show()
+
+ # Write the generated constants out to a file.
+ if len(argv) != 5:
+ print "Expected .h file name and .cc file name for"
+ print "both the plant and unaugmented plant"
+ else:
+ unaug_sprung_shooter = SprungShooter("RawSprungShooter")
+ unaug_shooter = Shooter("RawShooter")
+ unaug_loop_writer = control_loop.ControlLoopWriter("RawShooter",
+ [unaug_sprung_shooter,
+ unaug_shooter])
+ if argv[3][-3:] == '.cc':
+ unaug_loop_writer.Write(argv[4], argv[3])
+ else:
+ unaug_loop_writer.Write(argv[3], argv[4])
+
+ sprung_shooter = SprungShooterDeltaU()
+ shooter = ShooterDeltaU()
+ loop_writer = control_loop.ControlLoopWriter("Shooter", [sprung_shooter,
+ shooter])
+
+ loop_writer.AddConstant(control_loop.Constant("kMaxExtension", "%f",
+ sprung_shooter.max_extension))
+ loop_writer.AddConstant(control_loop.Constant("kSpringConstant", "%f",
+ sprung_shooter.Ks))
+ if argv[1][-3:] == '.cc':
+ loop_writer.Write(argv[2], argv[1])
+ else:
+ loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2015/control_loops/update_arm.sh b/y2015/control_loops/update_arm.sh
new file mode 100755
index 0000000..2a10f93
--- /dev/null
+++ b/y2015/control_loops/update_arm.sh
@@ -0,0 +1,12 @@
+#!/bin/bash
+#
+# Updates the arm controllers (for both robots).
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/arm.py fridge/arm_motor_plant.cc \
+ fridge/arm_motor_plant.h \
+ fridge/integral_arm_plant.cc \
+ fridge/integral_arm_plant.h
diff --git a/y2015/control_loops/update_claw.sh b/y2015/control_loops/update_claw.sh
new file mode 100755
index 0000000..d37e737
--- /dev/null
+++ b/y2015/control_loops/update_claw.sh
@@ -0,0 +1,10 @@
+#!/bin/bash
+#
+# Updates the claw controllers (for both robots).
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/claw.py claw/claw_motor_plant.cc \
+ claw/claw_motor_plant.h
diff --git a/y2015/control_loops/update_drivetrain.sh b/y2015/control_loops/update_drivetrain.sh
new file mode 100755
index 0000000..ecd1c41
--- /dev/null
+++ b/y2015/control_loops/update_drivetrain.sh
@@ -0,0 +1,12 @@
+#!/bin/bash
+#
+# Updates the drivetrain controllers (for both robots).
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/drivetrain.py drivetrain/drivetrain_dog_motor_plant.h \
+ drivetrain/drivetrain_dog_motor_plant.cc \
+ drivetrain/drivetrain_clutch_motor_plant.h \
+ drivetrain/drivetrain_clutch_motor_plant.cc
diff --git a/y2015/control_loops/update_elevator.sh b/y2015/control_loops/update_elevator.sh
new file mode 100755
index 0000000..4a7edb4
--- /dev/null
+++ b/y2015/control_loops/update_elevator.sh
@@ -0,0 +1,10 @@
+#!/bin/bash
+#
+# Updates the elevator controllers (for both robots).
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/elevator.py fridge/elevator_motor_plant.cc \
+ fridge/elevator_motor_plant.h
diff --git a/y2015/control_loops/update_polydrivetrain.sh b/y2015/control_loops/update_polydrivetrain.sh
new file mode 100755
index 0000000..338e40e
--- /dev/null
+++ b/y2015/control_loops/update_polydrivetrain.sh
@@ -0,0 +1,14 @@
+#!/bin/bash
+#
+# Updates the polydrivetrain controllers (for both robots) and CIM models.
+
+cd $(dirname $0)
+
+export PYTHONPATH=../../frc971/control_loops/python
+
+./python/polydrivetrain.py drivetrain/polydrivetrain_dog_motor_plant.h \
+ drivetrain/polydrivetrain_dog_motor_plant.cc \
+ drivetrain/polydrivetrain_clutch_motor_plant.h \
+ drivetrain/polydrivetrain_clutch_motor_plant.cc \
+ drivetrain/polydrivetrain_cim_plant.h \
+ drivetrain/polydrivetrain_cim_plant.cc