Merge "Update bot3 drivetrain and get defense bot working."
diff --git a/NO_BUILD_AMD64 b/NO_BUILD_AMD64
index 716368c..faa75a9 100644
--- a/NO_BUILD_AMD64
+++ b/NO_BUILD_AMD64
@@ -13,3 +13,4 @@
-//y2015_bot3:download
-//y2016/wpilib/...
-//y2016:download
+-//y2016:download_stripped
diff --git a/NO_BUILD_ROBORIO b/NO_BUILD_ROBORIO
index bd1907c..36ae012 100644
--- a/NO_BUILD_ROBORIO
+++ b/NO_BUILD_ROBORIO
@@ -3,6 +3,7 @@
-//y2012/control_loops/python/...
-//y2014_bot3/control_loops/python/...
-//y2014/control_loops/python/...
+-//y2014_bot3/control_loops/python/...
-//y2015/control_loops/python/...
-//y2015_bot3/control_loops/python/...
-//y2016/control_loops/python/...
diff --git a/WORKSPACE b/WORKSPACE
index 6d6f7e1..0d4eb2f 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -1,3 +1,5 @@
+workspace(name = 'org_frc971')
+
new_local_repository(
name = 'usr_repo',
path = '/usr',
diff --git a/aos/common/actions/actions.h b/aos/common/actions/actions.h
index b26f732..07e569e 100644
--- a/aos/common/actions/actions.h
+++ b/aos/common/actions/actions.h
@@ -123,7 +123,7 @@
run_value_(run_counter_.fetch_add(1, ::std::memory_order_relaxed) |
((getpid() & 0xFFFF) << 16)),
params_(params) {
- LOG(INFO, "Action %" PRIx32 " created on queue %s\n", run_value_,
+ LOG(DEBUG, "Action %" PRIx32 " created on queue %s\n", run_value_,
queue_group_->goal.name());
// Clear out any old status messages from before now.
queue_group_->status.FetchLatest();
@@ -211,10 +211,10 @@
run_value_, queue_group_->goal.name());
} else {
if (sent_cancel_) {
- LOG(INFO, "Action %" PRIx32 " on queue %s already cancelled\n",
+ LOG(DEBUG, "Action %" PRIx32 " on queue %s already cancelled\n",
run_value_, queue_group_->goal.name());
} else {
- LOG(INFO, "Canceling action %" PRIx32 " on queue %s\n", run_value_,
+ LOG(DEBUG, "Canceling action %" PRIx32 " on queue %s\n", run_value_,
queue_group_->goal.name());
queue_group_->goal.MakeWithBuilder().run(0).Send();
sent_cancel_ = true;
@@ -292,7 +292,7 @@
queue_group_->status->last_running == run_value_)) {
// It's currently running our instance.
has_started_ = true;
- LOG(INFO, "Action %" PRIx32 " on queue %s has been started\n",
+ LOG(DEBUG, "Action %" PRIx32 " on queue %s has been started\n",
run_value_, queue_group_->goal.name());
} else if (old_run_value_ != 0 &&
queue_group_->status->running == old_run_value_) {
@@ -324,7 +324,7 @@
template <typename T>
void TypedAction<T>::DoStart() {
if (goal_) {
- LOG(INFO, "Starting action %" PRIx32 "\n", run_value_);
+ LOG(DEBUG, "Starting action %" PRIx32 "\n", run_value_);
goal_->run = run_value_;
goal_->params = params_;
sent_started_ = true;
diff --git a/aos/common/logging/BUILD b/aos/common/logging/BUILD
index d4d3ca5..8b28482 100644
--- a/aos/common/logging/BUILD
+++ b/aos/common/logging/BUILD
@@ -176,6 +176,9 @@
hdrs = [
'implementations.h',
],
+ linkopts = [
+ '-pthread',
+ ],
deps = [
'//aos/common:die',
'//aos/common:time',
diff --git a/aos/common/time.cc b/aos/common/time.cc
index 87c991d..125b016 100644
--- a/aos/common/time.cc
+++ b/aos/common/time.cc
@@ -12,7 +12,45 @@
#include "aos/common/logging/logging.h"
#include "aos/common/mutex.h"
+namespace std {
+namespace this_thread {
+template <>
+void sleep_until(const ::aos::monotonic_clock::time_point &end_time) {
+ struct timespec end_time_timespec;
+ ::std::chrono::seconds sec =
+ ::std::chrono::duration_cast<::std::chrono::seconds>(
+ end_time.time_since_epoch());
+ ::std::chrono::nanoseconds nsec =
+ ::std::chrono::duration_cast<::std::chrono::nanoseconds>(
+ end_time.time_since_epoch() - sec);
+ end_time_timespec.tv_sec = sec.count();
+ end_time_timespec.tv_nsec = nsec.count();
+ int returnval;
+ do {
+ returnval = clock_nanosleep(CLOCK_MONOTONIC, TIMER_ABSTIME,
+ &end_time_timespec, nullptr);
+ if (returnval != EINTR && returnval != 0) {
+ PLOG(FATAL, "clock_nanosleep(%jd, TIMER_ABSTIME, %p, nullptr) failed",
+ static_cast<uintmax_t>(CLOCK_MONOTONIC), &end_time_timespec);
+ }
+ } while (returnval != 0);
+}
+
+} // namespace this_thread
+} // namespace std
+
+
namespace aos {
+monotonic_clock::time_point monotonic_clock::now() noexcept {
+ struct timespec current_time;
+ if (clock_gettime(CLOCK_MONOTONIC, ¤t_time) != 0) {
+ PLOG(FATAL, "clock_gettime(%jd, %p) failed",
+ static_cast<uintmax_t>(CLOCK_MONOTONIC), ¤t_time);
+ }
+ return time_point(::std::chrono::seconds(current_time.tv_sec) +
+ ::std::chrono::nanoseconds(current_time.tv_nsec));
+}
+
namespace time {
// State required to enable and use mock time.
diff --git a/aos/common/time.h b/aos/common/time.h
index a176ba0..40b72b0 100644
--- a/aos/common/time.h
+++ b/aos/common/time.h
@@ -7,12 +7,31 @@
#include <stdint.h>
#include <type_traits>
+#include <chrono>
+#include <thread>
#include <ostream>
#include "aos/common/type_traits.h"
#include "aos/common/macros.h"
namespace aos {
+
+class monotonic_clock {
+ public:
+ typedef ::std::chrono::nanoseconds::rep rep;
+ typedef ::std::chrono::nanoseconds::period period;
+ typedef ::std::chrono::nanoseconds duration;
+ typedef ::std::chrono::time_point<monotonic_clock> time_point;
+
+ static monotonic_clock::time_point now() noexcept;
+ static constexpr bool is_steady = true;
+
+ // Returns the epoch (0).
+ static constexpr monotonic_clock::time_point epoch() {
+ return time_point(duration(0));
+ }
+};
+
namespace time {
// A nice structure for representing times.
@@ -280,4 +299,15 @@
} // namespace time
} // namespace aos
+namespace std {
+namespace this_thread {
+// Template specialization for monotonic_clock, since we can use clock_nanosleep
+// with TIMER_ABSTIME and get very precise absolute time sleeps.
+template <>
+void sleep_until(const ::aos::monotonic_clock::time_point &end_time);
+
+} // namespace this_thread
+} // namespace std
+
+
#endif // AOS_COMMON_TIME_H_
diff --git a/aos/common/time_test.cc b/aos/common/time_test.cc
index 008b3cf..3ae82ab 100644
--- a/aos/common/time_test.cc
+++ b/aos/common/time_test.cc
@@ -1,5 +1,7 @@
#include "aos/common/time.h"
+#include <thread>
+
#include "gtest/gtest.h"
#include "aos/common/macros.h"
@@ -256,6 +258,16 @@
EXPECT_EQ(MACRO_DARG(Time(0, Time::kNSecInSec / 100)), Time::FromRate(100));
}
+// Test the monotonic_clock and sleep_until functions.
+TEST(TimeTest, MonotonicClockSleepAndNow) {
+ monotonic_clock::time_point start = monotonic_clock::now();
+ const auto kSleepTime = ::std::chrono::milliseconds(500);
+ ::std::this_thread::sleep_until(start + kSleepTime);
+ monotonic_clock::time_point end = monotonic_clock::now();
+ EXPECT_GE(end - start, kSleepTime);
+ EXPECT_LT(end - start, kSleepTime + ::std::chrono::milliseconds(200));
+}
+
} // namespace testing
} // namespace time
} // namespace aos
diff --git a/aos/downloader/downloader.bzl b/aos/downloader/downloader.bzl
index a98571a..e5179c9 100644
--- a/aos/downloader/downloader.bzl
+++ b/aos/downloader/downloader.bzl
@@ -5,7 +5,13 @@
executable = True,
content = '\n'.join([
'#!/bin/bash',
- 'cd "${BASH_SOURCE[@]}.runfiles"',
+ 'set -e',
+ 'cd "${BASH_SOURCE[@]}.runfiles/%s"' % ctx.workspace_name,
+ ] + ['%s %s --dirs %s -- %s "$@"' % (
+ ctx.executable._downloader.short_path,
+ ' '.join([src.short_path for src in d.downloader_srcs]),
+ d.downloader_dir,
+ ctx.attr.default_target) for d in ctx.attr.dirs] + [
'exec %s %s -- %s "$@"' % (ctx.executable._downloader.short_path,
' '.join([src.short_path for src in all_files]),
ctx.attr.default_target),
@@ -17,15 +23,26 @@
content = '\n'.join([f.basename for f in ctx.files.start_srcs]) + '\n',
)
+ to_download = [ctx.outputs._startlist]
+ to_download += all_files
+ for d in ctx.attr.dirs:
+ to_download += d.downloader_srcs
+
return struct(
runfiles = ctx.runfiles(
- files = all_files + ctx.files._downloader + [ctx.outputs._startlist],
+ files = to_download + ctx.files._downloader,
collect_data = True,
collect_default = True,
),
files = set([ctx.outputs.executable]),
)
+def _aos_downloader_dir_impl(ctx):
+ return struct(
+ downloader_dir = ctx.attr.dir,
+ downloader_srcs = ctx.files.srcs
+ )
+
'''Creates a binary which downloads code to a robot.
Running this with `bazel run` will actually download everything.
@@ -34,6 +51,7 @@
Attrs:
srcs: The files to download. They currently all get shoved into one folder.
+ dirs: A list of aos_downloader_dirs to download too.
start_srcs: Like srcs, except they also get put into start_list.txt.
default_target: The default host to download to. If not specified, defaults to
roboRIO-971.local.
@@ -54,6 +72,13 @@
mandatory = True,
allow_files = True,
),
+ 'dirs': attr.label_list(
+ mandatory = False,
+ providers = [
+ 'downloader_dir',
+ 'downloader_srcs',
+ ]
+ ),
'default_target': attr.string(
default = 'roboRIO-971-frc.local',
),
@@ -63,3 +88,26 @@
'_startlist': '%{name}.start_list.dir/start_list.txt',
},
)
+
+'''Downloads files to a specific directory.
+
+This rule does nothing by itself. Use it by adding to the dirs attribute of an
+aos_downloader rule.
+
+Attrs:
+ srcs: The files to download. They all go in the same directory.
+ dir: The directory (relative to the standard download directory) to put all
+ the files in.
+'''
+aos_downloader_dir = rule(
+ implementation = _aos_downloader_dir_impl,
+ attrs = {
+ 'srcs': attr.label_list(
+ mandatory = True,
+ allow_files = True,
+ ),
+ 'dir': attr.string(
+ mandatory = True,
+ ),
+ },
+)
diff --git a/aos/downloader/downloader.py b/aos/downloader/downloader.py
index 5cdd94e..9799b1f 100644
--- a/aos/downloader/downloader.py
+++ b/aos/downloader/downloader.py
@@ -23,9 +23,19 @@
def main(argv):
- srcs = argv[1:argv.index('--')]
args = argv[argv.index('--') + 1:]
+ relative_dir = ''
+ recursive = False
+
+ if '--dirs' in argv:
+ dirs_index = argv.index('--dirs')
+ srcs = argv[1:dirs_index]
+ relative_dir = argv[dirs_index + 1]
+ recursive = True
+ else:
+ srcs = argv[1:argv.index('--')]
+
ROBORIO_TARGET_DIR = '/home/admin/robot_code'
ROBORIO_USER = 'admin'
@@ -47,7 +57,7 @@
ssh_target = '%s@%s' % (user, hostname)
rsync_cmd = (['rsync', '-c', '-v', '-z', '--copy-links'] + srcs +
- ['%s:%s' % (ssh_target, target_dir)])
+ ['%s:%s/%s' % (ssh_target, target_dir, relative_dir)])
try:
subprocess.check_call(rsync_cmd)
except subprocess.CalledProcessError as e:
@@ -60,12 +70,13 @@
else:
raise e
- subprocess.check_call(
- ('ssh', ssh_target, '&&'.join([
- 'chmod u+s %s/starter_exe' % target_dir,
- 'echo \'Done moving new executables into place\'',
- 'bash -c \'sync && sync && sync\'',
- ])))
+ if not recursive:
+ subprocess.check_call(
+ ('ssh', ssh_target, '&&'.join([
+ 'chmod u+s %s/starter_exe' % target_dir,
+ 'echo \'Done moving new executables into place\'',
+ 'bash -c \'sync && sync && sync\'',
+ ])))
if __name__ == '__main__':
main(sys.argv)
diff --git a/aos/linux_code/ipc_lib/BUILD b/aos/linux_code/ipc_lib/BUILD
index 98aca55..95b30ce 100644
--- a/aos/linux_code/ipc_lib/BUILD
+++ b/aos/linux_code/ipc_lib/BUILD
@@ -8,6 +8,9 @@
hdrs = [
'aos_sync.h',
],
+ linkopts = [
+ '-pthread',
+ ],
deps = [
'//aos/common/logging',
'//aos/common:once',
diff --git a/aos/linux_code/ipc_lib/aos_sync.cc b/aos/linux_code/ipc_lib/aos_sync.cc
index b4b32ad..92eb1a1 100644
--- a/aos/linux_code/ipc_lib/aos_sync.cc
+++ b/aos/linux_code/ipc_lib/aos_sync.cc
@@ -33,7 +33,7 @@
using ::aos::linux_code::ipc_lib::FutexAccessorObserver;
-// This code was originally based on <http://www.akkadia.org/drepper/futex.pdf>,
+// This code was originally based on <https://www.akkadia.org/drepper/futex.pdf>,
// but is has since evolved a lot. However, that still has useful information.
//
// Finding information about actually using futexes is really REALLY hard, so
diff --git a/aos/testing/BUILD b/aos/testing/BUILD
index 8656d23..a8dce04 100644
--- a/aos/testing/BUILD
+++ b/aos/testing/BUILD
@@ -72,3 +72,15 @@
],
testonly = True,
)
+
+cc_library(
+ name = 'random_seed',
+ visibility = ['//visibility:public'],
+ srcs = [
+ 'random_seed.cc',
+ ],
+ hdrs = [
+ 'random_seed.h',
+ ],
+ testonly = True,
+)
diff --git a/aos/testing/random_seed.cc b/aos/testing/random_seed.cc
new file mode 100644
index 0000000..9e7136f
--- /dev/null
+++ b/aos/testing/random_seed.cc
@@ -0,0 +1,17 @@
+#include "aos/testing/random_seed.h"
+
+#include <stdlib.h>
+
+namespace aos {
+namespace testing {
+
+int RandomSeed() {
+ const char *from_environment = getenv("TEST_RANDOM_SEED");
+ if (from_environment != nullptr) {
+ return atoi(from_environment);
+ }
+ return 1;
+}
+
+} // namespace testing
+} // namespace aos
diff --git a/aos/testing/random_seed.h b/aos/testing/random_seed.h
new file mode 100644
index 0000000..825e7b1
--- /dev/null
+++ b/aos/testing/random_seed.h
@@ -0,0 +1,15 @@
+#ifndef AOS_TESTING_RANDOM_SEED_H_
+#define AOS_TESTING_RANDOM_SEED_H_
+
+namespace aos {
+namespace testing {
+
+// Returns the random seed to use for testing.
+//
+// This is ${TEST_RANDOM_SEED} if it is set or 1.
+int RandomSeed();
+
+} // namespace testing
+} // namespace aos
+
+#endif // AOS_TESTING_RANDOM_SEED_H_
diff --git a/debian/slycot.BUILD b/debian/slycot.BUILD
index 64eb358..55274b1 100644
--- a/debian/slycot.BUILD
+++ b/debian/slycot.BUILD
@@ -66,15 +66,15 @@
':slycot_c',
],
linkopts = ['-shared', '-lblas', '-llapack'],
- linkstatic=0,
+ linkstatic = False,
)
# Generate the _wrapper file which loads _fortranwrapper and pretends.
genrule(
name = '_wrapper',
outs = ['slycot/_wrapper.py'],
- cmd = 'echo "from _fortranwrapper import *" > $(OUTS)',
- output_to_bindir=1,
+ cmd = 'echo "from external.slycot_repo._fortranwrapper import *" > $(OUTS)',
+ output_to_bindir = True,
)
# Now present a python library for slycot
diff --git a/doc/make_bazel_package.sh b/doc/make_bazel_package.sh
index 1c10df0..a42acfa 100755
--- a/doc/make_bazel_package.sh
+++ b/doc/make_bazel_package.sh
@@ -10,12 +10,12 @@
BAZEL_SOURCE="$1"
VERSION="$(date +%Y%m%d%H%M)+$(GIT_DIR="${BAZEL_SOURCE}/.git" git rev-parse --short HEAD)"
-DEB="bazel_${VERSION}.deb"
+DEB="bazel_${VERSION}_amd64.deb"
"${BAZEL_SOURCE}/compile.sh" compile
(
cd "${BAZEL_SOURCE}"
-./output/bazel build //scripts/packages:bazel-debian --embed_label="${VERSION}"
+./output/bazel build -c opt //scripts/packages:bazel-debian --embed_label="${VERSION}"
)
cp "${BAZEL_SOURCE}/bazel-bin/scripts/packages/bazel-debian.deb" "${DEB}"
diff --git a/frc971/control_loops/BUILD b/frc971/control_loops/BUILD
index 5eeed1d..9dee424 100644
--- a/frc971/control_loops/BUILD
+++ b/frc971/control_loops/BUILD
@@ -59,6 +59,7 @@
cc_library(
name = 'position_sensor_sim',
+ testonly = True,
srcs = [
'position_sensor_sim.cc',
],
@@ -69,6 +70,7 @@
':queues',
':gaussian_noise',
'//debian:libm',
+ '//aos/testing:random_seed',
],
)
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index 72a32cc..05fc4a3 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -93,6 +93,32 @@
],
)
+genrule(
+ name = 'genrule_down_estimator',
+ visibility = ['//visibility:private'],
+ cmd = '$(location //frc971/control_loops/python:down_estimator) $(OUTS)',
+ tools = [
+ '//frc971/control_loops/python:down_estimator',
+ ],
+ outs = [
+ 'down_estimator.h',
+ 'down_estimator.cc',
+ ],
+)
+
+cc_library(
+ name = 'down_estimator',
+ hdrs = [
+ 'down_estimator.h',
+ ],
+ srcs = [
+ 'down_estimator.cc',
+ ],
+ deps = [
+ '//frc971/control_loops:state_feedback_loop',
+ ],
+)
+
cc_library(
name = 'drivetrain_lib',
srcs = [
@@ -102,12 +128,14 @@
'drivetrain.h',
],
deps = [
+ ':down_estimator',
':drivetrain_queue',
':gear',
':polydrivetrain',
':ssdrivetrain',
'//aos/common/controls:control_loop',
'//frc971/queues:gyro',
+ '//frc971/wpilib:imu_queue',
'//aos/common/util:log_interval',
'//aos/common/logging:queue_logging',
'//aos/common/logging:matrix_logging',
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index b4c04a3..f2b14a9 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -13,9 +13,11 @@
#include "frc971/control_loops/drivetrain/drivetrain.q.h"
#include "frc971/control_loops/drivetrain/polydrivetrain.h"
#include "frc971/control_loops/drivetrain/ssdrivetrain.h"
+#include "frc971/control_loops/drivetrain/down_estimator.h"
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
#include "frc971/queues/gyro.q.h"
#include "frc971/shifter_hall_effect.h"
+#include "frc971/wpilib/imu.q.h"
using frc971::sensors::gyro_reading;
@@ -32,11 +34,13 @@
kf_(dt_config_.make_kf_drivetrain_loop()),
dt_openloop_(dt_config_, &kf_),
dt_closedloop_(dt_config_, &kf_, &integrated_kf_heading_),
+ down_estimator_(MakeDownEstimatorLoop()),
left_gear_(dt_config_.default_high_gear ? Gear::HIGH : Gear::LOW),
right_gear_(dt_config_.default_high_gear ? Gear::HIGH : Gear::LOW),
left_high_requested_(dt_config_.default_high_gear),
right_high_requested_(dt_config_.default_high_gear) {
::aos::controls::HPolytope<0>::Init();
+ down_U_.setZero();
}
int DrivetrainLoop::ControllerIndexFromGears() {
@@ -76,6 +80,11 @@
const ::frc971::control_loops::DrivetrainQueue::Position *position,
::frc971::control_loops::DrivetrainQueue::Output *output,
::frc971::control_loops::DrivetrainQueue::Status *status) {
+ if (!has_been_enabled_ && output) {
+ has_been_enabled_ = true;
+ down_estimator_.mutable_X_hat(1, 0) = 0.0;
+ }
+
// TODO(austin): Put gear detection logic here.
switch (dt_config_.shifter_type) {
case ShifterType::SIMPLE_SHIFTER:
@@ -111,6 +120,36 @@
LOG_STRUCT(DEBUG, "state", gear_logging);
}
+ if (::frc971::imu_values.FetchLatest()) {
+ const double rate = -::frc971::imu_values->gyro_y;
+ const double accel_squared = ::frc971::imu_values->accelerometer_x *
+ ::frc971::imu_values->accelerometer_x +
+ ::frc971::imu_values->accelerometer_y *
+ ::frc971::imu_values->accelerometer_y +
+ ::frc971::imu_values->accelerometer_z *
+ ::frc971::imu_values->accelerometer_z;
+ const double angle = ::std::atan2(::frc971::imu_values->accelerometer_x,
+ ::frc971::imu_values->accelerometer_z) +
+ 0.008;
+ if (accel_squared > 1.03 || accel_squared < 0.97) {
+ LOG(DEBUG, "New IMU value, rejecting reading\n");
+ } else {
+ // -y is our gyro.
+ // z accel is down
+ // x accel is the front of the robot pointed down.
+ Eigen::Matrix<double, 1, 1> Y;
+ Y << angle;
+ down_estimator_.Correct(Y);
+ }
+
+ LOG(DEBUG,
+ "New IMU value from ADIS16448, rate is %f, angle %f, fused %f, bias "
+ "%f\n",
+ rate, angle, down_estimator_.X_hat(0, 0), down_estimator_.X_hat(1, 0));
+ down_U_ << rate;
+ }
+ down_estimator_.UpdateObserver(down_U_);
+
// TODO(austin): Signal the current gear to both loops.
if (gyro_reading.FetchLatest()) {
@@ -186,6 +225,7 @@
status->right_voltage_error = kf_.X_hat(5, 0);
status->estimated_angular_velocity_error = kf_.X_hat(6, 0);
status->estimated_heading = integrated_kf_heading_;
+ status->ground_angle = down_estimator_.X_hat(0, 0) + dt_config_.down_offset;
dt_openloop_.PopulateStatus(status);
dt_closedloop_.PopulateStatus(status);
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index a9541b7..1330708 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -48,6 +48,9 @@
PolyDrivetrain dt_openloop_;
DrivetrainMotorsSS dt_closedloop_;
+ StateFeedbackLoop<2, 1, 1> down_estimator_;
+ Eigen::Matrix<double, 1, 1> down_U_;
+
// Current gears for each drive side.
Gear left_gear_;
Gear right_gear_;
@@ -59,6 +62,8 @@
bool left_high_requested_;
bool right_high_requested_;
+
+ bool has_been_enabled_ = false;
};
} // namespace drivetrain
diff --git a/frc971/control_loops/drivetrain/drivetrain.q b/frc971/control_loops/drivetrain/drivetrain.q
index 4723aef..da4fadc 100644
--- a/frc971/control_loops/drivetrain/drivetrain.q
+++ b/frc971/control_loops/drivetrain/drivetrain.q
@@ -141,6 +141,9 @@
// True if the output voltage was capped last cycle.
bool output_was_capped;
+
+ // The angle of the robot relative to the ground.
+ double ground_angle;
};
queue Goal goal;
diff --git a/frc971/control_loops/drivetrain/drivetrain_config.h b/frc971/control_loops/drivetrain/drivetrain_config.h
index a0b6ac0..ea76ca9 100644
--- a/frc971/control_loops/drivetrain/drivetrain_config.h
+++ b/frc971/control_loops/drivetrain/drivetrain_config.h
@@ -48,6 +48,8 @@
// Variable that holds the default gear ratio. We use this in ZeroOutputs().
// (ie. true means high gear is default).
bool default_high_gear;
+
+ double down_offset;
};
} // namespace drivetrain
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index f2c4638..aa18aec 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -49,7 +49,7 @@
::y2016::control_loops::drivetrain::kHighGearRatio,
::y2016::control_loops::drivetrain::kLowGearRatio,
- kThreeStateDriveShifter, kThreeStateDriveShifter, false};
+ kThreeStateDriveShifter, kThreeStateDriveShifter, false, 0};
return kDrivetrainConfig;
};
@@ -256,7 +256,7 @@
.left_goal(-1.0)
.right_goal(1.0)
.Send();
- RunForTime(Time::InSeconds(1.0));
+ RunForTime(Time::InSeconds(2.0));
VerifyNearGoal();
}
diff --git a/frc971/control_loops/drivetrain/polydrivetrain.cc b/frc971/control_loops/drivetrain/polydrivetrain.cc
index 2383c83..121a231 100644
--- a/frc971/control_loops/drivetrain/polydrivetrain.cc
+++ b/frc971/control_loops/drivetrain/polydrivetrain.cc
@@ -112,7 +112,7 @@
const bool quickturn = goal.quickturn;
const bool highgear = goal.highgear;
- const double kWheelNonLinearity = 0.55;
+ const double kWheelNonLinearity = 0.25;
// Apply a sin function that's scaled to make it feel better.
const double angular_range = M_PI_2 * kWheelNonLinearity;
diff --git a/frc971/control_loops/position_sensor_sim.cc b/frc971/control_loops/position_sensor_sim.cc
index caa383e..6075155 100644
--- a/frc971/control_loops/position_sensor_sim.cc
+++ b/frc971/control_loops/position_sensor_sim.cc
@@ -70,6 +70,11 @@
index_count_++;
}
+ if (new_index_segment != cur_index_segment_) {
+ latched_pot_ = pot_noise_.AddNoiseToSample(cur_index_ * index_diff_ +
+ known_index_pos_);
+ }
+
cur_index_segment_ = new_index_segment;
cur_pos_ = new_pos;
}
@@ -86,7 +91,7 @@
double index_pulse_position = cur_index_ * index_diff_ + known_index_pos_;
// Populate the latched pot/encoder samples.
- values->latched_pot = pot_noise_.AddNoiseToSample(index_pulse_position);
+ values->latched_pot = latched_pot_;
values->latched_encoder = index_pulse_position - start_position_;
}
diff --git a/frc971/control_loops/position_sensor_sim.h b/frc971/control_loops/position_sensor_sim.h
index 6c1884d..3ce3056 100644
--- a/frc971/control_loops/position_sensor_sim.h
+++ b/frc971/control_loops/position_sensor_sim.h
@@ -1,6 +1,8 @@
#ifndef FRC971_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_
#define FRC971_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_
+#include "aos/testing/random_seed.h"
+
#include "frc971/control_loops/control_loops.q.h"
#include "frc971/control_loops/gaussian_noise.h"
@@ -18,7 +20,8 @@
// noise_seed: The seed to feed into the random number generator for the
// potentiometer values.
// TODO(danielp): Allow for starting with a non-zero encoder value.
- PositionSensorSimulator(double index_diff, unsigned int noise_seed = 0);
+ PositionSensorSimulator(double index_diff, unsigned int noise_seed =
+ ::aos::testing::RandomSeed());
// Set new parameters for the sensors. This is useful for unit tests to change
// the simulated sensors' behavior on the fly.
@@ -57,6 +60,8 @@
int cur_index_;
// How many index pulses we've seen.
int index_count_;
+ // The pot position at the most recent index pulse with noise added.
+ double latched_pot_;
// Distance between index pulses on the mechanism.
double index_diff_;
// Absolute position of a known index pulse.
diff --git a/frc971/control_loops/position_sensor_sim_test.cc b/frc971/control_loops/position_sensor_sim_test.cc
index 0c9d3a9..1ca5033 100644
--- a/frc971/control_loops/position_sensor_sim_test.cc
+++ b/frc971/control_loops/position_sensor_sim_test.cc
@@ -150,5 +150,50 @@
EXPECT_DOUBLE_EQ(index_diff * 1.25, position.latched_encoder);
}
+// Tests that the latched values update correctly.
+TEST_F(PositionSensorSimTest, LatchedValues) {
+ const double index_diff = 0.5;
+ PositionSensorSimulator sim(index_diff);
+ sim.Initialize(0, 0.25);
+ PotAndIndexPosition position;
+
+ sim.MoveTo(0.75 * index_diff);
+ sim.GetSensorValues(&position);
+ EXPECT_EQ(0u, position.index_pulses);
+
+ sim.MoveTo(1.75 * index_diff);
+ sim.GetSensorValues(&position);
+ EXPECT_EQ(1u, position.index_pulses);
+ EXPECT_NEAR(index_diff, position.latched_pot, 0.75);
+ EXPECT_DOUBLE_EQ(index_diff, position.latched_encoder);
+ const double first_latched_pot = position.latched_pot;
+
+ sim.MoveTo(1.95 * index_diff);
+ sim.GetSensorValues(&position);
+ EXPECT_EQ(1u, position.index_pulses);
+ EXPECT_NEAR(index_diff, position.latched_pot, 0.75);
+ EXPECT_DOUBLE_EQ(first_latched_pot, position.latched_pot);
+ EXPECT_DOUBLE_EQ(index_diff, position.latched_encoder);
+
+ sim.MoveTo(2.05 * index_diff);
+ sim.GetSensorValues(&position);
+ EXPECT_EQ(2u, position.index_pulses);
+ EXPECT_NEAR(index_diff * 2, position.latched_pot, 0.75);
+ EXPECT_DOUBLE_EQ(index_diff * 2, position.latched_encoder);
+
+ sim.MoveTo(1.95 * index_diff);
+ sim.GetSensorValues(&position);
+ EXPECT_EQ(3u, position.index_pulses);
+ EXPECT_NEAR(index_diff * 2, position.latched_pot, 0.75);
+ EXPECT_DOUBLE_EQ(index_diff * 2, position.latched_encoder);
+
+ sim.MoveTo(0.95 * index_diff);
+ sim.GetSensorValues(&position);
+ EXPECT_EQ(4u, position.index_pulses);
+ EXPECT_NEAR(index_diff, position.latched_pot, 0.75);
+ EXPECT_GT(::std::abs(first_latched_pot - position.latched_pot), 0.005);
+ EXPECT_DOUBLE_EQ(index_diff, position.latched_encoder);
+}
+
} // namespace control_loops
} // namespace frc971
diff --git a/frc971/control_loops/python/BUILD b/frc971/control_loops/python/BUILD
index d172983..897738a 100644
--- a/frc971/control_loops/python/BUILD
+++ b/frc971/control_loops/python/BUILD
@@ -26,3 +26,13 @@
':controls',
],
)
+
+py_binary(
+ name = 'down_estimator',
+ srcs = [
+ 'down_estimator.py',
+ ],
+ deps = [
+ ':controls',
+ ],
+)
diff --git a/frc971/control_loops/python/down_estimator.py b/frc971/control_loops/python/down_estimator.py
new file mode 100644
index 0000000..6db8f34
--- /dev/null
+++ b/frc971/control_loops/python/down_estimator.py
@@ -0,0 +1,121 @@
+#!/usr/bin/python
+
+import math
+import sys
+import random
+
+import numpy
+import gflags
+import glog
+from matplotlib import pylab
+
+from frc971.control_loops.python import controls
+from frc971.control_loops.python import control_loop
+
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
+class DownEstimator(control_loop.ControlLoop):
+ def __init__(self, name='DownEstimator'):
+ super(DownEstimator, self).__init__(name)
+ self.dt = 0.005
+
+ # State is [gyro_angle, bias].
+ # U is [gyro_x_velocity].
+
+ self.A_continuous = numpy.matrix([[0, 1],
+ [0, 0]])
+
+ self.B_continuous = numpy.matrix([[1],
+ [0]])
+
+ self.A, self.B = self.ContinuousToDiscrete(
+ self.A_continuous, self.B_continuous, self.dt)
+
+ q_gyro_noise = 1e-6
+ q_gyro_bias_noise = 1e-3
+ self.Q = numpy.matrix([[1.0 / (q_gyro_noise ** 2.0), 0.0],
+ [0.0, 1.0 / (q_gyro_bias_noise ** 2.0)]])
+
+ r_accelerometer_angle_noise = 5e+7
+ self.R = numpy.matrix([[(r_accelerometer_angle_noise ** 2.0)]])
+
+ self.C = numpy.matrix([[1.0, 0.0]])
+ self.D = numpy.matrix([[0]])
+
+ self.U_max = numpy.matrix([[numpy.pi]])
+ self.U_min = numpy.matrix([[-numpy.pi]])
+ self.K = numpy.matrix(numpy.zeros((1, 2)))
+
+ self.KalmanGain, self.Q_steady = controls.kalman(
+ A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
+
+ self.L = self.A * self.KalmanGain
+
+ self.InitializeState()
+
+ def Update(self, accelerometer_x, accelerometer_y, accelerometer_z, gyro_x):
+ acceleration = math.sqrt(
+ accelerometer_x**2 + accelerometer_y**2 + accelerometer_z**2)
+ if acceleration < 0.9 or acceleration > 1.1:
+ glog.error('bad total acceleration %f' % acceleration)
+ # TODO(Brian): Tune this?
+ return
+ accelerometer_angle = math.atan2(accelerometer_x, accelerometer_z)
+ Z = numpy.matrix([[accelerometer_angle], [gyro_x]])
+
+ Y = Z - self.H * self.X_hat
+ S = self.H * self.P * self.H.transpose() + self.R
+ K = self.P * self.H.transpose() * numpy.linalg.inv(S)
+ self.X_hat += K * Y
+ self.P = (numpy.identity(K.shape[0]) - K * self.H) * self.P
+
+def main(argv):
+ argv = FLAGS(argv)
+ glog.init()
+
+ estimator = DownEstimator()
+
+ if FLAGS.plot:
+ real_angles = [0]
+ real_velocities = [0]
+ estimated_angles = [0]
+ estimated_velocities = [0]
+ for _ in xrange(100):
+ estimator.Predict(0)
+ estimator.Update(numpy.sqrt(2) / 2.0, numpy.sqrt(2) / 2.0, 0, 0)
+ real_angles.append(math.pi / 2)
+ real_velocities.append(0)
+ estimated_angles.append(estimator.X_hat[0, 0])
+ estimated_velocities.append(estimator.X_hat[1, 0])
+ angle = math.pi / 2
+ velocity = 1
+ for i in xrange(100):
+ measured_velocity = velocity + (random.random() - 0.5) * 0.01 + 0.05
+ estimator.Predict(measured_velocity)
+ estimator.Update(math.sin(angle) + (random.random() - 0.5) * 0.02, 0,
+ math.cos(angle) + (random.random() - 0.5) * 0.02,
+ measured_velocity)
+ real_angles.append(angle)
+ real_velocities.append(velocity)
+ estimated_angles.append(estimator.X_hat[0, 0])
+ estimated_velocities.append(estimator.X_hat[1, 0])
+ angle += velocity * estimator.dt
+ pylab.plot(range(len(real_angles)), real_angles)
+ pylab.plot(range(len(real_velocities)), real_velocities)
+ pylab.plot(range(len(estimated_angles)), estimated_angles)
+ pylab.plot(range(len(estimated_velocities)), estimated_velocities)
+ pylab.show()
+
+ if len(argv) != 3:
+ print "Expected .h file name and .cc file name"
+ else:
+ namespaces = ['frc971', 'control_loops', 'drivetrain']
+ kf_loop_writer = control_loop.ControlLoopWriter(
+ "DownEstimator", [estimator],
+ namespaces = namespaces)
+ kf_loop_writer.Write(argv[1], argv[2])
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index d834f33..cf1a6f8 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -7,10 +7,12 @@
#include <math.h>
#include "aos/common/logging/queue_logging.h"
+#include "aos/common/messages/robot_state.q.h"
#include "aos/common/time.h"
#include "aos/linux_code/init.h"
#include "frc971/wpilib/imu.q.h"
+#include "frc971/zeroing/averager.h"
namespace frc971 {
namespace wpilib {
@@ -40,16 +42,17 @@
constexpr uint8_t kProdIdAddress = 0x56;
constexpr uint8_t kSerialNumberAddress = 0x58;
-// LSB/degree/second for the gyros.
-constexpr double kGyroLsbDegreeSecond = 25;
-// LSB/G for the accelerometers.
-constexpr double kAccelerometerLsbG = 1200;
-// LSB/gauss for the magnetometers.
-constexpr double kMagnetometerLsbGauss = 7.0 / 1000.0 /* mgauss to gauss */;
-// LSB/bar for the barometer.
-constexpr double kBarometerLsbPascal = 1.0 / (20.0 / 10 /* ubar to pascals */);
-// LSB/degree C for the temperature sensor.
-constexpr double kTemperatureLsbDegree = 1.0 / 0.07386;
+// degree/second/LSB for the gyros.
+constexpr double kGyroLsbDegreeSecond = 1.0 / 25.0;
+// G/LSB for the accelerometers.
+constexpr double kAccelerometerLsbG = 1.0 / 1200.0;
+// gauss/LSB for the magnetometers.
+constexpr double kMagnetometerLsbGauss =
+ 1.0 / (7.0 / 1000.0) /* mgauss to gauss */;
+// bar/LSB for the barometer.
+constexpr double kBarometerLsbPascal = 0.02 * 100;
+// degree/LSB C for the temperature sensor.
+constexpr double kTemperatureLsbDegree = 0.07386;
// Degrees C corresponding to 0 for the temperature sensor.
constexpr double kTemperatureZero = 31;
@@ -129,6 +132,13 @@
}
LOG(INFO, "IMU initialized successfully\n");
+ // Rounded to approximate the 204.8 Hz.
+ constexpr size_t kImuSendRate = 205;
+
+ zeroing::Averager<double, 6 * kImuSendRate> average_gyro_x;
+ zeroing::Averager<double, 6 * kImuSendRate> average_gyro_y;
+ zeroing::Averager<double, 6 * kImuSendRate> average_gyro_z;
+
bool got_an_interrupt = false;
while (run_) {
{
@@ -142,10 +152,10 @@
got_an_interrupt = true;
const ::aos::time::Time read_time = ::aos::time::Time::Now();
- uint8_t to_send[8 * 2 * 14], to_receive[8 * 2 * 14];
+ uint8_t to_send[2 * 14], to_receive[2 * 14];
+ memset(&to_send[0], 0, sizeof(to_send));
to_send[0] = kGlobalReadAddress;
- memset(&to_send[1], 0, sizeof(to_send) - 1);
- if (!DoTransaction<8 * 2 * 14>(to_send, to_receive)) continue;
+ if (!DoTransaction<2 * 14>(to_send, to_receive)) continue;
// If it's false now or another edge happened, then we're in trouble. This
// won't catch all instances of being a little bit slow (because of the
@@ -161,8 +171,8 @@
{
const uint16_t calculated_crc = CalculateCrc(&to_receive[4], 11);
- uint16_t received_crc;
- memcpy(&received_crc, &to_receive[13], 2);
+ uint16_t received_crc =
+ to_receive[13 * 2 + 1] | (to_receive[13 * 2] << 8);
if (received_crc != calculated_crc) {
LOG(WARNING, "received CRC %" PRIx16 " but calculated %" PRIx16 "\n",
received_crc, calculated_crc);
@@ -172,7 +182,7 @@
{
uint16_t diag_stat;
- memcpy(&diag_stat, &to_receive[1], 2);
+ memcpy(&diag_stat, &to_receive[2], 2);
if (!CheckDiagStatValue(diag_stat)) continue;
}
@@ -181,28 +191,57 @@
message->monotonic_timestamp_ns = read_time.ToNSec();
message->gyro_x =
- ConvertValue(&to_receive[2], kGyroLsbDegreeSecond) * (M_PI / 2.0);
+ ConvertValue(&to_receive[4], kGyroLsbDegreeSecond * M_PI / 180.0);
message->gyro_y =
- ConvertValue(&to_receive[3], kGyroLsbDegreeSecond) * (M_PI / 2.0);
+ ConvertValue(&to_receive[6], kGyroLsbDegreeSecond * M_PI / 180.0);
message->gyro_z =
- ConvertValue(&to_receive[4], kGyroLsbDegreeSecond) * (M_PI / 2.0);
+ ConvertValue(&to_receive[8], kGyroLsbDegreeSecond * M_PI / 180.0);
- message->accelerometer_x = ConvertValue(&to_receive[5], kAccelerometerLsbG);
- message->accelerometer_y = ConvertValue(&to_receive[6], kAccelerometerLsbG);
- message->accelerometer_z = ConvertValue(&to_receive[7], kAccelerometerLsbG);
+ // The first few seconds of samples are averaged and subtracted from
+ // subsequent samples for zeroing purposes.
+ if (!gyros_are_zeroed_) {
+ average_gyro_x.AddData(message->gyro_x);
+ average_gyro_y.AddData(message->gyro_y);
+ average_gyro_z.AddData(message->gyro_z);
+
+ if (average_gyro_x.full() && average_gyro_y.full() &&
+ average_gyro_z.full()) {
+ ::aos::joystick_state.FetchLatest();
+ if (::aos::joystick_state.get() && ::aos::joystick_state->enabled) {
+ gyro_x_zeroed_offset_ = -average_gyro_x.GetAverage();
+ gyro_y_zeroed_offset_ = -average_gyro_y.GetAverage();
+ gyro_z_zeroed_offset_ = -average_gyro_z.GetAverage();
+ LOG(INFO, "total gyro zero offset X:%f, Y:%f, Z:%f\n",
+ gyro_x_zeroed_offset_, gyro_y_zeroed_offset_,
+ gyro_z_zeroed_offset_);
+ gyros_are_zeroed_ = true;
+ }
+ }
+ }
+
+ message->gyro_x += gyro_x_zeroed_offset_;
+ message->gyro_y += gyro_y_zeroed_offset_;
+ message->gyro_z += gyro_z_zeroed_offset_;
+
+ message->accelerometer_x =
+ ConvertValue(&to_receive[10], kAccelerometerLsbG);
+ message->accelerometer_y =
+ ConvertValue(&to_receive[12], kAccelerometerLsbG);
+ message->accelerometer_z =
+ ConvertValue(&to_receive[14], kAccelerometerLsbG);
message->magnetometer_x =
- ConvertValue(&to_receive[8], kMagnetometerLsbGauss);
+ ConvertValue(&to_receive[16], kMagnetometerLsbGauss);
message->magnetometer_y =
- ConvertValue(&to_receive[9], kMagnetometerLsbGauss);
+ ConvertValue(&to_receive[18], kMagnetometerLsbGauss);
message->magnetometer_z =
- ConvertValue(&to_receive[10], kMagnetometerLsbGauss);
+ ConvertValue(&to_receive[20], kMagnetometerLsbGauss);
message->barometer =
- ConvertValue(&to_receive[11], kBarometerLsbPascal, false);
+ ConvertValue(&to_receive[22], kBarometerLsbPascal, false);
message->temperature =
- ConvertValue(&to_receive[12], kTemperatureLsbDegree) + kTemperatureZero;
+ ConvertValue(&to_receive[24], kTemperatureLsbDegree) + kTemperatureZero;
LOG_STRUCT(DEBUG, "sending", *message);
if (!message.Send()) {
@@ -214,12 +253,12 @@
float ADIS16448::ConvertValue(uint8_t *data, double lsb_per_output, bool sign) {
double value;
if (sign) {
- int16_t raw_value;
- memcpy(&raw_value, data, 2);
+ int16_t raw_value = static_cast<int16_t>(
+ (static_cast<uint16_t>(data[0]) << 8) | static_cast<uint16_t>(data[1]));
value = raw_value;
} else {
- uint16_t raw_value;
- memcpy(&raw_value, data, 2);
+ uint16_t raw_value =
+ (static_cast<uint16_t>(data[0]) << 8) | static_cast<uint16_t>(data[1]);
value = raw_value;
}
return value * lsb_per_output;
@@ -232,7 +271,9 @@
if (!DoTransaction<2>(to_send, to_receive)) return false;
- if (value) memcpy(value, to_receive, 2);
+ if (value) {
+ memcpy(value, to_receive, 2);
+ }
return true;
}
@@ -248,12 +289,6 @@
bool ADIS16448::CheckDiagStatValue(uint16_t value) const {
bool r = true;
- if (value & (1 << 0)) {
- LOG(WARNING, "IMU gave magnetometer functional test failure\n");
- }
- if (value & (1 << 1)) {
- LOG(WARNING, "IMU gave barometer functional test failure\n");
- }
if (value & (1 << 2)) {
LOG(WARNING, "IMU gave flash update failure\n");
}
@@ -266,6 +301,31 @@
if (value & (1 << 5)) {
LOG(WARNING, "IMU gave self-test failure\n");
r = false;
+ if (value & (1 << 10)) {
+ LOG(WARNING, "IMU gave X-axis gyro self-test failure\n");
+ }
+ if (value & (1 << 11)) {
+ LOG(WARNING, "IMU gave Y-axis gyro self-test failure\n");
+ }
+ if (value & (1 << 12)) {
+ LOG(WARNING, "IMU gave Z-axis gyro self-test failure\n");
+ }
+ if (value & (1 << 13)) {
+ LOG(WARNING, "IMU gave X-axis accelerometer self-test failure\n");
+ }
+ if (value & (1 << 14)) {
+ LOG(WARNING, "IMU gave Y-axis accelerometer self-test failure\n");
+ }
+ if (value & (1 << 15)) {
+ LOG(WARNING, "IMU gave Z-axis accelerometer self-test failure, %x\n",
+ value);
+ }
+ if (value & (1 << 0)) {
+ LOG(WARNING, "IMU gave magnetometer functional test failure\n");
+ }
+ if (value & (1 << 1)) {
+ LOG(WARNING, "IMU gave barometer functional test failure\n");
+ }
}
if (value & (1 << 6)) {
LOG(WARNING, "IMU gave flash test checksum failure\n");
@@ -276,30 +336,6 @@
if (value & (1 << 9)) {
LOG(WARNING, "IMU says alarm 2 is active\n");
}
- if (value & (1 << 10)) {
- LOG(WARNING, "IMU gave X-axis gyro self-test failure\n");
- r = false;
- }
- if (value & (1 << 11)) {
- LOG(WARNING, "IMU gave Y-axis gyro self-test failure\n");
- r = false;
- }
- if (value & (1 << 12)) {
- LOG(WARNING, "IMU gave Z-axis gyro self-test failure\n");
- r = false;
- }
- if (value & (1 << 13)) {
- LOG(WARNING, "IMU gave X-axis accelerometer self-test failure\n");
- r = false;
- }
- if (value & (1 << 14)) {
- LOG(WARNING, "IMU gave Y-axis accelerometer self-test failure\n");
- r = false;
- }
- if (value & (1 << 15)) {
- LOG(WARNING, "IMU gave Z-axis accelerometer self-test failure\n");
- r = false;
- }
return r;
}
@@ -320,7 +356,7 @@
serial_number);
// Divide the sampling by 2^2 = 4 to get 819.2 / 4 = 204.8 Hz.
- if (!WriteRegister(kSmplPrdAddress, 2 << 8)) return false;
+ if (!WriteRegister(kSmplPrdAddress, (2 << 8) | 1)) return false;
// Start a self test.
if (!WriteRegister(kMscCtrlAddress, 1 << 10)) return false;
@@ -342,8 +378,8 @@
((0 << 0) | // DIO1
(1 << 1) | // DIO goes high when data is valid
(1 << 2) | // enable DIO changing when data is vald
- (1 << 4)) // enable CRC16 for burst mode
- )) {
+ (1 << 4) | // enable CRC16 for burst mode
+ (1 << 6)))) {
return false;
}
return true;
diff --git a/frc971/wpilib/ADIS16448.h b/frc971/wpilib/ADIS16448.h
index 778ab49..c8552bf 100644
--- a/frc971/wpilib/ADIS16448.h
+++ b/frc971/wpilib/ADIS16448.h
@@ -37,6 +37,10 @@
void Quit() { run_ = false; }
+ double gyro_x_zeroed_offset() const { return gyro_x_zeroed_offset_; }
+ double gyro_y_zeroed_offset() const { return gyro_y_zeroed_offset_; }
+ double gyro_z_zeroed_offset() const { return gyro_z_zeroed_offset_; }
+
private:
// Converts a 16-bit value at data to a scaled output value where a value of 1
// corresponds to lsb_per_output.
@@ -70,6 +74,12 @@
DigitalInput *const dio1_;
::std::atomic<bool> run_{true};
+
+ // The averaged values of the gyro over 6 seconds after power up.
+ bool gyros_are_zeroed_ = false;
+ double gyro_x_zeroed_offset_ = 0.0;
+ double gyro_y_zeroed_offset_ = 0.0;
+ double gyro_z_zeroed_offset_ = 0.0;
};
} // namespace wpilib
diff --git a/frc971/wpilib/BUILD b/frc971/wpilib/BUILD
index 6ea778a..c01f7cc 100644
--- a/frc971/wpilib/BUILD
+++ b/frc971/wpilib/BUILD
@@ -99,8 +99,9 @@
'gyro_sender.h',
],
deps = [
- '//frc971/queues:gyro',
':gyro_interface',
+ '//frc971/queues:gyro',
+ '//frc971/zeroing:averager',
'//aos/common/logging',
'//aos/common/logging:queue_logging',
'//aos/common/util:phased_loop',
@@ -225,12 +226,14 @@
'ADIS16448.cc',
],
deps = [
- '//third_party/allwpilib_2016:wpilib',
+ ':imu_queue',
'//aos/common/logging',
'//aos/common/logging:queue_logging',
+ '//aos/common/messages:robot_state',
'//aos/common:time',
'//aos/linux_code:init',
- ':imu_queue',
+ '//frc971/zeroing:averager',
+ '//third_party/allwpilib_2016:wpilib',
],
)
diff --git a/frc971/wpilib/gyro_sender.cc b/frc971/wpilib/gyro_sender.cc
index dd3b3e1..82e9775 100644
--- a/frc971/wpilib/gyro_sender.cc
+++ b/frc971/wpilib/gyro_sender.cc
@@ -10,6 +10,7 @@
#include "aos/linux_code/init.h"
#include "frc971/queues/gyro.q.h"
+#include "frc971/zeroing/averager.h"
namespace frc971 {
namespace wpilib {
@@ -35,10 +36,8 @@
int startup_cycles_left = 2 * kReadingRate;
- double zeroing_data[6 * kReadingRate];
- size_t zeroing_index = 0;
+ zeroing::Averager<double, 6 * kReadingRate> zeroing_data;
bool zeroed = false;
- bool have_zeroing_data = false;
double zero_offset = 0;
::aos::time::PhasedLoop phased_loop(
@@ -118,22 +117,12 @@
message->velocity = 0.0;
message.Send();
}
- zeroing_data[zeroing_index] = new_angle;
- ++zeroing_index;
- if (zeroing_index >= sizeof(zeroing_data) / sizeof(zeroing_data[0])) {
- zeroing_index = 0;
- have_zeroing_data = true;
- }
+ zeroing_data.AddData(new_angle);
::aos::joystick_state.FetchLatest();
if (::aos::joystick_state.get() && ::aos::joystick_state->enabled &&
- have_zeroing_data) {
- zero_offset = 0;
- for (size_t i = 0; i < sizeof(zeroing_data) / sizeof(zeroing_data[0]);
- ++i) {
- zero_offset -= zeroing_data[i];
- }
- zero_offset /= sizeof(zeroing_data) / sizeof(zeroing_data[0]);
+ zeroing_data.full()) {
+ zero_offset = -zeroing_data.GetAverage();
LOG(INFO, "total zero offset %f\n", zero_offset);
zeroed = true;
}
diff --git a/frc971/zeroing/BUILD b/frc971/zeroing/BUILD
index 8a8d82c..c63d97d 100644
--- a/frc971/zeroing/BUILD
+++ b/frc971/zeroing/BUILD
@@ -2,6 +2,24 @@
load('/aos/build/queues', 'queue_library')
+cc_library(
+ name = 'averager',
+ hdrs = [
+ 'averager.h',
+ ],
+)
+
+cc_test(
+ name = 'averager_test',
+ srcs = [
+ 'averager_test.cc',
+ ],
+ deps = [
+ ':averager',
+ '//aos/testing:googletest',
+ ],
+)
+
queue_library(
name = 'zeroing_queue',
srcs = [
diff --git a/frc971/zeroing/averager.h b/frc971/zeroing/averager.h
new file mode 100644
index 0000000..879c246
--- /dev/null
+++ b/frc971/zeroing/averager.h
@@ -0,0 +1,56 @@
+#ifndef FRC971_ZEROING_AVERAGER_H_
+#define FRC971_ZEROING_AVERAGER_H_
+
+#include <algorithm>
+#include <array>
+#include <stdint.h>
+
+namespace frc971 {
+namespace zeroing {
+
+// Averages a set of given numbers. Numbers are given one at a time. Once full
+// the average may be requested.
+template <typename data_type, size_t data_size>
+class Averager {
+ public:
+ // Adds one data point to the set of data points to be averaged.
+ // If more than "data_size" samples are added, they will start overwriting
+ // the oldest ones.
+ void AddData(data_type data) {
+ data_[data_point_index_] = data;
+ num_data_points_ = ::std::min(data_size, num_data_points_ + 1);
+ data_point_index_ = (data_point_index_ + 1) % data_size;
+ }
+
+ // Returns the average of the data points.
+ data_type GetAverage() const {
+ // TODO(phil): What do we want to do without any elements?
+ if (num_data_points_ == 0) {
+ return 0;
+ }
+
+ data_type average = 0;
+ for (data_type data : data_) {
+ average += data;
+ }
+ return average / num_data_points_;
+ }
+
+ // Returns true when we've gathered data_size data points.
+ bool full() const { return num_data_points_ >= data_size; };
+
+ size_t size() const { return data_size; }
+
+ private:
+ // Data points to be averaged.
+ ::std::array<data_type, data_size> data_;
+ // Which data point in "data_" will be filled in next.
+ size_t data_point_index_ = 0;
+ // Number of data points added via AddData().
+ size_t num_data_points_ = 0;
+};
+
+} // namespace zeroing
+} // namespace frc971
+
+#endif // FRC971_ZEROING_AVERAGER_H_
diff --git a/frc971/zeroing/averager_test.cc b/frc971/zeroing/averager_test.cc
new file mode 100644
index 0000000..930a3cb
--- /dev/null
+++ b/frc971/zeroing/averager_test.cc
@@ -0,0 +1,35 @@
+#include "gtest/gtest.h"
+#include "frc971/zeroing/averager.h"
+
+namespace frc971 {
+namespace zeroing {
+
+class AveragerTest : public ::testing::Test {
+ protected:
+ void SetUp() override {}
+};
+
+// Makes sure that we can compute the average of a bunch of integers.
+TEST_F(AveragerTest, ComputeIntegerAverage) {
+ Averager<int, 6> averager;
+ for (size_t i = 0; i < averager.size(); ++i) {
+ ASSERT_FALSE(averager.full());
+ averager.AddData(static_cast<int>(i));
+ }
+ ASSERT_TRUE(averager.full());
+ ASSERT_EQ(2, averager.GetAverage());
+}
+
+// Makes sure that we can compute the average of a bunch of floats.
+TEST_F(AveragerTest, ComputeFloatAverage) {
+ Averager<float, 100> averager;
+ for (size_t i = 0; i < averager.size(); ++i) {
+ ASSERT_FALSE(averager.full());
+ averager.AddData(static_cast<float>(i) / 3.0);
+ }
+ ASSERT_TRUE(averager.full());
+ ASSERT_NEAR(16.5, averager.GetAverage(), 0.001);
+}
+
+} // namespace zeroing
+} // namespace frc971
diff --git a/frc971/zeroing/zeroing.cc b/frc971/zeroing/zeroing.cc
index e8cac6f..4ff6391 100644
--- a/frc971/zeroing/zeroing.cc
+++ b/frc971/zeroing/zeroing.cc
@@ -108,15 +108,15 @@
// zeroed.
zeroed_ = true;
// Throw an error if first_start_pos is bigger/smaller than
- // allowable_encoder_error_ * index_diff +
- // start_pos.
+ // allowable_encoder_error_ * index_diff + start_pos.
if (::std::abs(first_start_pos_ - start_pos_) >
allowable_encoder_error_ * index_diff_) {
if (!error_) {
LOG(ERROR,
"Encoder ticks out of range since last index pulse. first start "
- "position: %f recent starting position: %f\n",
- first_start_pos_, start_pos_);
+ "position: %f recent starting position: %f, allowable error: %f\n",
+ first_start_pos_, start_pos_,
+ allowable_encoder_error_ * index_diff_);
error_ = true;
}
}
diff --git a/frc971/zeroing/zeroing.h b/frc971/zeroing/zeroing.h
index 5216df0..b5e2c14 100644
--- a/frc971/zeroing/zeroing.h
+++ b/frc971/zeroing/zeroing.h
@@ -116,8 +116,8 @@
// Stores the position "start_pos" variable the first time the program
// is zeroed.
double first_start_pos_;
- // Value between 0 and 1 which determines a fraction of the index_diff
- // you want to use.
+ // The fraction of index_diff (possibly greater than 1) after which an error
+ // is reported.
double allowable_encoder_error_;
};
diff --git a/third_party/gperftools/BUILD b/third_party/gperftools/BUILD
index ada8712..4fa332f 100644
--- a/third_party/gperftools/BUILD
+++ b/third_party/gperftools/BUILD
@@ -137,6 +137,9 @@
'//third_party/empty_config_h',
],
copts = common_copts,
+ linkopts = [
+ '-pthread',
+ ],
alwayslink = True,
nocopts = '-std=gnu\+\+1y',
)
diff --git a/third_party/protobuf/protobuf.bzl b/third_party/protobuf/protobuf.bzl
index 0cc195b..d91cde4 100644
--- a/third_party/protobuf/protobuf.bzl
+++ b/third_party/protobuf/protobuf.bzl
@@ -1,13 +1,13 @@
# -*- mode: python; -*- PYTHON-PREPROCESSING-REQUIRED
def _GetPath(ctx, path):
- if str(ctx.label).startswith('@'):
+ if str(ctx.label).startswith('@') and not str(ctx.label).startswith('@//'):
fail('External labels not supported for now')
return path
def _GenDir(ctx):
if not ctx.attr.includes:
- if str(ctx.label).startswith('@'):
+ if str(ctx.label).startswith('@') and not str(ctx.label).startswith('@//'):
fail('External labels not supported for now')
return ''
if not ctx.attr.includes[0]:
diff --git a/tools/bazel b/tools/bazel
new file mode 100755
index 0000000..963a3e5
--- /dev/null
+++ b/tools/bazel
@@ -0,0 +1,107 @@
+#!/bin/bash
+
+# The bazel script calls this instead of the bazel-real binary which is
+# installed next to it. This script downloads a specific version of Bazel and
+# then calls that.
+
+# Alternatively, if the environment variable BAZEL_OVERRIDE is set, that will be
+# run directly (after printing a message). That is intended for testing only.
+
+# This script operates based on the assumption that any directory of the correct
+# name is a fully extracted, valid Bazel installation. It is careful to avoid
+# putting an invalid directory at that name at any point.
+
+set -e
+set -u
+set -o pipefail
+
+if [[ -n "${BAZEL_OVERRIDE+x}" ]]; then
+ tput setaf 1 >&2
+ echo -n "Actually calling " >&2
+ tput setaf 3 >&2
+ echo "${BAZEL_OVERRIDE}" >&2
+ tput sgr0 >&2
+ exec "${BAZEL_OVERRIDE}" "$@"
+fi
+
+readonly VERSION="201607070016+7a0d360"
+
+readonly DOWNLOAD_DIR="$(dirname "${BASH_SOURCE[0]}")/../bazel-downloads"
+# Directory to unpack bazel into. This must change whenever bazel changes.
+readonly VERSION_DIR="${DOWNLOAD_DIR}/${VERSION}-v1"
+readonly VERSION_BAZEL="${VERSION_DIR}/usr/bin/bazel"
+
+# Creating might fail if another invocation is racing us.
+if [[ ! -d "${DOWNLOAD_DIR}" ]]; then
+ mkdir "${DOWNLOAD_DIR}" || true
+fi
+if [[ ! -d "${DOWNLOAD_DIR}" ]]; then
+ echo "Failed to create ${DOWNLOAD_DIR}" >&2
+ exit 1
+fi
+
+readonly INSTALLER_NAME="bazel_${VERSION}_amd64.deb"
+readonly DOWNLOAD_URL="http://frc971.org/Build-Dependencies/${INSTALLER_NAME}"
+
+if [[ ! -d "${VERSION_DIR}" ]]; then
+ echo "Downloading Bazel version ${VERSION} from ${DOWNLOAD_URL}..." >&2
+
+ # A temporary directory which is definitely on the same filesystem as our final
+ # destination, which is important so we can atomically move it.
+ # If this move is non-atomic, then a concurrent Bazel command (like the verifier
+ # uses several of) could use a half-copied Bazel installation.
+ TEMP_DIR="$(mktemp --directory --tmpdir="${DOWNLOAD_DIR}")"
+ readonly TEMP_DIR
+
+ ( cd "${TEMP_DIR}"
+ wget "${DOWNLOAD_URL}" -O "${INSTALLER_NAME}" --no-verbose --show-progress
+ echo "Unpacking Bazel version ${VERSION}..." >&2
+ dpkg-deb -x "${INSTALLER_NAME}" extracted
+ )
+
+ touch "${TEMP_DIR}/extracted/usr/bin/bazel.bazelrc"
+
+ # Careful: somebody else might have already done it. If they manage to make
+ # the move between our check and our move, then we'll end up with a random
+ # extracted directory which won't do anybody any harm. If somebody else does
+ # that first, then our move will fail.
+ if [[ ! -d "${VERSION_DIR}" ]]; then
+ mv "${TEMP_DIR}/extracted" "${VERSION_DIR}" || true
+ fi
+ if [[ ! -d "${VERSION_DIR}" ]]; then
+ echo "Failed to create ${VERSION_DIR}" >&2
+ exit 1
+ fi
+ rm -rf "${TEMP_DIR}"
+ echo "Done downloading Bazel version ${VERSION}"
+fi
+
+if [[ -x "${VERSION_BAZEL}-real" ]]; then
+ exec -a "${VERSION_BAZEL}" env -i \
+ HOSTNAME="${HOSTNAME}" \
+ SHELL="${SHELL}" \
+ USER="${USER}" \
+ PATH="${PATH}" \
+ LANG="${LANG}" \
+ HOME="${HOME}" \
+ LOGNAME="${LOGNAME}" \
+ TERM="${TERM}" \
+ DISPLAY="${DISPLAY}" \
+ "${VERSION_BAZEL}-real" "$@"
+fi
+if [[ -x "${VERSION_BAZEL}" ]]; then
+ exec env -i \
+ HOSTNAME="${HOSTNAME}" \
+ SHELL="${SHELL}" \
+ USER="${USER}" \
+ PATH="${PATH}" \
+ LANG="${LANG}" \
+ HOME="${HOME}" \
+ LOGNAME="${LOGNAME}" \
+ TERM="${TERM}" \
+ DISPLAY="${DISPLAY}" \
+ "${VERSION_BAZEL}" "$@"
+fi
+
+echo "Can't find the real bazel!" >&2
+exit 1
diff --git a/y2014/control_loops/drivetrain/drivetrain_base.cc b/y2014/control_loops/drivetrain/drivetrain_base.cc
index 4894a51..96b27a6 100644
--- a/y2014/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2014/control_loops/drivetrain/drivetrain_base.cc
@@ -13,6 +13,7 @@
namespace control_loops {
const DrivetrainConfig &GetDrivetrainConfig() {
+ // TODO(austin): Switch over to using the profile.
static DrivetrainConfig kDrivetrainConfig{
::frc971::control_loops::drivetrain::ShifterType::HALL_EFFECT_SHIFTER,
::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
@@ -31,8 +32,7 @@
constants::GetValues().left_drive,
constants::GetValues().right_drive,
true,
- // TODO(austin): Switch over to using the profle.
- false};
+ 0};
return kDrivetrainConfig;
};
diff --git a/y2014/control_loops/drivetrain/drivetrain_main.cc b/y2014/control_loops/drivetrain/drivetrain_main.cc
index 52dafcc..883bdd2 100644
--- a/y2014/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2014/control_loops/drivetrain/drivetrain_main.cc
@@ -7,8 +7,7 @@
int main() {
::aos::Init();
- DrivetrainLoop drivetrain =
- DrivetrainLoop(::y2014::control_loops::GetDrivetrainConfig());
+ DrivetrainLoop drivetrain(::y2014::control_loops::GetDrivetrainConfig());
drivetrain.Run();
::aos::Cleanup();
return 0;
diff --git a/y2015_bot3/actors/drivetrain_actor.cc b/y2015_bot3/actors/drivetrain_actor.cc
index 32ce93f..5a83626 100644
--- a/y2015_bot3/actors/drivetrain_actor.cc
+++ b/y2015_bot3/actors/drivetrain_actor.cc
@@ -26,7 +26,8 @@
: aos::common::actions::ActorBase<actors::DrivetrainActionQueueGroup>(s) {}
bool DrivetrainActor::RunAction(const actors::DrivetrainActionParams ¶ms) {
- static const auto K = ::y2015_bot3::control_loops::MakeDrivetrainLoop().K();
+ static const auto K =
+ ::y2015_bot3::control_loops::drivetrain::MakeDrivetrainLoop().K();
const double yoffset = params.y_offset;
const double turn_offset =
diff --git a/y2016/BUILD b/y2016/BUILD
index 9bc5cd7..4a2e768 100644
--- a/y2016/BUILD
+++ b/y2016/BUILD
@@ -1,4 +1,5 @@
load('/aos/downloader/downloader', 'aos_downloader')
+load('/aos/downloader/downloader', 'aos_downloader_dir')
cc_library(
name = 'constants',
@@ -38,6 +39,7 @@
'//frc971/control_loops/drivetrain:drivetrain_queue',
'//frc971/queues:gyro',
'//y2016/actors:autonomous_action_lib',
+ '//y2016/actors:superstructure_action_lib',
'//y2016/actors:vision_align_action_lib',
'//y2016/control_loops/shooter:shooter_queue',
'//y2016/control_loops/superstructure:superstructure_lib',
@@ -54,7 +56,9 @@
'//y2016/control_loops/drivetrain:drivetrain',
'//y2016/control_loops/superstructure:superstructure',
'//y2016/control_loops/shooter:shooter',
+ '//y2016/dashboard:dashboard',
'//y2016/actors:autonomous_action',
+ '//y2016/actors:superstructure_action',
'//y2016/actors:vision_align_action',
'//y2016/wpilib:wpilib_interface',
'//y2016/vision:target_receiver',
@@ -62,6 +66,9 @@
srcs = [
'//aos:prime_binaries',
],
+ dirs = [
+ '//y2016/dashboard:www_files',
+ ],
)
aos_downloader(
@@ -72,7 +79,9 @@
'//y2016/control_loops/drivetrain:drivetrain.stripped',
'//y2016/control_loops/superstructure:superstructure.stripped',
'//y2016/control_loops/shooter:shooter.stripped',
+ '//y2016/dashboard:dashboard.stripped',
'//y2016/actors:autonomous_action.stripped',
+ '//y2016/actors:superstructure_action.stripped',
'//y2016/actors:vision_align_action.stripped',
'//y2016/wpilib:wpilib_interface.stripped',
'//y2016/vision:target_receiver.stripped',
@@ -80,4 +89,7 @@
srcs = [
'//aos:prime_binaries_stripped',
],
+ dirs = [
+ '//y2016/dashboard:www_files',
+ ],
)
diff --git a/y2016/actors/BUILD b/y2016/actors/BUILD
index cee67c0..453d49e 100644
--- a/y2016/actors/BUILD
+++ b/y2016/actors/BUILD
@@ -122,6 +122,7 @@
'//aos/common/logging',
'//aos/common/actions:action_lib',
'//frc971/control_loops/drivetrain:drivetrain_queue',
+ '//y2016/queues:ball_detector',
'//y2016/control_loops/superstructure:superstructure_queue',
'//y2016/control_loops/shooter:shooter_queue',
'//y2016/control_loops/drivetrain:drivetrain_base',
diff --git a/y2016/actors/autonomous_actor.cc b/y2016/actors/autonomous_actor.cc
index 9024335..199dda5 100644
--- a/y2016/actors/autonomous_actor.cc
+++ b/y2016/actors/autonomous_actor.cc
@@ -12,6 +12,7 @@
#include "y2016/control_loops/shooter/shooter.q.h"
#include "y2016/control_loops/superstructure/superstructure.q.h"
#include "y2016/actors/autonomous_action.q.h"
+#include "y2016/queues/ball_detector.q.h"
#include "y2016/vision/vision.q.h"
namespace y2016 {
@@ -28,8 +29,16 @@
const ProfileParameters kSlowTurn = {0.8, 3.0};
const ProfileParameters kFastTurn = {3.0, 10.0};
+const ProfileParameters kStealTurn = {4.0, 15.0};
+const ProfileParameters kSwerveTurn = {2.0, 7.0};
+const ProfileParameters kFinishTurn = {2.0, 5.0};
-const double kDistanceShort = 0.25;
+const ProfileParameters kTwoBallLowDrive = {1.7, 3.5};
+const ProfileParameters kTwoBallFastDrive = {3.0, 1.5};
+const ProfileParameters kTwoBallReturnDrive = {3.0, 1.9};
+const ProfileParameters kTwoBallReturnSlow = {3.0, 2.5};
+const ProfileParameters kTwoBallBallPickup = {2.0, 1.75};
+const ProfileParameters kTwoBallBallPickupAccel = {2.0, 2.5};
} // namespace
AutonomousActor::AutonomousActor(actors::AutonomousActionQueueGroup *s)
@@ -55,6 +64,7 @@
ProfileParameters linear,
ProfileParameters angular) {
{
+ LOG(INFO, "Driving distance %f, angle %f\n", distance, angle);
{
const double dangle = angle * dt_config_.robot_radius;
initial_drivetrain_.left += distance - dangle;
@@ -103,6 +113,8 @@
}
}
+constexpr double kDoNotTurnCare = 2.0;
+
bool AutonomousActor::WaitForDriveNear(double distance, double angle) {
::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
::aos::time::Time::InMS(5) / 2);
@@ -151,11 +163,9 @@
}
}
-bool AutonomousActor::WaitForDriveDone() {
+bool AutonomousActor::WaitForDriveProfileDone() {
::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
::aos::time::Time::InMS(5) / 2);
- constexpr double kPositionTolerance = 0.02;
- constexpr double kVelocityTolerance = 0.10;
constexpr double kProfileTolerance = 0.001;
while (true) {
@@ -168,15 +178,7 @@
if (::std::abs(drivetrain_queue.status->profiled_left_position_goal -
initial_drivetrain_.left) < kProfileTolerance &&
::std::abs(drivetrain_queue.status->profiled_right_position_goal -
- initial_drivetrain_.right) < kProfileTolerance &&
- ::std::abs(drivetrain_queue.status->estimated_left_position -
- initial_drivetrain_.left) < kPositionTolerance &&
- ::std::abs(drivetrain_queue.status->estimated_right_position -
- initial_drivetrain_.right) < kPositionTolerance &&
- ::std::abs(drivetrain_queue.status->estimated_left_velocity) <
- kVelocityTolerance &&
- ::std::abs(drivetrain_queue.status->estimated_right_velocity) <
- kVelocityTolerance) {
+ initial_drivetrain_.right) < kProfileTolerance) {
LOG(INFO, "Finished drive\n");
return true;
}
@@ -184,11 +186,117 @@
}
}
+bool AutonomousActor::WaitForMaxBy(double angle) {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ double max_angle = -M_PI;
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return true;
+ }
+ if (drivetrain_queue.status.get()) {
+ if (drivetrain_queue.status->ground_angle > max_angle) {
+ max_angle = drivetrain_queue.status->ground_angle;
+ }
+ if (drivetrain_queue.status->ground_angle < max_angle - angle) {
+ return true;
+ }
+ }
+ }
+}
+
+bool AutonomousActor::WaitForAboveAngle(double angle) {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return true;
+ }
+ if (drivetrain_queue.status.get()) {
+ if (drivetrain_queue.status->ground_angle > angle) {
+ return true;
+ }
+ }
+ }
+}
+
+bool AutonomousActor::WaitForBelowAngle(double angle) {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return true;
+ }
+ if (drivetrain_queue.status.get()) {
+ if (drivetrain_queue.status->ground_angle < angle) {
+ return true;
+ }
+ }
+ }
+}
+
+bool AutonomousActor::IsDriveDone() {
+ constexpr double kPositionTolerance = 0.02;
+ constexpr double kVelocityTolerance = 0.10;
+ constexpr double kProfileTolerance = 0.001;
+
+ if (drivetrain_queue.status.get()) {
+ if (::std::abs(drivetrain_queue.status->profiled_left_position_goal -
+ initial_drivetrain_.left) < kProfileTolerance &&
+ ::std::abs(drivetrain_queue.status->profiled_right_position_goal -
+ initial_drivetrain_.right) < kProfileTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_left_position -
+ initial_drivetrain_.left) < kPositionTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_right_position -
+ initial_drivetrain_.right) < kPositionTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_left_velocity) <
+ kVelocityTolerance &&
+ ::std::abs(drivetrain_queue.status->estimated_right_velocity) <
+ kVelocityTolerance) {
+ LOG(INFO, "Finished drive\n");
+ return true;
+ }
+ }
+ return false;
+}
+
+bool AutonomousActor::WaitForDriveDone() {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return true;
+ }
+ }
+}
+
void AutonomousActor::MoveSuperstructure(
double intake, double shoulder, double wrist,
const ProfileParameters intake_params,
const ProfileParameters shoulder_params,
- const ProfileParameters wrist_params, bool traverse_up) {
+ const ProfileParameters wrist_params, bool traverse_up,
+ double roller_power) {
superstructure_goal_ = {intake, shoulder, wrist};
auto new_superstructure_goal =
@@ -212,17 +320,45 @@
new_superstructure_goal->max_angular_acceleration_wrist =
wrist_params.max_acceleration;
- new_superstructure_goal->voltage_top_rollers = 0.0;
- new_superstructure_goal->voltage_bottom_rollers = 0.0;
+ new_superstructure_goal->voltage_top_rollers = roller_power;
+ new_superstructure_goal->voltage_bottom_rollers = roller_power;
new_superstructure_goal->traverse_unlatched = true;
new_superstructure_goal->traverse_down = !traverse_up;
+ new_superstructure_goal->voltage_climber = 0.0;
+ new_superstructure_goal->unfold_climber = false;
if (!new_superstructure_goal.Send()) {
LOG(ERROR, "Sending superstructure goal failed.\n");
}
}
+void AutonomousActor::OpenShooter() {
+ shooter_speed_ = 0.0;
+
+ if (!control_loops::shooter::shooter_queue.goal.MakeWithBuilder()
+ .angular_velocity(shooter_speed_)
+ .clamp_open(true)
+ .push_to_shooter(false)
+ .force_lights_on(false)
+ .Send()) {
+ LOG(ERROR, "Sending shooter goal failed.\n");
+ }
+}
+
+void AutonomousActor::CloseShooter() {
+ shooter_speed_ = 0.0;
+
+ if (!control_loops::shooter::shooter_queue.goal.MakeWithBuilder()
+ .angular_velocity(shooter_speed_)
+ .clamp_open(false)
+ .push_to_shooter(false)
+ .force_lights_on(false)
+ .Send()) {
+ LOG(ERROR, "Sending shooter goal failed.\n");
+ }
+}
+
void AutonomousActor::SetShooterSpeed(double speed) {
shooter_speed_ = speed;
@@ -300,7 +436,8 @@
vision_action_->Start();
}
-void AutonomousActor::WaitForAlignedWithVision() {
+void AutonomousActor::WaitForAlignedWithVision(
+ ::aos::time::Time align_duration) {
bool vision_valid = false;
double last_angle = 0.0;
int ready_to_fire = 0;
@@ -308,7 +445,7 @@
::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
::aos::time::Time::InMS(5) / 2);
::aos::time::Time end_time =
- ::aos::time::Time::Now() + aos::time::Time::InSeconds(3);
+ ::aos::time::Time::Now() + align_duration;
while (end_time > ::aos::time::Time::Now()) {
if (ShouldCancel()) break;
@@ -344,8 +481,9 @@
} else {
ready_to_fire = 0;
}
- if (ready_to_fire > 9) {
+ if (ready_to_fire > 15) {
break;
+ LOG(INFO, "Vision align success!\n");
}
}
phased_loop.SleepUntilNext();
@@ -353,15 +491,106 @@
vision_action_->Cancel();
WaitUntilDoneOrCanceled(::std::move(vision_action_));
+ LOG(INFO, "Done waiting for vision\n");
+}
+
+bool AutonomousActor::IntakeDone() {
+ control_loops::superstructure_queue.status.FetchAnother();
+
+ constexpr double kProfileError = 1e-5;
+ constexpr double kEpsilon = 0.15;
+
+ if (control_loops::superstructure_queue.status->state < 12 ||
+ control_loops::superstructure_queue.status->state == 16) {
+ LOG(ERROR, "Superstructure no longer running, aborting action\n");
+ return true;
+ }
+
+ if (::std::abs(control_loops::superstructure_queue.status->intake.goal_angle -
+ superstructure_goal_.intake) < kProfileError &&
+ ::std::abs(control_loops::superstructure_queue.status->intake
+ .goal_angular_velocity) < kProfileError) {
+ LOG(DEBUG, "Profile done.\n");
+ if (::std::abs(control_loops::superstructure_queue.status->intake.angle -
+ superstructure_goal_.intake) < kEpsilon &&
+ ::std::abs(control_loops::superstructure_queue.status->intake
+ .angular_velocity) < kEpsilon) {
+ LOG(INFO, "Near goal, done.\n");
+ return true;
+ }
+ }
+ return false;
+}
+
+bool AutonomousActor::SuperstructureProfileDone() {
+ constexpr double kProfileError = 1e-5;
+ return ::std::abs(
+ control_loops::superstructure_queue.status->intake.goal_angle -
+ superstructure_goal_.intake) < kProfileError &&
+ ::std::abs(
+ control_loops::superstructure_queue.status->shoulder.goal_angle -
+ superstructure_goal_.shoulder) < kProfileError &&
+ ::std::abs(
+ control_loops::superstructure_queue.status->wrist.goal_angle -
+ superstructure_goal_.wrist) < kProfileError &&
+ ::std::abs(control_loops::superstructure_queue.status->intake
+ .goal_angular_velocity) < kProfileError &&
+ ::std::abs(control_loops::superstructure_queue.status->shoulder
+ .goal_angular_velocity) < kProfileError &&
+ ::std::abs(control_loops::superstructure_queue.status->wrist
+ .goal_angular_velocity) < kProfileError;
+}
+
+bool AutonomousActor::SuperstructureDone() {
+ control_loops::superstructure_queue.status.FetchAnother();
+
+ constexpr double kEpsilon = 0.03;
+
+ if (control_loops::superstructure_queue.status->state < 12 ||
+ control_loops::superstructure_queue.status->state == 16) {
+ LOG(ERROR, "Superstructure no longer running, aborting action\n");
+ return true;
+ }
+
+ if (SuperstructureProfileDone()) {
+ LOG(DEBUG, "Profile done.\n");
+ if (::std::abs(control_loops::superstructure_queue.status->intake.angle -
+ superstructure_goal_.intake) < (kEpsilon + 0.1) &&
+ ::std::abs(control_loops::superstructure_queue.status->shoulder.angle -
+ superstructure_goal_.shoulder) < (kEpsilon + 0.05) &&
+ ::std::abs(control_loops::superstructure_queue.status->wrist.angle -
+ superstructure_goal_.wrist) < (kEpsilon + 0.01) &&
+ ::std::abs(control_loops::superstructure_queue.status->intake
+ .angular_velocity) < (kEpsilon + 0.1) &&
+ ::std::abs(control_loops::superstructure_queue.status->shoulder
+ .angular_velocity) < (kEpsilon + 0.10) &&
+ ::std::abs(control_loops::superstructure_queue.status->wrist
+ .angular_velocity) < (kEpsilon + 0.05)) {
+ LOG(INFO, "Near goal, done.\n");
+ return true;
+ }
+ }
+ return false;
+}
+
+void AutonomousActor::WaitForIntake() {
+ while (true) {
+ if (ShouldCancel()) return;
+ if (IntakeDone()) return;
+ }
}
void AutonomousActor::WaitForSuperstructure() {
while (true) {
if (ShouldCancel()) return;
- control_loops::superstructure_queue.status.FetchAnother();
+ if (SuperstructureDone()) return;
+ }
+}
- constexpr double kProfileError = 1e-5;
- constexpr double kEpsilon = 0.03;
+void AutonomousActor::WaitForSuperstructureProfile() {
+ while (true) {
+ if (ShouldCancel()) return;
+ control_loops::superstructure_queue.status.FetchAnother();
if (control_loops::superstructure_queue.status->state < 12 ||
control_loops::superstructure_queue.status->state == 16) {
@@ -369,75 +598,81 @@
return;
}
- if (::std::abs(
- control_loops::superstructure_queue.status->intake.goal_angle -
- superstructure_goal_.intake) < kProfileError &&
- ::std::abs(
- control_loops::superstructure_queue.status->shoulder.goal_angle -
- superstructure_goal_.shoulder) < kProfileError &&
- ::std::abs(
- control_loops::superstructure_queue.status->wrist.goal_angle -
- superstructure_goal_.wrist) < kProfileError &&
- ::std::abs(control_loops::superstructure_queue.status->intake
- .goal_angular_velocity) < kProfileError &&
- ::std::abs(control_loops::superstructure_queue.status->shoulder
- .goal_angular_velocity) < kProfileError &&
- ::std::abs(control_loops::superstructure_queue.status->wrist
- .goal_angular_velocity) < kProfileError) {
- LOG(INFO, "Profile done.\n");
- if (::std::abs(control_loops::superstructure_queue.status->intake.angle -
- superstructure_goal_.intake) < kEpsilon &&
- ::std::abs(
- control_loops::superstructure_queue.status->shoulder.angle -
- superstructure_goal_.shoulder) < kEpsilon &&
- ::std::abs(control_loops::superstructure_queue.status->wrist.angle -
- superstructure_goal_.wrist) < kEpsilon &&
- ::std::abs(control_loops::superstructure_queue.status->intake
- .angular_velocity) < kEpsilon &&
- ::std::abs(control_loops::superstructure_queue.status->shoulder
- .angular_velocity) < kEpsilon &&
- ::std::abs(control_loops::superstructure_queue.status->wrist
- .angular_velocity) < kEpsilon) {
- LOG(INFO, "Near goal, done.\n");
- return;
- }
+ if (SuperstructureProfileDone()) return;
+ }
+}
+
+void AutonomousActor::WaitForSuperstructureLow() {
+ while (true) {
+ if (ShouldCancel()) return;
+ control_loops::superstructure_queue.status.FetchAnother();
+
+ if (control_loops::superstructure_queue.status->state < 12 ||
+ control_loops::superstructure_queue.status->state == 16) {
+ LOG(ERROR, "Superstructure no longer running, aborting action\n");
+ return;
+ }
+ if (SuperstructureProfileDone()) return;
+ if (control_loops::superstructure_queue.status->shoulder.angle < 0.1) {
+ return;
}
}
}
+void AutonomousActor::BackLongShotLowBarTwoBall() {
+ LOG(INFO, "Expanding for back long shot\n");
+ MoveSuperstructure(0.00, M_PI / 2.0 - 0.2, -0.55, {7.0, 40.0}, {4.0, 6.0},
+ {10.0, 25.0}, false, 0.0);
+}
+
+void AutonomousActor::BackLongShotTwoBall() {
+ LOG(INFO, "Expanding for back long shot\n");
+ MoveSuperstructure(0.00, M_PI / 2.0 - 0.2, -0.55, {7.0, 40.0}, {4.0, 6.0},
+ {10.0, 25.0}, false, 0.0);
+}
+
+void AutonomousActor::BackLongShotTwoBallFinish() {
+ LOG(INFO, "Expanding for back long shot\n");
+ MoveSuperstructure(0.00, M_PI / 2.0 - 0.2, -0.625, {7.0, 40.0}, {4.0, 6.0},
+ {10.0, 25.0}, false, 0.0);
+}
+
void AutonomousActor::BackLongShot() {
LOG(INFO, "Expanding for back long shot\n");
- MoveSuperstructure(-0.05, M_PI / 2.0 - 0.2, -0.62, {7.0, 40.0}, {4.0, 10.0},
- {10.0, 25.0}, false);
+ MoveSuperstructure(0.80, M_PI / 2.0 - 0.2, -0.62, {7.0, 40.0}, {4.0, 6.0},
+ {10.0, 25.0}, false, 0.0);
}
void AutonomousActor::BackMiddleShot() {
LOG(INFO, "Expanding for back middle shot\n");
MoveSuperstructure(-0.05, M_PI / 2.0 - 0.2, -0.665, {7.0, 40.0}, {4.0, 10.0},
- {10.0, 25.0}, false);
+ {10.0, 25.0}, false, 0.0);
+}
+
+void AutonomousActor::FrontLongShot() {
+ LOG(INFO, "Expanding for front long shot\n");
+ MoveSuperstructure(0.80, M_PI / 2.0 + 0.1, M_PI + 0.41 + 0.02, {7.0, 40.0},
+ {4.0, 6.0}, {10.0, 25.0}, false, 0.0);
+}
+
+void AutonomousActor::FrontMiddleShot() {
+ LOG(INFO, "Expanding for front middle shot\n");
+ MoveSuperstructure(-0.05, M_PI / 2.0 + 0.1, M_PI + 0.44, {7.0, 40.0},
+ {4.0, 10.0}, {10.0, 25.0}, true, 0.0);
}
void AutonomousActor::TuckArm(bool low_bar, bool traverse_down) {
MoveSuperstructure(low_bar ? -0.05 : 2.0, -0.010, 0.0, {7.0, 40.0},
- {4.0, 10.0}, {10.0, 25.0}, !traverse_down);
+ {4.0, 10.0}, {10.0, 25.0}, !traverse_down, 0.0);
}
-void AutonomousActor::DoFullShot(bool center) {
- // Get the superstructure to unfold and get ready for shooting.
- LOG(INFO, "Unfolding superstructure\n");
- if (center) {
- BackMiddleShot();
- } else {
- BackLongShot();
- }
-
- // Spin up the shooter wheels.
- LOG(INFO, "Spinning up the shooter wheels\n");
- SetShooterSpeed(640.0);
-
+void AutonomousActor::DoFullShot() {
if (ShouldCancel()) return;
// Make sure that the base is aligned with the base.
LOG(INFO, "Waiting for the superstructure\n");
WaitForSuperstructure();
+
+ ::aos::time::SleepFor(::aos::time::Time::InSeconds(0.5));
+
if (ShouldCancel()) return;
LOG(INFO, "Triggering the vision actor\n");
AlignWithVisionGoal();
@@ -445,12 +680,13 @@
// Wait for the drive base to be aligned with the target and make sure that
// the shooter is up to speed.
LOG(INFO, "Waiting for vision to be aligned\n");
- WaitForAlignedWithVision();
+ WaitForAlignedWithVision(aos::time::Time::InSeconds(2));
if (ShouldCancel()) return;
LOG(INFO, "Waiting for shooter to be up to speed\n");
WaitForShooterSpeed();
if (ShouldCancel()) return;
+ ::aos::time::SleepFor(::aos::time::Time::InSeconds(0.3));
LOG(INFO, "Shoot!\n");
Shoot();
@@ -463,7 +699,7 @@
// Wait for everything to be folded up.
LOG(INFO, "Waiting for superstructure to be folded back down\n");
- WaitForSuperstructure();
+ WaitForSuperstructureLow();
}
void AutonomousActor::LowBarDrive() {
@@ -486,46 +722,306 @@
StartDrive(0, -M_PI / 4.0 - 0.2, kLowBarDrive, kSlowTurn);
}
+void AutonomousActor::TippyDrive(double goal_distance, double tip_distance,
+ double below, double above) {
+ StartDrive(goal_distance, 0.0, kMoatDrive, kSlowTurn);
+ if (!WaitForBelowAngle(below)) return;
+ if (!WaitForAboveAngle(above)) return;
+ // Ok, we are good now. Compensate by moving the goal by the error.
+ // Should be here at 2.7
+ drivetrain_queue.status.FetchLatest();
+ if (drivetrain_queue.status.get()) {
+ const double left_error =
+ (initial_drivetrain_.left -
+ drivetrain_queue.status->estimated_left_position);
+ const double right_error =
+ (initial_drivetrain_.right -
+ drivetrain_queue.status->estimated_right_position);
+ const double distance_to_go = (left_error + right_error) / 2.0;
+ const double distance_compensation =
+ goal_distance - tip_distance - distance_to_go;
+ LOG(INFO, "Going %f further at the bump\n", distance_compensation);
+ StartDrive(distance_compensation, 0.0, kMoatDrive, kSlowTurn);
+ }
+}
+
void AutonomousActor::MiddleDrive() {
TuckArm(false, false);
- StartDrive(4.7, 0.0, kMoatDrive, kSlowTurn);
+ TippyDrive(3.65, 2.7, -0.2, 0.0);
if (!WaitForDriveDone()) return;
- StartDrive(0.0, M_PI, kMoatDrive, kFastTurn);
}
void AutonomousActor::OneFromMiddleDrive(bool left) {
- const double kTurnAngle = left ? M_PI / 2.0 - 0.40 : (-M_PI / 2.0 + 0.40);
- const double kFlipTurnAngle =
- left ? (M_PI - kTurnAngle) : (-M_PI - kTurnAngle);
+ const double kTurnAngle = left ? -0.41 : 0.41;
TuckArm(false, false);
- StartDrive(5.0 - kDistanceShort, 0.0, kMoatDrive, kFastTurn);
- if (!WaitForDriveDone()) return;
- StartDrive(0.0, kTurnAngle, kRealignDrive, kFastTurn);
- if (!WaitForDriveDone()) return;
- StartDrive(-1.3, 0.0, kRealignDrive, kFastTurn);
- if (!WaitForDriveDone()) return;
- StartDrive(0.0, kFlipTurnAngle, kRealignDrive, kFastTurn);
+ TippyDrive(4.05, 2.7, -0.2, 0.0);
if (!WaitForDriveDone()) return;
- StartDrive(0.3, 0.0, kRealignDrive, kFastTurn);
+ StartDrive(0.0, kTurnAngle, kRealignDrive, kFastTurn);
}
void AutonomousActor::TwoFromMiddleDrive() {
- const double kTurnAngle = M_PI / 2.0 - 0.13;
TuckArm(false, false);
- StartDrive(5.0 - kDistanceShort, 0.0, kMoatDrive, kFastTurn);
- if (!WaitForDriveDone()) return;
- StartDrive(0.0, kTurnAngle, kMoatDrive, kFastTurn);
- if (!WaitForDriveDone()) return;
- StartDrive(-2.6, 0.0, kRealignDrive, kFastTurn);
- if (!WaitForDriveDone()) return;
- StartDrive(0.0, M_PI - kTurnAngle, kMoatDrive, kFastTurn);
+ constexpr double kDriveDistance = 5.10;
+ TippyDrive(kDriveDistance, 2.7, -0.2, 0.0);
+
+ if (!WaitForDriveNear(kDriveDistance - 3.0, 2.0)) return;
+ StartDrive(0, -M_PI / 2 - 0.10, kMoatDrive, kFastTurn);
if (!WaitForDriveDone()) return;
- StartDrive(0.3, 0.0, kRealignDrive, kFastTurn);
+ StartDrive(0, M_PI / 3 + 0.35, kMoatDrive, kFastTurn);
+}
+
+void AutonomousActor::CloseIfBall() {
+ ::y2016::sensors::ball_detector.FetchLatest();
+ if (::y2016::sensors::ball_detector.get()) {
+ const bool ball_detected = ::y2016::sensors::ball_detector->voltage > 2.5;
+ if (ball_detected) {
+ CloseShooter();
+ }
+ }
+}
+
+void AutonomousActor::WaitForBallOrDriveDone() {
+ ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
+ ::aos::time::Time::InMS(5) / 2);
+ while (true) {
+ if (ShouldCancel()) {
+ return;
+ }
+ phased_loop.SleepUntilNext();
+ drivetrain_queue.status.FetchLatest();
+ if (IsDriveDone()) {
+ return;
+ }
+
+ ::y2016::sensors::ball_detector.FetchLatest();
+ if (::y2016::sensors::ball_detector.get()) {
+ const bool ball_detected = ::y2016::sensors::ball_detector->voltage > 2.5;
+ if (ball_detected) {
+ return;
+ }
+ }
+ }
+}
+
+void AutonomousActor::WaitForBall() {
+ while (true) {
+ ::y2016::sensors::ball_detector.FetchAnother();
+ if (::y2016::sensors::ball_detector.get()) {
+ const bool ball_detected = ::y2016::sensors::ball_detector->voltage > 2.5;
+ if (ball_detected) {
+ return;
+ }
+ if (ShouldCancel()) return;
+ }
+ }
+}
+
+void AutonomousActor::TwoBallAuto() {
+ aos::time::Time start_time = aos::time::Time::Now();
+ OpenShooter();
+ MoveSuperstructure(0.10, -0.010, 0.0, {8.0, 60.0}, {4.0, 10.0}, {10.0, 25.0},
+ false, 12.0);
+ if (ShouldCancel()) return;
+ LOG(INFO, "Waiting for the intake to come down.\n");
+
+ WaitForIntake();
+ LOG(INFO, "Intake done at %f seconds, starting to drive\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ if (ShouldCancel()) return;
+ const double kDriveDistance = 5.05;
+ StartDrive(-kDriveDistance, 0.0, kTwoBallLowDrive, kSlowTurn);
+
+ StartDrive(0.0, 0.4, kTwoBallLowDrive, kSwerveTurn);
+ if (!WaitForDriveNear(kDriveDistance - 0.5, kDoNotTurnCare)) return;
+
+ // Check if the ball is there.
+ bool first_ball_there = true;
+ ::y2016::sensors::ball_detector.FetchLatest();
+ if (::y2016::sensors::ball_detector.get()) {
+ const bool ball_detected = ::y2016::sensors::ball_detector->voltage > 2.5;
+ first_ball_there = ball_detected;
+ LOG(INFO, "Saw the ball: %d at %f\n", first_ball_there,
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ }
+ MoveSuperstructure(0.10, -0.010, 0.0, {8.0, 40.0}, {4.0, 10.0}, {10.0, 25.0},
+ false, 0.0);
+ LOG(INFO, "Shutting off rollers at %f seconds, starting to straighten out\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ StartDrive(0.0, -0.4, kTwoBallLowDrive, kSwerveTurn);
+ MoveSuperstructure(-0.05, -0.010, 0.0, {8.0, 40.0}, {4.0, 10.0}, {10.0, 25.0},
+ false, 0.0);
+ CloseShooter();
+ if (!WaitForDriveNear(kDriveDistance - 2.4, kDoNotTurnCare)) return;
+
+ // We are now under the low bar. Start lifting.
+ BackLongShotLowBarTwoBall();
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(640.0);
+ StartDrive(0.0, 0.0, kTwoBallFastDrive, kSwerveTurn);
+
+ if (!WaitForDriveNear(1.50, kDoNotTurnCare)) return;
+ constexpr double kShootTurnAngle = -M_PI / 4.0 - 0.05;
+ StartDrive(0, kShootTurnAngle, kTwoBallFastDrive, kFinishTurn);
+ BackLongShotTwoBall();
+
+ if (!WaitForDriveDone()) return;
+ LOG(INFO, "First shot done driving at %f seconds\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+
+ WaitForSuperstructureProfile();
+
+ if (ShouldCancel()) return;
+ AlignWithVisionGoal();
+
+ WaitForShooterSpeed();
+ if (ShouldCancel()) return;
+
+ constexpr double kVisionExtra = 0.0;
+ WaitForAlignedWithVision(aos::time::Time::InSeconds(0.5 + kVisionExtra));
+ BackLongShotTwoBallFinish();
+ WaitForSuperstructureProfile();
+ if (ShouldCancel()) return;
+ LOG(INFO, "Shoot!\n");
+ if (first_ball_there) {
+ Shoot();
+ } else {
+ LOG(INFO, "Nah, not shooting\n");
+ }
+
+ LOG(INFO, "First shot at %f seconds\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ if (ShouldCancel()) return;
+
+ SetShooterSpeed(0.0);
+ LOG(INFO, "Folding superstructure back down\n");
+ TuckArm(true, true);
+
+ // Undo vision move.
+ StartDrive(0.0, 0.0, kTwoBallFastDrive, kFinishTurn);
+ if (!WaitForDriveDone()) return;
+
+ constexpr double kBackDrive = 3.09 - 0.4;
+ StartDrive(kBackDrive, 0.0, kTwoBallReturnDrive, kSlowTurn);
+ if (!WaitForDriveNear(kBackDrive - 0.19, kDoNotTurnCare)) return;
+ StartDrive(0, -kShootTurnAngle, kTwoBallReturnDrive, kSwerveTurn);
+ if (!WaitForDriveNear(1.0, kDoNotTurnCare)) return;
+ StartDrive(0, 0, kTwoBallReturnSlow, kSwerveTurn);
+
+ if (!WaitForDriveNear(0.06, kDoNotTurnCare)) return;
+ LOG(INFO, "At Low Bar %f\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+
+ OpenShooter();
+ constexpr double kSecondBallAfterBarDrive = 2.10;
+ StartDrive(kSecondBallAfterBarDrive, 0.0, kTwoBallBallPickupAccel, kSlowTurn);
+ if (!WaitForDriveNear(kSecondBallAfterBarDrive - 0.5, kDoNotTurnCare)) return;
+ constexpr double kBallSmallWallTurn = -0.11;
+ StartDrive(0, kBallSmallWallTurn, kTwoBallBallPickup, kFinishTurn);
+
+ MoveSuperstructure(0.03, -0.010, 0.0, {8.0, 60.0}, {4.0, 10.0}, {10.0, 25.0},
+ false, 12.0);
+
+ if (!WaitForDriveProfileDone()) return;
+
+ MoveSuperstructure(0.10, -0.010, 0.0, {8.0, 60.0}, {4.0, 10.0}, {10.0, 25.0},
+ false, 12.0);
+
+ LOG(INFO, "Done backing up %f\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+
+ constexpr double kDriveBackDistance = 5.15 - 0.4;
+ StartDrive(-kDriveBackDistance, 0.0, kTwoBallLowDrive, kFinishTurn);
+ CloseIfBall();
+ if (!WaitForDriveNear(kDriveBackDistance - 0.75, kDoNotTurnCare)) return;
+
+ StartDrive(0.0, -kBallSmallWallTurn, kTwoBallLowDrive, kFinishTurn);
+ LOG(INFO, "Straightening up at %f\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+
+ CloseIfBall();
+ if (!WaitForDriveNear(kDriveBackDistance - 2.3, kDoNotTurnCare)) return;
+
+ ::y2016::sensors::ball_detector.FetchLatest();
+ if (::y2016::sensors::ball_detector.get()) {
+ const bool ball_detected = ::y2016::sensors::ball_detector->voltage > 2.5;
+ if (!ball_detected) {
+ if (!WaitForDriveDone()) return;
+ LOG(INFO, "Aborting, no ball %f\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ return;
+ }
+ }
+ CloseShooter();
+
+ BackLongShotLowBarTwoBall();
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(640.0);
+ StartDrive(0.0, 0.0, kTwoBallFastDrive, kSwerveTurn);
+
+ if (!WaitForDriveNear(1.80, kDoNotTurnCare)) return;
+ StartDrive(0, kShootTurnAngle, kTwoBallFastDrive, kFinishTurn);
+ BackLongShotTwoBall();
+
+ if (!WaitForDriveDone()) return;
+ LOG(INFO, "Second shot done driving at %f seconds\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ WaitForSuperstructure();
+ AlignWithVisionGoal();
+ if (ShouldCancel()) return;
+
+ WaitForShooterSpeed();
+ if (ShouldCancel()) return;
+
+ // 2.2 with 0.4 of vision.
+ // 1.8 without any vision.
+ LOG(INFO, "Going to vision align at %f\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ WaitForAlignedWithVision(start_time + aos::time::Time::InSeconds(13.5 + kVisionExtra * 2) -
+ aos::time::Time::Now());
+ BackLongShotTwoBallFinish();
+ WaitForSuperstructureProfile();
+ if (ShouldCancel()) return;
+ LOG(INFO, "Shoot at %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
+ Shoot();
+
+ LOG(INFO, "Second shot at %f seconds\n",
+ (aos::time::Time::Now() - start_time).ToSeconds());
+ if (ShouldCancel()) return;
+
+ SetShooterSpeed(0.0);
+ LOG(INFO, "Folding superstructure back down\n");
+ TuckArm(true, false);
+ LOG(INFO, "Shot %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
+
+ WaitForSuperstructureLow();
+
+ LOG(INFO, "Done %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
+}
+
+void AutonomousActor::StealAndMoveOverBy(double distance) {
+ OpenShooter();
+ MoveSuperstructure(0.10, -0.010, 0.0, {8.0, 60.0}, {4.0, 10.0}, {10.0, 25.0},
+ true, 12.0);
+ if (ShouldCancel()) return;
+ LOG(INFO, "Waiting for the intake to come down.\n");
+
+ WaitForIntake();
+ if (ShouldCancel()) return;
+ StartDrive(-distance, M_PI / 2.0, kFastDrive, kStealTurn);
+ WaitForBallOrDriveDone();
+ if (ShouldCancel()) return;
+ MoveSuperstructure(1.0, -0.010, 0.0, {8.0, 60.0}, {4.0, 10.0}, {10.0, 25.0},
+ true, 12.0);
+
+ if (!WaitForDriveDone()) return;
+ StartDrive(0.0, M_PI / 2.0, kFastDrive, kStealTurn);
+ if (!WaitForDriveDone()) return;
}
bool AutonomousActor::RunAction(const actors::AutonomousActionParams ¶ms) {
+ aos::time::Time start_time = aos::time::Time::Now();
LOG(INFO, "Starting autonomous action with mode %" PRId32 "\n", params.mode);
InitializeEncoders();
@@ -534,27 +1030,139 @@
switch (params.mode) {
case 0:
LowBarDrive();
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontLongShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(640.0);
+
break;
case 1:
TwoFromMiddleDrive();
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
break;
case 2:
OneFromMiddleDrive(true);
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
break;
case 3:
MiddleDrive();
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
break;
case 4:
OneFromMiddleDrive(false);
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
break;
+ case 5:
+ TwoBallAuto();
+ return true;
+ break;
+ case 6:
+ StealAndMoveOverBy(3.10 + 2 * 52 * 2.54 / 100.0);
+ if (ShouldCancel()) return true;
+
+ TwoFromMiddleDrive();
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
+ break;
+ case 7:
+ StealAndMoveOverBy(2.95 + 52 * 2.54 / 100.0);
+ if (ShouldCancel()) return true;
+
+ OneFromMiddleDrive(true);
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
+ break;
+ case 8: {
+ StealAndMoveOverBy(2.95);
+ if (ShouldCancel()) return true;
+
+ MiddleDrive();
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
+ } break;
+ case 9: {
+ StealAndMoveOverBy(1.70);
+ if (ShouldCancel()) return true;
+
+ OneFromMiddleDrive(false);
+ if (!WaitForDriveDone()) return true;
+ // Get the superstructure to unfold and get ready for shooting.
+ LOG(INFO, "Unfolding superstructure\n");
+ FrontMiddleShot();
+
+ // Spin up the shooter wheels.
+ LOG(INFO, "Spinning up the shooter wheels\n");
+ SetShooterSpeed(600.0);
+
+ } break;
default:
LOG(ERROR, "Invalid auto mode %d\n", params.mode);
return true;
}
+ DoFullShot();
+
+ StartDrive(0.5, 0.0, kMoatDrive, kFastTurn);
if (!WaitForDriveDone()) return true;
- DoFullShot(params.mode != 0);
+ LOG(INFO, "Done %f\n", (aos::time::Time::Now() - start_time).ToSeconds());
::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
::aos::time::Time::InMS(5) / 2);
diff --git a/y2016/actors/autonomous_actor.h b/y2016/actors/autonomous_actor.h
index 15ed95d..9a26731 100644
--- a/y2016/actors/autonomous_actor.h
+++ b/y2016/actors/autonomous_actor.h
@@ -33,6 +33,17 @@
// Waits for the drive motion to finish. Returns true if it succeeded, and
// false if it cancels.
bool WaitForDriveDone();
+ void WaitForBallOrDriveDone();
+
+ void StealAndMoveOverBy(double distance);
+
+ // Returns true if the drive has finished.
+ bool IsDriveDone();
+ // Waits until the robot is pitched up above the specified angle, or the move
+ // finishes. Returns true on success, and false if it cancels.
+ bool WaitForAboveAngle(double angle);
+ bool WaitForBelowAngle(double angle);
+ bool WaitForMaxBy(double angle);
// Waits until the profile and distance is within distance and angle of the
// goal. Returns true on success, and false when canceled.
@@ -60,14 +71,32 @@
const ProfileParameters intake_params,
const ProfileParameters shoulder_params,
const ProfileParameters wrist_params,
- bool traverse_up);
+ bool traverse_up, double roller_power);
void WaitForSuperstructure();
+ void WaitForSuperstructureProfile();
+ void WaitForSuperstructureLow();
+ void WaitForIntake();
+ bool IntakeDone();
+ bool WaitForDriveProfileDone();
+ void FrontLongShot();
+ void FrontMiddleShot();
void BackLongShot();
+ void BackLongShotTwoBall();
+ void BackLongShotTwoBallFinish();
+ void BackLongShotLowBarTwoBall();
void BackMiddleShot();
+ void WaitForBall();
void TuckArm(bool arm_down, bool traverse_down);
+ void OpenShooter();
+ void CloseShooter();
+ void CloseIfBall();
+ bool SuperstructureProfileDone();
+ bool SuperstructureDone();
+ void TippyDrive(double goal_distance, double tip_distance, double below,
+ double above);
- void DoFullShot(bool center);
+ void DoFullShot();
void LowBarDrive();
// Drive to the middle spot over the middle position. Designed for the rock
// wall, rough terain, or ramparts.
@@ -82,7 +111,9 @@
void Shoot();
void AlignWithVisionGoal();
- void WaitForAlignedWithVision();
+ void WaitForAlignedWithVision(aos::time::Time align_duration);
+
+ void TwoBallAuto();
::std::unique_ptr<actors::VisionAlignAction> vision_action_;
};
diff --git a/y2016/actors/superstructure_action.q b/y2016/actors/superstructure_action.q
index 72bd310..231f5e7 100644
--- a/y2016/actors/superstructure_action.q
+++ b/y2016/actors/superstructure_action.q
@@ -4,7 +4,10 @@
// Parameters to send with start.
struct SuperstructureActionParams {
- double value;
+ double partial_angle;
+ double delay_time;
+ double full_angle;
+ double shooter_angle;
};
queue_group SuperstructureActionQueueGroup {
diff --git a/y2016/actors/superstructure_actor.cc b/y2016/actors/superstructure_actor.cc
index b8ad33a..c2d7c4d 100644
--- a/y2016/actors/superstructure_actor.cc
+++ b/y2016/actors/superstructure_actor.cc
@@ -1,5 +1,7 @@
#include "y2016/actors/superstructure_actor.h"
+#include <cmath>
+
#include "aos/common/util/phased_loop.h"
#include "aos/common/logging/logging.h"
#include "y2016/actors/superstructure_actor.h"
@@ -9,22 +11,94 @@
namespace actors {
SuperstructureActor::SuperstructureActor(
- actors::SuperstructureActionQueueGroup* s)
+ actors::SuperstructureActionQueueGroup *s)
: aos::common::actions::ActorBase<actors::SuperstructureActionQueueGroup>(
s) {}
bool SuperstructureActor::RunAction(
- const actors::SuperstructureActionParams& params) {
- LOG(INFO, "Starting superstructure action with value %f", params.value);
+ const actors::SuperstructureActionParams ¶ms) {
+ LOG(INFO, "Starting superstructure action\n");
- while (true) {
- control_loops::superstructure_queue.status.FetchLatest();
- ::aos::time::PhasedLoop phased_loop(::aos::time::Time::InMS(5),
- ::aos::time::Time::InMS(5) / 2);
- break;
+ MoveSuperstructure(params.partial_angle, params.shooter_angle, false);
+ WaitForSuperstructure();
+ if (ShouldCancel()) return true;
+ MoveSuperstructure(params.partial_angle, params.shooter_angle, true);
+ if (!WaitOrCancel(::aos::time::Time::InSeconds(params.delay_time))) return true;
+ MoveSuperstructure(params.full_angle, params.shooter_angle, true);
+ WaitForSuperstructure();
+ if (ShouldCancel()) return true;
+ return true;
+}
+
+void SuperstructureActor::MoveSuperstructure(double shoulder, double shooter,
+ bool unfold_climber) {
+ superstructure_goal_ = {0, shoulder, shooter};
+
+ auto new_superstructure_goal =
+ ::y2016::control_loops::superstructure_queue.goal.MakeMessage();
+
+ new_superstructure_goal->angle_intake = 0;
+ new_superstructure_goal->angle_shoulder = shoulder;
+ new_superstructure_goal->angle_wrist = shooter;
+
+ new_superstructure_goal->max_angular_velocity_intake = 7.0;
+ new_superstructure_goal->max_angular_velocity_shoulder = 4.0;
+ new_superstructure_goal->max_angular_velocity_wrist = 10.0;
+
+ new_superstructure_goal->max_angular_acceleration_intake = 40.0;
+ new_superstructure_goal->max_angular_acceleration_shoulder = 5.0;
+ new_superstructure_goal->max_angular_acceleration_wrist = 25.0;
+
+ new_superstructure_goal->voltage_top_rollers = 0;
+ new_superstructure_goal->voltage_bottom_rollers = 0;
+
+ new_superstructure_goal->traverse_unlatched = true;
+ new_superstructure_goal->traverse_down = false;
+ new_superstructure_goal->voltage_climber = 0.0;
+ new_superstructure_goal->unfold_climber = unfold_climber;
+
+ if (!new_superstructure_goal.Send()) {
+ LOG(ERROR, "Sending superstructure move failed.\n");
+ }
+}
+
+bool SuperstructureActor::SuperstructureProfileDone() {
+ constexpr double kProfileError = 1e-2;
+ return ::std::abs(
+ control_loops::superstructure_queue.status->intake.goal_angle -
+ superstructure_goal_.intake) < kProfileError &&
+ ::std::abs(
+ control_loops::superstructure_queue.status->shoulder.goal_angle -
+ superstructure_goal_.shoulder) < kProfileError &&
+ ::std::abs(control_loops::superstructure_queue.status->intake
+ .goal_angular_velocity) < kProfileError &&
+ ::std::abs(control_loops::superstructure_queue.status->shoulder
+ .goal_angular_velocity) < kProfileError;
+}
+
+bool SuperstructureActor::SuperstructureDone() {
+ control_loops::superstructure_queue.status.FetchAnother();
+
+ // We are no longer running if we are in the zeroing states (below 12), or
+ // estopped.
+ if (control_loops::superstructure_queue.status->state < 12 ||
+ control_loops::superstructure_queue.status->state == 16) {
+ LOG(ERROR, "Superstructure no longer running, aborting action\n");
+ return true;
}
- return true;
+ if (SuperstructureProfileDone()) {
+ LOG(DEBUG, "Profile done.\n");
+ return true;
+ }
+ return false;
+}
+
+void SuperstructureActor::WaitForSuperstructure() {
+ while (true) {
+ if (ShouldCancel()) return;
+ if (SuperstructureDone()) return;
+ }
}
::std::unique_ptr<SuperstructureAction> MakeSuperstructureAction(
diff --git a/y2016/actors/superstructure_actor.h b/y2016/actors/superstructure_actor.h
index b882585..4d5e372 100644
--- a/y2016/actors/superstructure_actor.h
+++ b/y2016/actors/superstructure_actor.h
@@ -13,9 +13,21 @@
class SuperstructureActor
: public ::aos::common::actions::ActorBase<SuperstructureActionQueueGroup> {
public:
- explicit SuperstructureActor(SuperstructureActionQueueGroup* s);
+ explicit SuperstructureActor(SuperstructureActionQueueGroup *s);
- bool RunAction(const actors::SuperstructureActionParams& params) override;
+ // Internal struct holding superstructure goals sent by autonomous to the
+ // loop.
+ struct SuperstructureGoal {
+ double intake;
+ double shoulder;
+ double wrist;
+ };
+ SuperstructureGoal superstructure_goal_;
+ bool RunAction(const actors::SuperstructureActionParams ¶ms) override;
+ void MoveSuperstructure(double shoulder, double shooter, bool unfold_climber);
+ void WaitForSuperstructure();
+ bool SuperstructureProfileDone();
+ bool SuperstructureDone();
};
using SuperstructureAction =
@@ -23,7 +35,7 @@
// Makes a new SuperstructureActor action.
::std::unique_ptr<SuperstructureAction> MakeSuperstructureAction(
- const ::y2016::actors::SuperstructureActionParams& params);
+ const ::y2016::actors::SuperstructureActionParams ¶ms);
} // namespace actors
} // namespace y2016
diff --git a/y2016/actors/vision_align_actor.cc b/y2016/actors/vision_align_actor.cc
index ad899be..00695f0 100644
--- a/y2016/actors/vision_align_actor.cc
+++ b/y2016/actors/vision_align_actor.cc
@@ -43,38 +43,33 @@
if (!::y2016::vision::vision_status.FetchLatest()) {
continue;
}
+ const auto &vision_status = *::y2016::vision::vision_status;
- if (!::y2016::vision::vision_status->left_image_valid ||
- !::y2016::vision::vision_status->right_image_valid) {
+ if (!vision_status.left_image_valid || !vision_status.right_image_valid) {
continue;
}
const double side_distance_change =
- ::y2016::vision::vision_status->horizontal_angle * robot_radius;
+ vision_status.horizontal_angle * robot_radius;
if (!::std::isfinite(side_distance_change)) {
continue;
}
- drivetrain_queue.status.FetchLatest();
- if (drivetrain_queue.status.get()) {
- const double left_current =
- drivetrain_queue.status->estimated_left_position;
- const double right_current =
- drivetrain_queue.status->estimated_right_position;
+ const double left_current = vision_status.drivetrain_left_position;
+ const double right_current = vision_status.drivetrain_right_position;
- if (!drivetrain_queue.goal.MakeWithBuilder()
- .steering(0.0)
- .throttle(0.0)
- .highgear(false)
- .quickturn(false)
- .control_loop_driving(true)
- .left_goal(left_current + side_distance_change)
- .right_goal(right_current - side_distance_change)
- .left_velocity_goal(0)
- .right_velocity_goal(0)
- .Send()) {
- LOG(WARNING, "sending drivetrain goal failed\n");
- }
+ if (!drivetrain_queue.goal.MakeWithBuilder()
+ .steering(0.0)
+ .throttle(0.0)
+ .highgear(false)
+ .quickturn(false)
+ .control_loop_driving(true)
+ .left_goal(left_current + side_distance_change)
+ .right_goal(right_current - side_distance_change)
+ .left_velocity_goal(0)
+ .right_velocity_goal(0)
+ .Send()) {
+ LOG(WARNING, "sending drivetrain goal failed\n");
}
}
diff --git a/y2016/constants.cc b/y2016/constants.cc
index 4f1a01e..974a82d 100644
--- a/y2016/constants.cc
+++ b/y2016/constants.cc
@@ -71,6 +71,7 @@
0.0, 0.3},
},
+ 0.0,
"practice",
};
break;
@@ -85,27 +86,28 @@
-4.550531 + 150.40906362 * M_PI / 180.0 + 0.5098 - 0.0178 - 0.0725,
{Values::kZeroingSampleSize, Values::kIntakeEncoderIndexDifference,
// Location of an index pulse.
- 0.018008, 1.5},
+ 0.018008, 2.5},
},
// Shoulder
{
// Value to add to the pot reading for the shoulder.
-1.0 - 0.0822 + 0.06138835 * M_PI / 180.0 - 0.0323 - 0.1057 +
- 0.0035 + 0.0055,
+ 0.0035 + 0.0055 - 0.001 - 0.0103 + 0.0032 - 0.0755,
{Values::kZeroingSampleSize, Values::kShoulderEncoderIndexDifference,
- 0.536989, 1.5},
+ 0.535359, 2.5},
},
// Wrist
{
// Value to add to the pot reading for the wrist.
3.2390714288298668 + -0.06138835 * M_PI / 180.0 + 0.0078 - 0.0548 -
- 0.0167 + 0.002,
+ 0.0167 + 0.002 - 0.0026 - 0.1040 - 0.0035 - 0.0012 + 0.0166 - 0.017 + 0.148 + 0.004,
{Values::kZeroingSampleSize, Values::kWristEncoderIndexDifference,
- -1.040454, 1.5},
+ -0.354946, 2.5},
},
+ 0.0,
"competition",
};
break;
@@ -117,26 +119,28 @@
{
// Hard stop is 164.2067247 degrees.
-4.2193 + (164.2067247 * M_PI / 180.0 + 0.02 - 0.0235) + 0.0549 -
- 0.104,
+ 0.104 + 0.019 - 0.938 + 0.660 - 0.002,
{Values::kZeroingSampleSize, Values::kIntakeEncoderIndexDifference,
- 0.363074, 0.3},
+ 0.332370, 1.3},
},
// Shoulder (Now calibrated at 0)
{
- -1.0016 - 0.0841 + 0.06138835 * M_PI / 180.0,
+ -1.0016 - 0.0841 + 0.06138835 * M_PI / 180.0 + 1.07838 - 1.0441 +
+ 0.0034 + 0.0065,
{Values::kZeroingSampleSize, Values::kShoulderEncoderIndexDifference,
- 0.014860, 0.3},
+ 0.126458, 1.3},
},
// Wrist
{
3.326328571170133 - 0.06138835 * M_PI / 180.0 - 0.177 + 0.0323 -
- 0.023,
+ 0.023 + 0.0488 + 0.0120 - 0.0005 - 0.0784 - 0.0010 - 0.080 + 0.1245,
{Values::kZeroingSampleSize, Values::kWristEncoderIndexDifference,
- -0.622423, 0.3},
+ -0.263227, 1.3},
},
+ 0.011,
"practice",
};
break;
diff --git a/y2016/constants.h b/y2016/constants.h
index 7416a3f..a83456c 100644
--- a/y2016/constants.h
+++ b/y2016/constants.h
@@ -33,14 +33,14 @@
// Ratios for our subsystems.
static constexpr double kShooterEncoderRatio = 1.0;
static constexpr double kIntakeEncoderRatio =
- 16.0 / 48.0 * 18.0 / 72.0 * 14.0 / 64.0;
+ 14.0 / 64.0 * 18.0 / 72.0 * 16.0 / 48.0;
static constexpr double kShoulderEncoderRatio =
- 12.0 / 42.0 * 18.0 / 72.0 * 14.0 / 64.0;
+ 14.0 / 64.0 * 18.0 / 72.0 * 12.0 / 42.0;
static constexpr double kWristEncoderRatio =
- 16.0 / 48.0 * 18.0 / 64.0 * 14.0 / 54.0;
+ 14.0 / 54.0 * 18.0 / 64.0 * 16.0 / 48.0;
- static constexpr double kIntakePotRatio = 16.0 / 48.0 * 18.0 / 72.0;
- static constexpr double kShoulderPotRatio = 16.0 / 58.0;
+ static constexpr double kIntakePotRatio = 18.0 / 72.0 * 16.0 / 48.0;
+ static constexpr double kShoulderPotRatio = 12.0 / 42.0;
static constexpr double kWristPotRatio = 16.0 / 48.0;
// Difference in radians between index pulses.
@@ -54,15 +54,15 @@
// Subsystem motion ranges, in whatever units that their respective queues say
// the use.
static constexpr ::frc971::constants::Range kIntakeRange{// Lower hard stop
- -0.4,
+ -0.5,
// Upper hard stop
- 2.75 + 0.05,
+ 2.85 + 0.05,
// Lower soft stop
-0.300,
// Uppper soft stop
2.725};
static constexpr ::frc971::constants::Range kShoulderRange{// Lower hard stop
- -0.100,
+ -0.150,
// Upper hard stop
2.8,
// Lower soft stop
@@ -70,9 +70,9 @@
// Uppper soft stop
2.0};
static constexpr ::frc971::constants::Range kWristRange{// Lower hard stop
- -2.9,
+ -3.0,
// Upper hard stop
- 2.9,
+ 3.0,
// Lower soft stop
-2.6,
// Uppper soft stop
@@ -99,6 +99,7 @@
};
Wrist wrist;
+ const double down_error;
const char *vision_name;
};
diff --git a/y2016/control_loops/drivetrain/drivetrain_base.cc b/y2016/control_loops/drivetrain/drivetrain_base.cc
index 2e64090..9aeb4c8 100644
--- a/y2016/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2016/control_loops/drivetrain/drivetrain_base.cc
@@ -36,7 +36,8 @@
drivetrain::kLowGearRatio,
kThreeStateDriveShifter,
kThreeStateDriveShifter,
- true};
+ true,
+ constants::GetValues().down_error};
return kDrivetrainConfig;
};
diff --git a/y2016/control_loops/python/arm.py b/y2016/control_loops/python/arm.py
index 75f0c59..8908038 100755
--- a/y2016/control_loops/python/arm.py
+++ b/y2016/control_loops/python/arm.py
@@ -379,8 +379,8 @@
scenario_plotter = ScenarioPlotter()
- J_accelerating = 12
- J_decelerating = 5
+ J_accelerating = 18
+ J_decelerating = 7
arm = Arm(name='AcceleratingArm', J=J_accelerating)
arm_integral_controller = IntegralArm(
diff --git a/y2016/control_loops/python/drivetrain.py b/y2016/control_loops/python/drivetrain.py
index 3701e57..83eb677 100755
--- a/y2016/control_loops/python/drivetrain.py
+++ b/y2016/control_loops/python/drivetrain.py
@@ -77,7 +77,7 @@
# Radius of the robot, in meters (requires tuning by hand)
self.rb = 0.601 / 2.0
# Radius of the wheels, in meters.
- self.r = 0.097155 * 0.9811158901447808
+ self.r = 0.097155 * 0.9811158901447808 / 118.0 * 115.75
# Resistance of the motor, divided by the number of motors.
self.resistance = 12.0 / self.stall_current
# Motor velocity constant
diff --git a/y2016/control_loops/python/intake.py b/y2016/control_loops/python/intake.py
index cc2dfaf..d99160d 100755
--- a/y2016/control_loops/python/intake.py
+++ b/y2016/control_loops/python/intake.py
@@ -42,7 +42,7 @@
# Moment of inertia, measured in CAD.
# Extra mass to compensate for friction is added on.
- self.J = 0.34 + 0.65
+ self.J = 0.34 + 0.40
# Control loop time step
self.dt = 0.005
@@ -73,7 +73,7 @@
glog.debug("Free speed is %f", self.free_speed * numpy.pi * 2.0 / 60.0 / self.G)
q_pos = 0.20
- q_vel = 5.5
+ q_vel = 5.0
self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
[0.0, (1.0 / (q_vel ** 2.0))]])
diff --git a/y2016/control_loops/python/shoulder.py b/y2016/control_loops/python/shoulder.py
index 6beac61..6c07725 100755
--- a/y2016/control_loops/python/shoulder.py
+++ b/y2016/control_loops/python/shoulder.py
@@ -71,7 +71,7 @@
controllability = controls.ctrb(self.A, self.B)
q_pos = 0.16
- q_vel = 1.5
+ q_vel = 0.95
self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
[0.0, (1.0 / (q_vel ** 2.0))]])
diff --git a/y2016/control_loops/python/wrist.py b/y2016/control_loops/python/wrist.py
index 660e577..f08f1a2 100755
--- a/y2016/control_loops/python/wrist.py
+++ b/y2016/control_loops/python/wrist.py
@@ -39,7 +39,7 @@
# Gear ratio
self.G = (56.0 / 12.0) * (54.0 / 14.0) * (64.0 / 18.0) * (48.0 / 16.0)
- self.J = 0.20
+ self.J = 0.35
# Control loop time step
self.dt = 0.005
diff --git a/y2016/control_loops/shooter/shooter.cc b/y2016/control_loops/shooter/shooter.cc
index 0936eea..629b980 100644
--- a/y2016/control_loops/shooter/shooter.cc
+++ b/y2016/control_loops/shooter/shooter.cc
@@ -84,7 +84,17 @@
// Turn the lights on if we are supposed to spin.
if (output) {
- if (::std::abs(goal->angular_velocity) > 0.0 || goal->force_lights_on) {
+ if (::std::abs(goal->angular_velocity) > 0.0) {
+ output->lights_on = true;
+ if (goal->shooting_forwards) {
+ output->forwards_flashlight = true;
+ output->backwards_flashlight = false;
+ } else {
+ output->forwards_flashlight = false;
+ output->backwards_flashlight = true;
+ }
+ }
+ if (goal->force_lights_on) {
output->lights_on = true;
}
}
diff --git a/y2016/control_loops/shooter/shooter.q b/y2016/control_loops/shooter/shooter.q
index b799b5a..0e00a02 100644
--- a/y2016/control_loops/shooter/shooter.q
+++ b/y2016/control_loops/shooter/shooter.q
@@ -31,6 +31,9 @@
// Forces the lights on.
bool force_lights_on;
+
+ // If true, the robot is shooting forwards.
+ bool shooting_forwards;
};
message Position {
@@ -65,6 +68,9 @@
// If true, the lights are on.
bool lights_on;
+
+ bool forwards_flashlight;
+ bool backwards_flashlight;
};
queue Goal goal;
diff --git a/y2016/control_loops/superstructure/BUILD b/y2016/control_loops/superstructure/BUILD
index f633d7b..6a10b61 100644
--- a/y2016/control_loops/superstructure/BUILD
+++ b/y2016/control_loops/superstructure/BUILD
@@ -78,6 +78,7 @@
'//aos/common/controls:control_loop',
'//aos/common/util:trapezoid_profile',
'//aos/common:math',
+ '//y2016/queues:ball_detector',
'//frc971/control_loops:state_feedback_loop',
'//frc971/control_loops:simple_capped_state_feedback_loop',
'//frc971/zeroing',
diff --git a/y2016/control_loops/superstructure/superstructure.cc b/y2016/control_loops/superstructure/superstructure.cc
index e5f0fff..0c1ac6a 100644
--- a/y2016/control_loops/superstructure/superstructure.cc
+++ b/y2016/control_loops/superstructure/superstructure.cc
@@ -7,6 +7,7 @@
#include "y2016/control_loops/superstructure/integral_intake_plant.h"
#include "y2016/control_loops/superstructure/integral_arm_plant.h"
+#include "y2016/queues/ball_detector.q.h"
#include "y2016/constants.h"
@@ -18,6 +19,7 @@
// The maximum voltage the intake roller will be allowed to use.
constexpr float kMaxIntakeTopVoltage = 12.0;
constexpr float kMaxIntakeBottomVoltage = 12.0;
+constexpr float kMaxClimberVoltage = 12.0;
// Aliases to reduce typing.
constexpr double kIntakeEncoderIndexDifference =
@@ -46,7 +48,7 @@
// incorporating a small safety margin makes writing test cases much easier
// since you can directly compare statuses against the constants in the
// CollisionAvoidance class.
- constexpr double kSafetyMargin = 0.02; // radians
+ constexpr double kSafetyMargin = 0.03; // radians
// Avoid colliding the shooter with the frame.
// If the shoulder is below a certain angle or we want to move it below
@@ -80,15 +82,15 @@
if (wrist_angle > kMaxWristAngleForMovingByIntake ||
wrist_angle < kMinWristAngleForMovingByIntake) {
shoulder_angle_goal =
- ::std::max(original_shoulder_angle_goal,
- kMinShoulderAngleForIntakeInterference + kSafetyMargin);
+ ::std::max(original_shoulder_angle_goal,
+ kMinShoulderAngleForIntakeInterference + kSafetyMargin);
}
} else {
if (wrist_angle > kMaxWristAngleForMovingByIntake ||
wrist_angle < kMinWristAngleForMovingByIntake) {
- shoulder_angle_goal =
- ::std::max(original_shoulder_angle_goal,
- kMinShoulderAngleForIntakeUpInterference + kSafetyMargin);
+ shoulder_angle_goal = ::std::max(
+ original_shoulder_angle_goal,
+ kMinShoulderAngleForIntakeUpInterference + kSafetyMargin);
}
}
if (::std::abs(wrist_angle) > kMaxWristAngleForSafeArmStowing) {
@@ -172,8 +174,7 @@
CollisionAvoidance::kMaxShoulderAngleUntilSafeIntakeStowing &&
shoulder_angle <=
CollisionAvoidance::kMinShoulderAngleForIntakeUpInterference &&
- intake_angle >
- CollisionAvoidance::kMaxIntakeAngleBeforeArmInterference) {
+ intake_angle > CollisionAvoidance::kMaxIntakeAngleBeforeArmInterference) {
LOG(DEBUG, "Collided: Intake %f > %f, and shoulder %f < %f < %f.\n",
intake_angle, CollisionAvoidance::kMaxIntakeAngleBeforeArmInterference,
CollisionAvoidance::kMaxShoulderAngleUntilSafeIntakeStowing,
@@ -208,7 +209,7 @@
if (shoulder_angle <
CollisionAvoidance::kMinShoulderAngleForHorizontalShooter &&
::std::abs(wrist_angle) > kMaxWristAngleForSafeArmStowing) {
- LOG(DEBUG, "Collided: Shoulder %f < %f and wrist |%f| < %f.\n",
+ LOG(DEBUG, "Collided: Shoulder %f < %f and wrist |%f| > %f.\n",
shoulder_angle,
CollisionAvoidance::kMinShoulderAngleForHorizontalShooter, wrist_angle,
kMaxWristAngleForSafeArmStowing);
@@ -469,6 +470,29 @@
arm_.unprofiled_goal(2, 0));
}
+ // If we're about to ask the wrist to go past one of its limits, then
+ // move the goal so it will be just at the limit when we finish lifting
+ // the shoulder. If it wasn't intersecting something before, this can't
+ // cause it to crash into anything.
+ const double ungrounded_wrist = arm_.goal(2, 0) - arm_.goal(0, 0);
+ const double unprofiled_ungrounded_wrist =
+ arm_.unprofiled_goal(2, 0) - arm_.unprofiled_goal(0, 0);
+ if (unprofiled_ungrounded_wrist >
+ constants::Values::kWristRange.upper &&
+ ungrounded_wrist >
+ constants::Values::kWristRange.upper - kWristAlmostLevel) {
+ arm_.set_unprofiled_goal(arm_.unprofiled_goal(0, 0),
+ constants::Values::kWristRange.upper +
+ arm_.unprofiled_goal(0, 0));
+ } else if (unprofiled_ungrounded_wrist <
+ constants::Values::kWristRange.lower &&
+ ungrounded_wrist < constants::Values::kWristRange.lower +
+ kWristAlmostLevel) {
+ arm_.set_unprofiled_goal(arm_.unprofiled_goal(0, 0),
+ constants::Values::kWristRange.lower +
+ arm_.unprofiled_goal(0, 0));
+ }
+
// Wait until we are level and then go for it.
if (IsArmNear(kLooseTolerance)) {
state_ = LOW_ARM_ZERO_LEVEL_SHOOTER;
@@ -609,10 +633,28 @@
const double max_voltage = (state_ == RUNNING || state_ == LANDING_RUNNING)
? kOperatingVoltage
: kZeroingVoltage;
- arm_.set_max_voltage(max_voltage, max_voltage);
+ if (unsafe_goal) {
+ constexpr float kTriggerThreshold = 12.0 * 0.90 / 0.005;
+
+ if (unsafe_goal->voltage_climber > 1.0) {
+ kill_shoulder_accumulator_ +=
+ ::std::min(kMaxClimberVoltage, unsafe_goal->voltage_climber);
+ } else {
+ kill_shoulder_accumulator_ = 0.0;
+ }
+
+ if (kill_shoulder_accumulator_ > kTriggerThreshold) {
+ kill_shoulder_ = true;
+ }
+ }
+ arm_.set_max_voltage(
+ kill_shoulder_ ? 0.0 : max_voltage,
+ kill_shoulder_ ? (arm_.X_hat(0, 0) < 0.05 ? kShooterHangingLowVoltage
+ : kShooterHangingVoltage)
+ : max_voltage);
intake_.set_max_voltage(max_voltage);
- if (IsRunning()) {
+ if (IsRunning() && !kill_shoulder_) {
// We don't want lots of negative voltage when we are near the bellypan on
// the shoulder...
// TODO(austin): Do I want to push negative power into the belly pan at this
@@ -649,16 +691,40 @@
output->voltage_shoulder = arm_.shoulder_voltage();
output->voltage_wrist = arm_.wrist_voltage();
- // Logic to run our rollers on the intake.
output->voltage_top_rollers = 0.0;
output->voltage_bottom_rollers = 0.0;
+
+ output->voltage_climber = 0.0;
+ output->unfold_climber = false;
if (unsafe_goal) {
- output->voltage_top_rollers = ::std::max(
- -kMaxIntakeTopVoltage,
- ::std::min(unsafe_goal->voltage_top_rollers, kMaxIntakeTopVoltage));
- output->voltage_bottom_rollers = ::std::max(
- -kMaxIntakeBottomVoltage,
- ::std::min(unsafe_goal->voltage_bottom_rollers, kMaxIntakeBottomVoltage));
+ // Ball detector lights.
+ ::y2016::sensors::ball_detector.FetchLatest();
+ bool ball_detected = false;
+ if (::y2016::sensors::ball_detector.get()) {
+ ball_detected = ::y2016::sensors::ball_detector->voltage > 2.5;
+ }
+
+ // Climber.
+ output->voltage_climber = ::std::max(
+ static_cast<float>(0.0),
+ ::std::min(unsafe_goal->voltage_climber, kMaxClimberVoltage));
+ output->unfold_climber = unsafe_goal->unfold_climber;
+
+ // Intake.
+ if (unsafe_goal->force_intake || !ball_detected) {
+ output->voltage_top_rollers = ::std::max(
+ -kMaxIntakeTopVoltage,
+ ::std::min(unsafe_goal->voltage_top_rollers, kMaxIntakeTopVoltage));
+ output->voltage_bottom_rollers =
+ ::std::max(-kMaxIntakeBottomVoltage,
+ ::std::min(unsafe_goal->voltage_bottom_rollers,
+ kMaxIntakeBottomVoltage));
+ } else {
+ output->voltage_top_rollers = 0.0;
+ output->voltage_bottom_rollers = 0.0;
+ }
+
+ // Traverse.
output->traverse_unlatched = unsafe_goal->traverse_unlatched;
output->traverse_down = unsafe_goal->traverse_down;
}
@@ -697,7 +763,8 @@
status->intake.unprofiled_goal_angle = intake_.unprofiled_goal(0, 0);
status->intake.unprofiled_goal_angular_velocity =
intake_.unprofiled_goal(1, 0);
- status->intake.calculated_velocity = (intake_.angle() - last_intake_angle_) / 0.005;
+ status->intake.calculated_velocity =
+ (intake_.angle() - last_intake_angle_) / 0.005;
status->intake.voltage_error = intake_.X_hat(2, 0);
status->intake.estimator_state = intake_.IntakeEstimatorState();
status->intake.feedforwards_power = intake_.controller().ff_U(0, 0);
diff --git a/y2016/control_loops/superstructure/superstructure.h b/y2016/control_loops/superstructure/superstructure.h
index 9cd570c..eb16405 100644
--- a/y2016/control_loops/superstructure/superstructure.h
+++ b/y2016/control_loops/superstructure/superstructure.h
@@ -111,6 +111,8 @@
&control_loops::superstructure_queue);
static constexpr double kZeroingVoltage = 6.0;
+ static constexpr double kShooterHangingVoltage = 6.0;
+ static constexpr double kShooterHangingLowVoltage = 2.0;
static constexpr double kOperatingVoltage = 12.0;
static constexpr double kLandingShoulderDownVoltage = -1.5;
@@ -232,6 +234,9 @@
float last_wrist_angle_ = 0.0;
float last_intake_angle_ = 0.0;
+ double kill_shoulder_accumulator_ = 0.0;
+ bool kill_shoulder_ = false;
+
// Returns true if the profile has finished, and the joint is within the
// specified tolerance.
bool IsArmNear(double tolerance);
diff --git a/y2016/control_loops/superstructure/superstructure.q b/y2016/control_loops/superstructure/superstructure.q
index f550512..842beb7 100644
--- a/y2016/control_loops/superstructure/superstructure.q
+++ b/y2016/control_loops/superstructure/superstructure.q
@@ -65,6 +65,13 @@
float voltage_top_rollers;
float voltage_bottom_rollers;
+ // Voltage to sent to the climber. Positive is pulling the robot up.
+ float voltage_climber;
+ // If true, unlatch the climber and allow it to unfold.
+ bool unfold_climber;
+
+ bool force_intake;
+
// If true, release the latch which holds the traverse mechanism in the
// middle.
bool traverse_unlatched;
@@ -116,6 +123,11 @@
float voltage_top_rollers;
float voltage_bottom_rollers;
+ // Voltage to sent to the climber. Positive is pulling the robot up.
+ float voltage_climber;
+ // If true, release the latch to trigger the climber to unfold.
+ bool unfold_climber;
+
// If true, release the latch to hold the traverse mechanism in the middle.
bool traverse_unlatched;
// If true, fire the traverse mechanism down.
diff --git a/y2016/control_loops/superstructure/superstructure_lib_test.cc b/y2016/control_loops/superstructure/superstructure_lib_test.cc
index 9fdec26..02f7ae2 100644
--- a/y2016/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2016/control_loops/superstructure/superstructure_lib_test.cc
@@ -795,7 +795,7 @@
RunForTime(Time::InSeconds(2), false);
EXPECT_EQ(Superstructure::DISABLED_INITIALIZED, superstructure_.state());
- superstructure_plant_.set_power_error(1.0, 1.0, 1.0);
+ superstructure_plant_.set_power_error(1.0, 1.5, 1.0);
RunForTime(Time::InSeconds(1), false);
diff --git a/y2016/dashboard/BUILD b/y2016/dashboard/BUILD
new file mode 100644
index 0000000..65e650c
--- /dev/null
+++ b/y2016/dashboard/BUILD
@@ -0,0 +1,37 @@
+load('/aos/externals/seasocks/gen_embedded', 'gen_embedded')
+load('/aos/downloader/downloader', 'aos_downloader_dir')
+
+gen_embedded(
+ name = 'gen_embedded',
+ srcs = glob(['www_defaults/**/*'], ['www/**/*']),
+)
+
+aos_downloader_dir(
+ name = 'www_files',
+ visibility = ['//visibility:public'],
+ srcs = glob([
+ 'www/**/*',
+ ]),
+ dir = "www",
+)
+
+cc_binary(
+ name = 'dashboard',
+ visibility = ['//visibility:public'],
+ srcs = [
+ 'dashboard.cc',
+ 'dashboard.h',
+ ],
+ deps = [
+ ':gen_embedded',
+ '//aos/linux_code:init',
+ '//aos/common/logging',
+ '//aos/common/util:phased_loop',
+ '//aos/common:time',
+ '//third_party/seasocks',
+ '//y2016/actors:autonomous_action_queue',
+ '//y2016/vision:vision_queue',
+ '//y2016/control_loops/superstructure:superstructure_queue',
+ '//y2016/queues:ball_detector',
+ ],
+)
diff --git a/y2016/dashboard/dashboard.cc b/y2016/dashboard/dashboard.cc
new file mode 100644
index 0000000..bdfedb8
--- /dev/null
+++ b/y2016/dashboard/dashboard.cc
@@ -0,0 +1,302 @@
+#include "y2016/dashboard/dashboard.h"
+
+#include <iostream>
+#include <sstream>
+#include <string>
+#include <thread>
+#include <vector>
+#include <complex>
+
+#include "seasocks/Server.h"
+
+#include "aos/linux_code/init.h"
+#include "aos/common/logging/logging.h"
+#include "aos/common/time.h"
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/mutex.h"
+
+#include "y2016/actors/autonomous_action.q.h"
+#include "y2016/vision/vision.q.h"
+#include "y2016/control_loops/superstructure/superstructure.q.h"
+#include "y2016/queues/ball_detector.q.h"
+
+#include "y2016/dashboard/embedded.h"
+
+namespace y2016 {
+namespace dashboard {
+namespace big_indicator {
+constexpr int kBlack = 0;
+constexpr int kBallIntaked = 1;
+constexpr int kAiming = 2;
+constexpr int kLockedOn = 3;
+} // namespace big_indicator
+
+namespace superstructure_indicator {
+constexpr int kBlack = 0;
+constexpr int kNotZeroed = 1;
+constexpr int kEstopped = 2;
+} // namespace superstructure_indicator
+
+// Define the following if we want to use a local www directory and feed in
+// dummy data.
+//#define DASHBOARD_TESTING
+
+// Define the following if we want to read from the vision queue, which has
+// caused problems in the past when auto aiming that still need to be addressed.
+//#define DASHBOARD_READ_VISION_QUEUE
+
+DataCollector::DataCollector()
+ : cur_raw_data_("no data"),
+ sample_id_(0),
+ measure_index_(0),
+ overflow_id_(20) {}
+
+void DataCollector::RunIteration() {
+ ::aos::MutexLocker locker(&mutex_);
+ measure_index_ = 0;
+
+// Add recorded data here. /////
+#ifdef DASHBOARD_TESTING
+ // The following feeds data into the webserver when we do not have a process
+ // feeding data to the queues.
+ // To test, we are sending three streams holding randomly generated numbers.
+ AddPoint("test", ::std::rand() % 4);
+ AddPoint("test2", ::std::rand() % 3);
+ AddPoint("test3", ::std::rand() % 3 - 1);
+ (void)big_indicator::kBlack;
+ (void)big_indicator::kBallIntaked;
+ (void)big_indicator::kAiming;
+ (void)big_indicator::kLockedOn;
+ (void)superstructure_indicator::kBlack;
+ (void)superstructure_indicator::kNotZeroed;
+ (void)superstructure_indicator::kEstopped;
+#else
+ int big_indicator = big_indicator::kBlack;
+ int superstructure_state_indicator = superstructure_indicator::kBlack;
+ // We should never have a -1 here, so this is an indicator that somethings
+ // gone wrong with reading the auto queue.
+ int auto_mode_indicator = -1;
+
+ ::y2016::actors::auto_mode.FetchLatest();
+ ::y2016::control_loops::superstructure_queue.status.FetchLatest();
+ ::y2016::sensors::ball_detector.FetchLatest();
+ ::y2016::vision::vision_status.FetchLatest();
+
+// Caused glitching with auto-aim at NASA, so be cautious with this until
+// we find a good fix.
+#ifdef DASHBOARD_READ_VISION_QUEUE
+ if (::y2016::vision::vision_status.get() &&
+ (::y2016::vision::vision_status->left_image_valid ||
+ ::y2016::vision::vision_status->right_image_valid)) {
+ big_indicator = big_indicator::kAiming;
+ if (::std::abs(::y2016::vision::vision_status->horizontal_angle) < 0.002) {
+ big_indicator = big_indicator::kLockedOn;
+ }
+ }
+#else
+ (void)big_indicator::kAiming;
+ (void)big_indicator::kLockedOn;
+#endif
+
+ // Ball detector comes after vision because we want to prioritize that
+ // indication.
+ if (::y2016::sensors::ball_detector.get()) {
+ // TODO(comran): Grab detected voltage from joystick_reader. Except this
+ // value may not change, so it may be worth it to keep it as it is right
+ // now.
+ if (::y2016::sensors::ball_detector->voltage > 2.5) {
+ big_indicator = big_indicator::kBallIntaked;
+ }
+ }
+
+ if (::y2016::control_loops::superstructure_queue.status.get()) {
+ if (!::y2016::control_loops::superstructure_queue.status->zeroed) {
+ superstructure_state_indicator = superstructure_indicator::kNotZeroed;
+ }
+ if (::y2016::control_loops::superstructure_queue.status->estopped) {
+ superstructure_state_indicator = superstructure_indicator::kEstopped;
+ }
+ }
+
+ if (::y2016::actors::auto_mode.get()) {
+ auto_mode_indicator = ::y2016::actors::auto_mode->mode;
+ }
+
+ AddPoint("big indicator", big_indicator);
+ AddPoint("superstructure state indicator", superstructure_state_indicator);
+ AddPoint("auto mode indicator", auto_mode_indicator);
+#endif
+
+ // Get ready for next iteration. /////
+ sample_id_++;
+}
+
+void DataCollector::AddPoint(const ::std::string &name, double value) {
+ // Mutex should be locked when this method is called to synchronize packets.
+ CHECK(mutex_.OwnedBySelf());
+
+ size_t index = GetIndex(sample_id_);
+
+ ItemDatapoint datapoint{value, ::aos::time::Time::Now()};
+ if (measure_index_ >= sample_items_.size()) {
+ // New item in our data table.
+ ::std::vector<ItemDatapoint> datapoints;
+ SampleItem item{name, datapoints};
+ sample_items_.emplace_back(item);
+ } else if (index >= sample_items_.at(measure_index_).datapoints.size()) {
+ // New data point for an already existing item.
+ sample_items_.at(measure_index_).datapoints.emplace_back(datapoint);
+ } else {
+ // Overwrite an already existing data point for an already existing item.
+ sample_items_.at(measure_index_).datapoints.at(index) = datapoint;
+ }
+
+ measure_index_++;
+}
+
+::std::string DataCollector::Fetch(int32_t from_sample) {
+ ::aos::MutexLocker locker(&mutex_);
+
+ ::std::stringstream message;
+ message.precision(10);
+
+ // Send out the names of each item when requested by the client.
+ // Example: *item_one_name,item_two_name,item_three_name
+ if (from_sample == 0) {
+ message << "*"; // Begin name packet.
+
+ // Add comma-separated list of names.
+ for (size_t cur_data_name = 0; cur_data_name < sample_items_.size();
+ cur_data_name++) {
+ if (cur_data_name > 0) {
+ message << ",";
+ }
+ message << sample_items_.at(cur_data_name).name;
+ }
+ return message.str();
+ }
+
+ // Send out one sample containing the data.
+ // Samples are split with dollar signs, info with percent signs, and
+ // measurements with commas.
+ // Example of data with two samples: $289%2803.13%10,67$290%2803.14%12,68
+
+ // Note that we are ignoring the from_sample being sent to keep up with the
+ // live data without worrying about client lag.
+ int32_t cur_sample = sample_id_ - 2;
+ int32_t adjusted_index = GetIndex(cur_sample);
+ message << "$"; // Begin data packet.
+
+ // Make sure we are not out of range.
+ if (static_cast<size_t>(adjusted_index) <
+ sample_items_.at(0).datapoints.size()) {
+ message << cur_sample << "%"
+ << sample_items_.at(0)
+ .datapoints.at(adjusted_index)
+ .time.ToSeconds() << "%"; // Send time.
+ // Add comma-separated list of data points.
+ for (size_t cur_measure = 0; cur_measure < sample_items_.size();
+ cur_measure++) {
+ if (cur_measure > 0) {
+ message << ",";
+ }
+ message << sample_items_.at(cur_measure)
+ .datapoints.at(adjusted_index)
+ .value;
+ }
+ }
+
+ return message.str();
+}
+
+size_t DataCollector::GetIndex(size_t sample_id) {
+ return sample_id % overflow_id_;
+}
+
+void DataCollector::operator()() {
+ ::aos::SetCurrentThreadName("DashboardData");
+
+ while (run_) {
+ ::aos::time::PhasedLoopXMS(100, 0);
+ RunIteration();
+ }
+}
+
+SocketHandler::SocketHandler()
+ : data_collector_thread_(::std::ref(data_collector_)) {}
+
+void SocketHandler::onConnect(seasocks::WebSocket *connection) {
+ connections_.insert(connection);
+ LOG(INFO, "Connected: %s : %s\n", connection->getRequestUri().c_str(),
+ seasocks::formatAddress(connection->getRemoteAddress()).c_str());
+}
+
+void SocketHandler::onData(seasocks::WebSocket *connection, const char *data) {
+ int32_t from_sample = atoi(data);
+
+ ::std::string send_data = data_collector_.Fetch(from_sample);
+ connection->send(send_data.c_str());
+}
+
+void SocketHandler::onDisconnect(seasocks::WebSocket *connection) {
+ connections_.erase(connection);
+ LOG(INFO, "Disconnected: %s : %s\n", connection->getRequestUri().c_str(),
+ seasocks::formatAddress(connection->getRemoteAddress()).c_str());
+}
+
+void SocketHandler::Quit() {
+ data_collector_.Quit();
+ data_collector_thread_.join();
+}
+
+SeasocksLogger::SeasocksLogger(Level min_level_to_log)
+ : PrintfLogger(min_level_to_log) {}
+
+void SeasocksLogger::log(Level level, const char *message) {
+ // Convert Seasocks error codes to AOS.
+ log_level aos_level;
+ switch (level) {
+ case seasocks::Logger::INFO:
+ aos_level = INFO;
+ break;
+ case seasocks::Logger::WARNING:
+ aos_level = WARNING;
+ break;
+ case seasocks::Logger::ERROR:
+ case seasocks::Logger::SEVERE:
+ aos_level = ERROR;
+ break;
+ case seasocks::Logger::DEBUG:
+ case seasocks::Logger::ACCESS:
+ default:
+ aos_level = DEBUG;
+ break;
+ }
+ LOG(aos_level, "Seasocks: %s\n", message);
+}
+
+} // namespace dashboard
+} // namespace y2016
+
+int main(int, char *[]) {
+ ::aos::InitNRT();
+
+ ::seasocks::Server server(::std::shared_ptr<seasocks::Logger>(
+ new ::y2016::dashboard::SeasocksLogger(seasocks::Logger::INFO)));
+ ::y2016::dashboard::SocketHandler socket_handler;
+
+ server.addWebSocketHandler(
+ "/ws",
+ ::std::shared_ptr<::y2016::dashboard::SocketHandler>(&socket_handler));
+#ifdef DASHBOARD_TESTING
+ server.serve("www", 1180);
+#else
+ // Absolute directory of www folder on the robot.
+ server.serve("/home/admin/robot_code/www", 1180);
+#endif
+
+ socket_handler.Quit();
+
+ ::aos::Cleanup();
+ return 0;
+}
diff --git a/y2016/dashboard/dashboard.h b/y2016/dashboard/dashboard.h
new file mode 100644
index 0000000..003820c
--- /dev/null
+++ b/y2016/dashboard/dashboard.h
@@ -0,0 +1,96 @@
+#include <iostream>
+#include <memory>
+#include <sstream>
+#include <string>
+#include <thread>
+#include <atomic>
+#include <vector>
+
+#include "seasocks/PageHandler.h"
+#include "seasocks/PrintfLogger.h"
+#include "seasocks/StringUtil.h"
+#include "seasocks/WebSocket.h"
+
+#include "aos/linux_code/init.h"
+#include "aos/common/time.h"
+#include "aos/common/util/phased_loop.h"
+#include "aos/common/mutex.h"
+
+namespace y2016 {
+namespace dashboard {
+
+// Dashboard is a webserver that opens a socket and stream data from the robot
+// to the client. It is divided between the DataCollector, which polls
+// RunIteration to determine what to send to the client, and an instance of a
+// Seasocks server, which initiates a webserver on a port and opens a socket
+// for streaming data.
+
+// It is an adaption of http_status, which was a 2015 project
+// that plotted live position data from the robot queues on a webpage for
+// debugging.
+
+class DataCollector {
+ public:
+ DataCollector();
+ void RunIteration();
+
+ // Store a datapoint. In this case, we are reading data points to determine
+ // what color to display on the webpage indicators. Traditionally, this would
+ // be used to plot live data on a graph on the page.
+ void AddPoint(const ::std::string &name, double value);
+
+ // Method called by the websocket to get a JSON-packaged string containing,
+ // at most, a constant number of samples, starting at from_sample.
+ ::std::string Fetch(int32_t from_sample);
+
+ void operator()();
+ void Quit() { run_ = false; }
+
+ private:
+ // Returns a wrapped index based on the overflow size.
+ size_t GetIndex(size_t sample_id);
+
+ struct ItemDatapoint {
+ double value;
+ ::aos::time::Time time;
+ };
+
+ struct SampleItem {
+ ::std::string name;
+ ::std::vector<ItemDatapoint> datapoints;
+ };
+
+ // Storage vector that is written and overwritten with data in a FIFO fashion.
+ ::std::vector<SampleItem> sample_items_;
+
+ ::std::string cur_raw_data_;
+ int32_t sample_id_; // Last sample id used.
+ size_t measure_index_; // Last measure index used.
+ const int32_t overflow_id_; // Vector wrapping size.
+
+ ::std::atomic<bool> run_{true};
+ ::aos::Mutex mutex_;
+};
+
+class SocketHandler : public seasocks::WebSocket::Handler {
+ public:
+ SocketHandler();
+ void onConnect(seasocks::WebSocket* connection) override;
+ void onData(seasocks::WebSocket* connection, const char* data) override;
+ void onDisconnect(seasocks::WebSocket* connection) override;
+ void Quit();
+
+ private:
+ ::std::set<seasocks::WebSocket*> connections_;
+ DataCollector data_collector_;
+ ::std::thread data_collector_thread_;
+};
+
+class SeasocksLogger : public seasocks::PrintfLogger {
+ public:
+ SeasocksLogger(Level min_level_to_log);
+ void log(Level level, const char* message) override;
+};
+
+} // namespace dashboard
+} // namespace y2016
diff --git a/y2016/dashboard/www/index.html b/y2016/dashboard/www/index.html
new file mode 100644
index 0000000..da5512f
--- /dev/null
+++ b/y2016/dashboard/www/index.html
@@ -0,0 +1,245 @@
+<!DOCTYPE html>
+<html>
+<head>
+<title>Spartan Dashboard</title>
+
+<script type="text/javascript">
+var escapable =
+ /[\x00-\x1f\ud800-\udfff\u200c-\u200f\u2028-\u202f\u2060-\u206f\ufff0-\uffff]/g;
+var ws;
+var intervalTime = 50;
+var selected = 0;
+var reconnecting = false;
+var lastSampleID = 0;
+var resetTimeout;
+
+// Filter out junky JSON packets that will otherwise cause nasty decoding
+// errors. These errors come as a result of incomplete packets, corrupted data,
+// or any other artifacts that find themselves into the socket stream.
+
+function filterUnicode(quoted) {
+ escapable.lastIndex = 0;
+ if (!escapable.test(quoted)) return quoted;
+
+ return quoted.replace(escapable, '');
+}
+
+// Change the current data index to plot on the graph.
+// Get a new JSON packet from the websocket on the robot.
+function refresh() {
+ if (!reconnecting) ws.send(lastSampleID);
+}
+
+function initSocketLoop() {
+ ws = new WebSocket('ws://' + document.location.host + '/ws');
+
+ var numDatas = 0;
+
+ $(function() {
+
+ // Socket created & first opened.
+ ws.onopen = function() {
+ reconnecting = false;
+ refresh();
+ $('#message').text('');
+ };
+
+ // Socket disconnected.
+ ws.onclose = function() {
+ console.log('onclose');
+ reconnect();
+ };
+
+ ws.onmessage = function(message) {
+ message = message.data;
+ if(message.charAt(0) == "*"){
+ message = message.substring(1);
+ var names = message.split(",");
+ for (var i = numDatas; i < names.length; i++) {
+ $('#dataTable').append('<tr><td>' + names[i] + '</td><td></td></tr>');
+ numDatas++;
+ }
+ lastSampleID = 1;
+ }else{
+ var samples = message.split("$");
+ for(var x = 0;x < samples.length;x++){
+ var info = samples[x].split("%");
+ lastSampleID = info[0];
+
+ if(!(typeof info[2] === "undefined")){
+ var values = info[2].split(",");
+
+ // For the big indicator.
+ switch(parseInt(values[0])){
+ case 1:
+ $("#bigIndicator").css("background", "#00FF00");
+ $("#bigIndicator").css("color", "#000000");
+ $("#bigIndicator").text("Ball detected");
+ break;
+ case 2:
+ $("#bigIndicator").css("background", "#FFFF00");
+ $("#bigIndicator").css("color", "#000000");
+ $("#bigIndicator").text("Target seen");
+ break;
+ case 3:
+ $("#bigIndicator").css("background", "#0000FF");
+ $("#bigIndicator").css("color", "#000000");
+ $("#bigIndicator").text("Target aligned");
+ break;
+ case 0:
+ default:
+ $("#bigIndicator").css("background", "#000000");
+ $("#bigIndicator").css("color", "#444444");
+ $("#bigIndicator").text("No ball, no target");
+ break;
+ }
+
+ // Superstructure state indicator.
+ switch(parseInt(values[1])){
+ case 1:
+ $("#superstructureStateIndicator").css("background", "#FF0000");
+ $("#superstructureStateIndicator").css("color", "#000000");
+ $("#superstructureStateIndicator").text("Not zeroed");
+ break;
+ case 2:
+ $("#superstructureStateIndicator").css("background", "#FF8C00");
+ $("#superstructureStateIndicator").css("color", "#000000");
+ $("#superstructureStateIndicator").text("Estopped");
+ break;
+ case 0:
+ default:
+ $("#superstructureStateIndicator").css("background", "#000000");
+ $("#superstructureStateIndicator").css("color", "#444444");
+ $("#superstructureStateIndicator").text("Superstructure OK");
+ break;
+ }
+
+ // Auto mode indicator.
+ $("#autoModeIndicator").text("Mode: " + values[2]);
+ if (parseInt(values[2]) < 0){
+ $("#autoModeIndicator").css("visibility", "hidden");
+ } else {
+ $("#autoModeIndicator").css("visibility", "visible");
+ }
+
+ // Populate data table.
+ for(var y = 0;y < values.length;y++){
+ if(!(typeof info[1] === "undefined"
+ || typeof values[y] === "undefined")){
+ $('#dataTable').find('tr').eq(y).find('td').eq(1)
+ .text(values[y]);
+ }
+ }
+ }
+ }
+ }
+
+ setTimeout(refresh, intervalTime);
+ };
+
+ // Socket error, most likely due to a server-side error.
+ ws.onerror = function(error) {
+ console.log('onerror ' + error);
+ };
+ });
+}
+
+function reconnect() {
+ $('#message').text('Reconnecting...');
+ $('#dataTable').empty();
+ lastSampleID = 0;
+ reconnecting = true;
+
+ setTimeout(function(){
+ initSocketLoop()
+ }, 500);
+}
+
+window.onload = function() {
+ initSocketLoop();
+}
+</script>
+<script type="text/javascript" src='jquery-2.2.3.min.js'></script>
+<style>
+body {
+ width: 100%;
+ margin-left: auto;
+ margin-right:auto;
+}
+
+#dataTable {
+ position: absolute;
+ top: 0;
+ background: #FFFFFF;
+ left: 0;
+ width: 200px;
+ cell-spacing:0;
+ cell-padding:0;
+ text-align: left;
+ z-index: 99999;
+}
+
+#headsUpDisplay {
+ width: 1000px;
+ position: absolute;
+ margin-left: auto;
+ margin-right: auto;
+ left: 0;
+ right: 0;
+ z-index: 10000000;
+}
+
+#message {
+ color: #FF0000;
+ text-align: center;
+ background: #000000;
+ font-size: 100px;
+}
+
+#indicatorContainer {
+ width: 100%;
+ height: 100%;
+ position: absolute;
+ top: 0;
+ left: 0;
+ background: #000000;
+ text-align: center;
+ font-size: 100px;
+}
+
+#bigIndicator {
+ background: #000000;
+}
+
+#superstructureStateIndicator {
+ background: #000000;
+ width: 60%;
+}
+
+#autoModeIndicator {
+ background: #FF0000;
+}
+</style>
+</head>
+<body>
+<!-- Data -->
+<table id="dataTable">
+</table>
+
+<div id="headsUpDisplay">
+ <p id="message"></p>
+ <p id="data"></p>
+</div>
+
+<table id="indicatorContainer">
+ <tr>
+ <td id="bigIndicator" colspan="2">Ball detected</td>
+ </tr>
+ <tr style="height:10%">
+ <td id="superstructureStateIndicator">Superstructure state</td>
+ <td id="autoModeIndicator">Auto mode</td>
+ </tr>
+</table>
+
+</body>
+</html>
diff --git a/y2016/dashboard/www/jquery-2.2.3.min.js b/y2016/dashboard/www/jquery-2.2.3.min.js
new file mode 100644
index 0000000..b8c4187
--- /dev/null
+++ b/y2016/dashboard/www/jquery-2.2.3.min.js
@@ -0,0 +1,4 @@
+/*! jQuery v2.2.3 | (c) jQuery Foundation | jquery.org/license */
+!function(a,b){"object"==typeof module&&"object"==typeof module.exports?module.exports=a.document?b(a,!0):function(a){if(!a.document)throw new Error("jQuery requires a window with a document");return b(a)}:b(a)}("undefined"!=typeof window?window:this,function(a,b){var c=[],d=a.document,e=c.slice,f=c.concat,g=c.push,h=c.indexOf,i={},j=i.toString,k=i.hasOwnProperty,l={},m="2.2.3",n=function(a,b){return new n.fn.init(a,b)},o=/^[\s\uFEFF\xA0]+|[\s\uFEFF\xA0]+$/g,p=/^-ms-/,q=/-([\da-z])/gi,r=function(a,b){return b.toUpperCase()};n.fn=n.prototype={jquery:m,constructor:n,selector:"",length:0,toArray:function(){return e.call(this)},get:function(a){return null!=a?0>a?this[a+this.length]:this[a]:e.call(this)},pushStack:function(a){var b=n.merge(this.constructor(),a);return b.prevObject=this,b.context=this.context,b},each:function(a){return n.each(this,a)},map:function(a){return this.pushStack(n.map(this,function(b,c){return a.call(b,c,b)}))},slice:function(){return this.pushStack(e.apply(this,arguments))},first:function(){return this.eq(0)},last:function(){return this.eq(-1)},eq:function(a){var b=this.length,c=+a+(0>a?b:0);return this.pushStack(c>=0&&b>c?[this[c]]:[])},end:function(){return this.prevObject||this.constructor()},push:g,sort:c.sort,splice:c.splice},n.extend=n.fn.extend=function(){var a,b,c,d,e,f,g=arguments[0]||{},h=1,i=arguments.length,j=!1;for("boolean"==typeof g&&(j=g,g=arguments[h]||{},h++),"object"==typeof g||n.isFunction(g)||(g={}),h===i&&(g=this,h--);i>h;h++)if(null!=(a=arguments[h]))for(b in a)c=g[b],d=a[b],g!==d&&(j&&d&&(n.isPlainObject(d)||(e=n.isArray(d)))?(e?(e=!1,f=c&&n.isArray(c)?c:[]):f=c&&n.isPlainObject(c)?c:{},g[b]=n.extend(j,f,d)):void 0!==d&&(g[b]=d));return g},n.extend({expando:"jQuery"+(m+Math.random()).replace(/\D/g,""),isReady:!0,error:function(a){throw new Error(a)},noop:function(){},isFunction:function(a){return"function"===n.type(a)},isArray:Array.isArray,isWindow:function(a){return null!=a&&a===a.window},isNumeric:function(a){var b=a&&a.toString();return!n.isArray(a)&&b-parseFloat(b)+1>=0},isPlainObject:function(a){var b;if("object"!==n.type(a)||a.nodeType||n.isWindow(a))return!1;if(a.constructor&&!k.call(a,"constructor")&&!k.call(a.constructor.prototype||{},"isPrototypeOf"))return!1;for(b in a);return void 0===b||k.call(a,b)},isEmptyObject:function(a){var b;for(b in a)return!1;return!0},type:function(a){return null==a?a+"":"object"==typeof a||"function"==typeof a?i[j.call(a)]||"object":typeof a},globalEval:function(a){var b,c=eval;a=n.trim(a),a&&(1===a.indexOf("use strict")?(b=d.createElement("script"),b.text=a,d.head.appendChild(b).parentNode.removeChild(b)):c(a))},camelCase:function(a){return a.replace(p,"ms-").replace(q,r)},nodeName:function(a,b){return a.nodeName&&a.nodeName.toLowerCase()===b.toLowerCase()},each:function(a,b){var c,d=0;if(s(a)){for(c=a.length;c>d;d++)if(b.call(a[d],d,a[d])===!1)break}else for(d in a)if(b.call(a[d],d,a[d])===!1)break;return a},trim:function(a){return null==a?"":(a+"").replace(o,"")},makeArray:function(a,b){var c=b||[];return null!=a&&(s(Object(a))?n.merge(c,"string"==typeof a?[a]:a):g.call(c,a)),c},inArray:function(a,b,c){return null==b?-1:h.call(b,a,c)},merge:function(a,b){for(var c=+b.length,d=0,e=a.length;c>d;d++)a[e++]=b[d];return a.length=e,a},grep:function(a,b,c){for(var d,e=[],f=0,g=a.length,h=!c;g>f;f++)d=!b(a[f],f),d!==h&&e.push(a[f]);return e},map:function(a,b,c){var d,e,g=0,h=[];if(s(a))for(d=a.length;d>g;g++)e=b(a[g],g,c),null!=e&&h.push(e);else for(g in a)e=b(a[g],g,c),null!=e&&h.push(e);return f.apply([],h)},guid:1,proxy:function(a,b){var c,d,f;return"string"==typeof b&&(c=a[b],b=a,a=c),n.isFunction(a)?(d=e.call(arguments,2),f=function(){return a.apply(b||this,d.concat(e.call(arguments)))},f.guid=a.guid=a.guid||n.guid++,f):void 0},now:Date.now,support:l}),"function"==typeof Symbol&&(n.fn[Symbol.iterator]=c[Symbol.iterator]),n.each("Boolean Number String Function Array Date RegExp Object Error Symbol".split(" "),function(a,b){i["[object "+b+"]"]=b.toLowerCase()});function s(a){var b=!!a&&"length"in a&&a.length,c=n.type(a);return"function"===c||n.isWindow(a)?!1:"array"===c||0===b||"number"==typeof b&&b>0&&b-1 in a}var t=function(a){var b,c,d,e,f,g,h,i,j,k,l,m,n,o,p,q,r,s,t,u="sizzle"+1*new Date,v=a.document,w=0,x=0,y=ga(),z=ga(),A=ga(),B=function(a,b){return a===b&&(l=!0),0},C=1<<31,D={}.hasOwnProperty,E=[],F=E.pop,G=E.push,H=E.push,I=E.slice,J=function(a,b){for(var c=0,d=a.length;d>c;c++)if(a[c]===b)return c;return-1},K="checked|selected|async|autofocus|autoplay|controls|defer|disabled|hidden|ismap|loop|multiple|open|readonly|required|scoped",L="[\\x20\\t\\r\\n\\f]",M="(?:\\\\.|[\\w-]|[^\\x00-\\xa0])+",N="\\["+L+"*("+M+")(?:"+L+"*([*^$|!~]?=)"+L+"*(?:'((?:\\\\.|[^\\\\'])*)'|\"((?:\\\\.|[^\\\\\"])*)\"|("+M+"))|)"+L+"*\\]",O=":("+M+")(?:\\((('((?:\\\\.|[^\\\\'])*)'|\"((?:\\\\.|[^\\\\\"])*)\")|((?:\\\\.|[^\\\\()[\\]]|"+N+")*)|.*)\\)|)",P=new RegExp(L+"+","g"),Q=new RegExp("^"+L+"+|((?:^|[^\\\\])(?:\\\\.)*)"+L+"+$","g"),R=new RegExp("^"+L+"*,"+L+"*"),S=new RegExp("^"+L+"*([>+~]|"+L+")"+L+"*"),T=new RegExp("="+L+"*([^\\]'\"]*?)"+L+"*\\]","g"),U=new RegExp(O),V=new RegExp("^"+M+"$"),W={ID:new RegExp("^#("+M+")"),CLASS:new RegExp("^\\.("+M+")"),TAG:new RegExp("^("+M+"|[*])"),ATTR:new RegExp("^"+N),PSEUDO:new RegExp("^"+O),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+L+"*(even|odd|(([+-]|)(\\d*)n|)"+L+"*(?:([+-]|)"+L+"*(\\d+)|))"+L+"*\\)|)","i"),bool:new RegExp("^(?:"+K+")$","i"),needsContext:new RegExp("^"+L+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+L+"*((?:-\\d)?\\d*)"+L+"*\\)|)(?=[^-]|$)","i")},X=/^(?:input|select|textarea|button)$/i,Y=/^h\d$/i,Z=/^[^{]+\{\s*\[native \w/,$=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,_=/[+~]/,aa=/'|\\/g,ba=new RegExp("\\\\([\\da-f]{1,6}"+L+"?|("+L+")|.)","ig"),ca=function(a,b,c){var d="0x"+b-65536;return d!==d||c?b:0>d?String.fromCharCode(d+65536):String.fromCharCode(d>>10|55296,1023&d|56320)},da=function(){m()};try{H.apply(E=I.call(v.childNodes),v.childNodes),E[v.childNodes.length].nodeType}catch(ea){H={apply:E.length?function(a,b){G.apply(a,I.call(b))}:function(a,b){var c=a.length,d=0;while(a[c++]=b[d++]);a.length=c-1}}}function fa(a,b,d,e){var f,h,j,k,l,o,r,s,w=b&&b.ownerDocument,x=b?b.nodeType:9;if(d=d||[],"string"!=typeof a||!a||1!==x&&9!==x&&11!==x)return d;if(!e&&((b?b.ownerDocument||b:v)!==n&&m(b),b=b||n,p)){if(11!==x&&(o=$.exec(a)))if(f=o[1]){if(9===x){if(!(j=b.getElementById(f)))return d;if(j.id===f)return d.push(j),d}else if(w&&(j=w.getElementById(f))&&t(b,j)&&j.id===f)return d.push(j),d}else{if(o[2])return H.apply(d,b.getElementsByTagName(a)),d;if((f=o[3])&&c.getElementsByClassName&&b.getElementsByClassName)return H.apply(d,b.getElementsByClassName(f)),d}if(c.qsa&&!A[a+" "]&&(!q||!q.test(a))){if(1!==x)w=b,s=a;else if("object"!==b.nodeName.toLowerCase()){(k=b.getAttribute("id"))?k=k.replace(aa,"\\$&"):b.setAttribute("id",k=u),r=g(a),h=r.length,l=V.test(k)?"#"+k:"[id='"+k+"']";while(h--)r[h]=l+" "+qa(r[h]);s=r.join(","),w=_.test(a)&&oa(b.parentNode)||b}if(s)try{return H.apply(d,w.querySelectorAll(s)),d}catch(y){}finally{k===u&&b.removeAttribute("id")}}}return i(a.replace(Q,"$1"),b,d,e)}function ga(){var a=[];function b(c,e){return a.push(c+" ")>d.cacheLength&&delete b[a.shift()],b[c+" "]=e}return b}function ha(a){return a[u]=!0,a}function ia(a){var b=n.createElement("div");try{return!!a(b)}catch(c){return!1}finally{b.parentNode&&b.parentNode.removeChild(b),b=null}}function ja(a,b){var c=a.split("|"),e=c.length;while(e--)d.attrHandle[c[e]]=b}function ka(a,b){var c=b&&a,d=c&&1===a.nodeType&&1===b.nodeType&&(~b.sourceIndex||C)-(~a.sourceIndex||C);if(d)return d;if(c)while(c=c.nextSibling)if(c===b)return-1;return a?1:-1}function la(a){return function(b){var c=b.nodeName.toLowerCase();return"input"===c&&b.type===a}}function ma(a){return function(b){var c=b.nodeName.toLowerCase();return("input"===c||"button"===c)&&b.type===a}}function na(a){return ha(function(b){return b=+b,ha(function(c,d){var e,f=a([],c.length,b),g=f.length;while(g--)c[e=f[g]]&&(c[e]=!(d[e]=c[e]))})})}function oa(a){return a&&"undefined"!=typeof a.getElementsByTagName&&a}c=fa.support={},f=fa.isXML=function(a){var b=a&&(a.ownerDocument||a).documentElement;return b?"HTML"!==b.nodeName:!1},m=fa.setDocument=function(a){var b,e,g=a?a.ownerDocument||a:v;return g!==n&&9===g.nodeType&&g.documentElement?(n=g,o=n.documentElement,p=!f(n),(e=n.defaultView)&&e.top!==e&&(e.addEventListener?e.addEventListener("unload",da,!1):e.attachEvent&&e.attachEvent("onunload",da)),c.attributes=ia(function(a){return a.className="i",!a.getAttribute("className")}),c.getElementsByTagName=ia(function(a){return a.appendChild(n.createComment("")),!a.getElementsByTagName("*").length}),c.getElementsByClassName=Z.test(n.getElementsByClassName),c.getById=ia(function(a){return o.appendChild(a).id=u,!n.getElementsByName||!n.getElementsByName(u).length}),c.getById?(d.find.ID=function(a,b){if("undefined"!=typeof b.getElementById&&p){var c=b.getElementById(a);return c?[c]:[]}},d.filter.ID=function(a){var b=a.replace(ba,ca);return function(a){return a.getAttribute("id")===b}}):(delete d.find.ID,d.filter.ID=function(a){var b=a.replace(ba,ca);return function(a){var c="undefined"!=typeof a.getAttributeNode&&a.getAttributeNode("id");return c&&c.value===b}}),d.find.TAG=c.getElementsByTagName?function(a,b){return"undefined"!=typeof b.getElementsByTagName?b.getElementsByTagName(a):c.qsa?b.querySelectorAll(a):void 0}:function(a,b){var c,d=[],e=0,f=b.getElementsByTagName(a);if("*"===a){while(c=f[e++])1===c.nodeType&&d.push(c);return d}return f},d.find.CLASS=c.getElementsByClassName&&function(a,b){return"undefined"!=typeof b.getElementsByClassName&&p?b.getElementsByClassName(a):void 0},r=[],q=[],(c.qsa=Z.test(n.querySelectorAll))&&(ia(function(a){o.appendChild(a).innerHTML="<a id='"+u+"'></a><select id='"+u+"-\r\\' msallowcapture=''><option selected=''></option></select>",a.querySelectorAll("[msallowcapture^='']").length&&q.push("[*^$]="+L+"*(?:''|\"\")"),a.querySelectorAll("[selected]").length||q.push("\\["+L+"*(?:value|"+K+")"),a.querySelectorAll("[id~="+u+"-]").length||q.push("~="),a.querySelectorAll(":checked").length||q.push(":checked"),a.querySelectorAll("a#"+u+"+*").length||q.push(".#.+[+~]")}),ia(function(a){var b=n.createElement("input");b.setAttribute("type","hidden"),a.appendChild(b).setAttribute("name","D"),a.querySelectorAll("[name=d]").length&&q.push("name"+L+"*[*^$|!~]?="),a.querySelectorAll(":enabled").length||q.push(":enabled",":disabled"),a.querySelectorAll("*,:x"),q.push(",.*:")})),(c.matchesSelector=Z.test(s=o.matches||o.webkitMatchesSelector||o.mozMatchesSelector||o.oMatchesSelector||o.msMatchesSelector))&&ia(function(a){c.disconnectedMatch=s.call(a,"div"),s.call(a,"[s!='']:x"),r.push("!=",O)}),q=q.length&&new RegExp(q.join("|")),r=r.length&&new RegExp(r.join("|")),b=Z.test(o.compareDocumentPosition),t=b||Z.test(o.contains)?function(a,b){var c=9===a.nodeType?a.documentElement:a,d=b&&b.parentNode;return a===d||!(!d||1!==d.nodeType||!(c.contains?c.contains(d):a.compareDocumentPosition&&16&a.compareDocumentPosition(d)))}:function(a,b){if(b)while(b=b.parentNode)if(b===a)return!0;return!1},B=b?function(a,b){if(a===b)return l=!0,0;var d=!a.compareDocumentPosition-!b.compareDocumentPosition;return d?d:(d=(a.ownerDocument||a)===(b.ownerDocument||b)?a.compareDocumentPosition(b):1,1&d||!c.sortDetached&&b.compareDocumentPosition(a)===d?a===n||a.ownerDocument===v&&t(v,a)?-1:b===n||b.ownerDocument===v&&t(v,b)?1:k?J(k,a)-J(k,b):0:4&d?-1:1)}:function(a,b){if(a===b)return l=!0,0;var c,d=0,e=a.parentNode,f=b.parentNode,g=[a],h=[b];if(!e||!f)return a===n?-1:b===n?1:e?-1:f?1:k?J(k,a)-J(k,b):0;if(e===f)return ka(a,b);c=a;while(c=c.parentNode)g.unshift(c);c=b;while(c=c.parentNode)h.unshift(c);while(g[d]===h[d])d++;return d?ka(g[d],h[d]):g[d]===v?-1:h[d]===v?1:0},n):n},fa.matches=function(a,b){return fa(a,null,null,b)},fa.matchesSelector=function(a,b){if((a.ownerDocument||a)!==n&&m(a),b=b.replace(T,"='$1']"),c.matchesSelector&&p&&!A[b+" "]&&(!r||!r.test(b))&&(!q||!q.test(b)))try{var d=s.call(a,b);if(d||c.disconnectedMatch||a.document&&11!==a.document.nodeType)return d}catch(e){}return fa(b,n,null,[a]).length>0},fa.contains=function(a,b){return(a.ownerDocument||a)!==n&&m(a),t(a,b)},fa.attr=function(a,b){(a.ownerDocument||a)!==n&&m(a);var e=d.attrHandle[b.toLowerCase()],f=e&&D.call(d.attrHandle,b.toLowerCase())?e(a,b,!p):void 0;return void 0!==f?f:c.attributes||!p?a.getAttribute(b):(f=a.getAttributeNode(b))&&f.specified?f.value:null},fa.error=function(a){throw new Error("Syntax error, unrecognized expression: "+a)},fa.uniqueSort=function(a){var b,d=[],e=0,f=0;if(l=!c.detectDuplicates,k=!c.sortStable&&a.slice(0),a.sort(B),l){while(b=a[f++])b===a[f]&&(e=d.push(f));while(e--)a.splice(d[e],1)}return k=null,a},e=fa.getText=function(a){var b,c="",d=0,f=a.nodeType;if(f){if(1===f||9===f||11===f){if("string"==typeof a.textContent)return a.textContent;for(a=a.firstChild;a;a=a.nextSibling)c+=e(a)}else if(3===f||4===f)return a.nodeValue}else while(b=a[d++])c+=e(b);return c},d=fa.selectors={cacheLength:50,createPseudo:ha,match:W,attrHandle:{},find:{},relative:{">":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(a){return a[1]=a[1].replace(ba,ca),a[3]=(a[3]||a[4]||a[5]||"").replace(ba,ca),"~="===a[2]&&(a[3]=" "+a[3]+" "),a.slice(0,4)},CHILD:function(a){return a[1]=a[1].toLowerCase(),"nth"===a[1].slice(0,3)?(a[3]||fa.error(a[0]),a[4]=+(a[4]?a[5]+(a[6]||1):2*("even"===a[3]||"odd"===a[3])),a[5]=+(a[7]+a[8]||"odd"===a[3])):a[3]&&fa.error(a[0]),a},PSEUDO:function(a){var b,c=!a[6]&&a[2];return W.CHILD.test(a[0])?null:(a[3]?a[2]=a[4]||a[5]||"":c&&U.test(c)&&(b=g(c,!0))&&(b=c.indexOf(")",c.length-b)-c.length)&&(a[0]=a[0].slice(0,b),a[2]=c.slice(0,b)),a.slice(0,3))}},filter:{TAG:function(a){var b=a.replace(ba,ca).toLowerCase();return"*"===a?function(){return!0}:function(a){return a.nodeName&&a.nodeName.toLowerCase()===b}},CLASS:function(a){var b=y[a+" "];return b||(b=new RegExp("(^|"+L+")"+a+"("+L+"|$)"))&&y(a,function(a){return b.test("string"==typeof a.className&&a.className||"undefined"!=typeof a.getAttribute&&a.getAttribute("class")||"")})},ATTR:function(a,b,c){return function(d){var e=fa.attr(d,a);return null==e?"!="===b:b?(e+="","="===b?e===c:"!="===b?e!==c:"^="===b?c&&0===e.indexOf(c):"*="===b?c&&e.indexOf(c)>-1:"$="===b?c&&e.slice(-c.length)===c:"~="===b?(" "+e.replace(P," ")+" ").indexOf(c)>-1:"|="===b?e===c||e.slice(0,c.length+1)===c+"-":!1):!0}},CHILD:function(a,b,c,d,e){var f="nth"!==a.slice(0,3),g="last"!==a.slice(-4),h="of-type"===b;return 1===d&&0===e?function(a){return!!a.parentNode}:function(b,c,i){var j,k,l,m,n,o,p=f!==g?"nextSibling":"previousSibling",q=b.parentNode,r=h&&b.nodeName.toLowerCase(),s=!i&&!h,t=!1;if(q){if(f){while(p){m=b;while(m=m[p])if(h?m.nodeName.toLowerCase()===r:1===m.nodeType)return!1;o=p="only"===a&&!o&&"nextSibling"}return!0}if(o=[g?q.firstChild:q.lastChild],g&&s){m=q,l=m[u]||(m[u]={}),k=l[m.uniqueID]||(l[m.uniqueID]={}),j=k[a]||[],n=j[0]===w&&j[1],t=n&&j[2],m=n&&q.childNodes[n];while(m=++n&&m&&m[p]||(t=n=0)||o.pop())if(1===m.nodeType&&++t&&m===b){k[a]=[w,n,t];break}}else if(s&&(m=b,l=m[u]||(m[u]={}),k=l[m.uniqueID]||(l[m.uniqueID]={}),j=k[a]||[],n=j[0]===w&&j[1],t=n),t===!1)while(m=++n&&m&&m[p]||(t=n=0)||o.pop())if((h?m.nodeName.toLowerCase()===r:1===m.nodeType)&&++t&&(s&&(l=m[u]||(m[u]={}),k=l[m.uniqueID]||(l[m.uniqueID]={}),k[a]=[w,t]),m===b))break;return t-=e,t===d||t%d===0&&t/d>=0}}},PSEUDO:function(a,b){var c,e=d.pseudos[a]||d.setFilters[a.toLowerCase()]||fa.error("unsupported pseudo: "+a);return e[u]?e(b):e.length>1?(c=[a,a,"",b],d.setFilters.hasOwnProperty(a.toLowerCase())?ha(function(a,c){var d,f=e(a,b),g=f.length;while(g--)d=J(a,f[g]),a[d]=!(c[d]=f[g])}):function(a){return e(a,0,c)}):e}},pseudos:{not:ha(function(a){var b=[],c=[],d=h(a.replace(Q,"$1"));return d[u]?ha(function(a,b,c,e){var f,g=d(a,null,e,[]),h=a.length;while(h--)(f=g[h])&&(a[h]=!(b[h]=f))}):function(a,e,f){return b[0]=a,d(b,null,f,c),b[0]=null,!c.pop()}}),has:ha(function(a){return function(b){return fa(a,b).length>0}}),contains:ha(function(a){return a=a.replace(ba,ca),function(b){return(b.textContent||b.innerText||e(b)).indexOf(a)>-1}}),lang:ha(function(a){return V.test(a||"")||fa.error("unsupported lang: "+a),a=a.replace(ba,ca).toLowerCase(),function(b){var c;do if(c=p?b.lang:b.getAttribute("xml:lang")||b.getAttribute("lang"))return c=c.toLowerCase(),c===a||0===c.indexOf(a+"-");while((b=b.parentNode)&&1===b.nodeType);return!1}}),target:function(b){var c=a.location&&a.location.hash;return c&&c.slice(1)===b.id},root:function(a){return a===o},focus:function(a){return a===n.activeElement&&(!n.hasFocus||n.hasFocus())&&!!(a.type||a.href||~a.tabIndex)},enabled:function(a){return a.disabled===!1},disabled:function(a){return a.disabled===!0},checked:function(a){var b=a.nodeName.toLowerCase();return"input"===b&&!!a.checked||"option"===b&&!!a.selected},selected:function(a){return a.parentNode&&a.parentNode.selectedIndex,a.selected===!0},empty:function(a){for(a=a.firstChild;a;a=a.nextSibling)if(a.nodeType<6)return!1;return!0},parent:function(a){return!d.pseudos.empty(a)},header:function(a){return Y.test(a.nodeName)},input:function(a){return X.test(a.nodeName)},button:function(a){var b=a.nodeName.toLowerCase();return"input"===b&&"button"===a.type||"button"===b},text:function(a){var b;return"input"===a.nodeName.toLowerCase()&&"text"===a.type&&(null==(b=a.getAttribute("type"))||"text"===b.toLowerCase())},first:na(function(){return[0]}),last:na(function(a,b){return[b-1]}),eq:na(function(a,b,c){return[0>c?c+b:c]}),even:na(function(a,b){for(var c=0;b>c;c+=2)a.push(c);return a}),odd:na(function(a,b){for(var c=1;b>c;c+=2)a.push(c);return a}),lt:na(function(a,b,c){for(var d=0>c?c+b:c;--d>=0;)a.push(d);return a}),gt:na(function(a,b,c){for(var d=0>c?c+b:c;++d<b;)a.push(d);return a})}},d.pseudos.nth=d.pseudos.eq;for(b in{radio:!0,checkbox:!0,file:!0,password:!0,image:!0})d.pseudos[b]=la(b);for(b in{submit:!0,reset:!0})d.pseudos[b]=ma(b);function pa(){}pa.prototype=d.filters=d.pseudos,d.setFilters=new pa,g=fa.tokenize=function(a,b){var c,e,f,g,h,i,j,k=z[a+" "];if(k)return b?0:k.slice(0);h=a,i=[],j=d.preFilter;while(h){c&&!(e=R.exec(h))||(e&&(h=h.slice(e[0].length)||h),i.push(f=[])),c=!1,(e=S.exec(h))&&(c=e.shift(),f.push({value:c,type:e[0].replace(Q," ")}),h=h.slice(c.length));for(g in d.filter)!(e=W[g].exec(h))||j[g]&&!(e=j[g](e))||(c=e.shift(),f.push({value:c,type:g,matches:e}),h=h.slice(c.length));if(!c)break}return b?h.length:h?fa.error(a):z(a,i).slice(0)};function qa(a){for(var b=0,c=a.length,d="";c>b;b++)d+=a[b].value;return d}function ra(a,b,c){var d=b.dir,e=c&&"parentNode"===d,f=x++;return b.first?function(b,c,f){while(b=b[d])if(1===b.nodeType||e)return a(b,c,f)}:function(b,c,g){var h,i,j,k=[w,f];if(g){while(b=b[d])if((1===b.nodeType||e)&&a(b,c,g))return!0}else while(b=b[d])if(1===b.nodeType||e){if(j=b[u]||(b[u]={}),i=j[b.uniqueID]||(j[b.uniqueID]={}),(h=i[d])&&h[0]===w&&h[1]===f)return k[2]=h[2];if(i[d]=k,k[2]=a(b,c,g))return!0}}}function sa(a){return a.length>1?function(b,c,d){var e=a.length;while(e--)if(!a[e](b,c,d))return!1;return!0}:a[0]}function ta(a,b,c){for(var d=0,e=b.length;e>d;d++)fa(a,b[d],c);return c}function ua(a,b,c,d,e){for(var f,g=[],h=0,i=a.length,j=null!=b;i>h;h++)(f=a[h])&&(c&&!c(f,d,e)||(g.push(f),j&&b.push(h)));return g}function va(a,b,c,d,e,f){return d&&!d[u]&&(d=va(d)),e&&!e[u]&&(e=va(e,f)),ha(function(f,g,h,i){var j,k,l,m=[],n=[],o=g.length,p=f||ta(b||"*",h.nodeType?[h]:h,[]),q=!a||!f&&b?p:ua(p,m,a,h,i),r=c?e||(f?a:o||d)?[]:g:q;if(c&&c(q,r,h,i),d){j=ua(r,n),d(j,[],h,i),k=j.length;while(k--)(l=j[k])&&(r[n[k]]=!(q[n[k]]=l))}if(f){if(e||a){if(e){j=[],k=r.length;while(k--)(l=r[k])&&j.push(q[k]=l);e(null,r=[],j,i)}k=r.length;while(k--)(l=r[k])&&(j=e?J(f,l):m[k])>-1&&(f[j]=!(g[j]=l))}}else r=ua(r===g?r.splice(o,r.length):r),e?e(null,g,r,i):H.apply(g,r)})}function wa(a){for(var b,c,e,f=a.length,g=d.relative[a[0].type],h=g||d.relative[" "],i=g?1:0,k=ra(function(a){return a===b},h,!0),l=ra(function(a){return J(b,a)>-1},h,!0),m=[function(a,c,d){var e=!g&&(d||c!==j)||((b=c).nodeType?k(a,c,d):l(a,c,d));return b=null,e}];f>i;i++)if(c=d.relative[a[i].type])m=[ra(sa(m),c)];else{if(c=d.filter[a[i].type].apply(null,a[i].matches),c[u]){for(e=++i;f>e;e++)if(d.relative[a[e].type])break;return va(i>1&&sa(m),i>1&&qa(a.slice(0,i-1).concat({value:" "===a[i-2].type?"*":""})).replace(Q,"$1"),c,e>i&&wa(a.slice(i,e)),f>e&&wa(a=a.slice(e)),f>e&&qa(a))}m.push(c)}return sa(m)}function xa(a,b){var c=b.length>0,e=a.length>0,f=function(f,g,h,i,k){var l,o,q,r=0,s="0",t=f&&[],u=[],v=j,x=f||e&&d.find.TAG("*",k),y=w+=null==v?1:Math.random()||.1,z=x.length;for(k&&(j=g===n||g||k);s!==z&&null!=(l=x[s]);s++){if(e&&l){o=0,g||l.ownerDocument===n||(m(l),h=!p);while(q=a[o++])if(q(l,g||n,h)){i.push(l);break}k&&(w=y)}c&&((l=!q&&l)&&r--,f&&t.push(l))}if(r+=s,c&&s!==r){o=0;while(q=b[o++])q(t,u,g,h);if(f){if(r>0)while(s--)t[s]||u[s]||(u[s]=F.call(i));u=ua(u)}H.apply(i,u),k&&!f&&u.length>0&&r+b.length>1&&fa.uniqueSort(i)}return k&&(w=y,j=v),t};return c?ha(f):f}return h=fa.compile=function(a,b){var c,d=[],e=[],f=A[a+" "];if(!f){b||(b=g(a)),c=b.length;while(c--)f=wa(b[c]),f[u]?d.push(f):e.push(f);f=A(a,xa(e,d)),f.selector=a}return f},i=fa.select=function(a,b,e,f){var i,j,k,l,m,n="function"==typeof a&&a,o=!f&&g(a=n.selector||a);if(e=e||[],1===o.length){if(j=o[0]=o[0].slice(0),j.length>2&&"ID"===(k=j[0]).type&&c.getById&&9===b.nodeType&&p&&d.relative[j[1].type]){if(b=(d.find.ID(k.matches[0].replace(ba,ca),b)||[])[0],!b)return e;n&&(b=b.parentNode),a=a.slice(j.shift().value.length)}i=W.needsContext.test(a)?0:j.length;while(i--){if(k=j[i],d.relative[l=k.type])break;if((m=d.find[l])&&(f=m(k.matches[0].replace(ba,ca),_.test(j[0].type)&&oa(b.parentNode)||b))){if(j.splice(i,1),a=f.length&&qa(j),!a)return H.apply(e,f),e;break}}}return(n||h(a,o))(f,b,!p,e,!b||_.test(a)&&oa(b.parentNode)||b),e},c.sortStable=u.split("").sort(B).join("")===u,c.detectDuplicates=!!l,m(),c.sortDetached=ia(function(a){return 1&a.compareDocumentPosition(n.createElement("div"))}),ia(function(a){return a.innerHTML="<a href='#'></a>","#"===a.firstChild.getAttribute("href")})||ja("type|href|height|width",function(a,b,c){return c?void 0:a.getAttribute(b,"type"===b.toLowerCase()?1:2)}),c.attributes&&ia(function(a){return a.innerHTML="<input/>",a.firstChild.setAttribute("value",""),""===a.firstChild.getAttribute("value")})||ja("value",function(a,b,c){return c||"input"!==a.nodeName.toLowerCase()?void 0:a.defaultValue}),ia(function(a){return null==a.getAttribute("disabled")})||ja(K,function(a,b,c){var d;return c?void 0:a[b]===!0?b.toLowerCase():(d=a.getAttributeNode(b))&&d.specified?d.value:null}),fa}(a);n.find=t,n.expr=t.selectors,n.expr[":"]=n.expr.pseudos,n.uniqueSort=n.unique=t.uniqueSort,n.text=t.getText,n.isXMLDoc=t.isXML,n.contains=t.contains;var u=function(a,b,c){var d=[],e=void 0!==c;while((a=a[b])&&9!==a.nodeType)if(1===a.nodeType){if(e&&n(a).is(c))break;d.push(a)}return d},v=function(a,b){for(var c=[];a;a=a.nextSibling)1===a.nodeType&&a!==b&&c.push(a);return c},w=n.expr.match.needsContext,x=/^<([\w-]+)\s*\/?>(?:<\/\1>|)$/,y=/^.[^:#\[\.,]*$/;function z(a,b,c){if(n.isFunction(b))return n.grep(a,function(a,d){return!!b.call(a,d,a)!==c});if(b.nodeType)return n.grep(a,function(a){return a===b!==c});if("string"==typeof b){if(y.test(b))return n.filter(b,a,c);b=n.filter(b,a)}return n.grep(a,function(a){return h.call(b,a)>-1!==c})}n.filter=function(a,b,c){var d=b[0];return c&&(a=":not("+a+")"),1===b.length&&1===d.nodeType?n.find.matchesSelector(d,a)?[d]:[]:n.find.matches(a,n.grep(b,function(a){return 1===a.nodeType}))},n.fn.extend({find:function(a){var b,c=this.length,d=[],e=this;if("string"!=typeof a)return this.pushStack(n(a).filter(function(){for(b=0;c>b;b++)if(n.contains(e[b],this))return!0}));for(b=0;c>b;b++)n.find(a,e[b],d);return d=this.pushStack(c>1?n.unique(d):d),d.selector=this.selector?this.selector+" "+a:a,d},filter:function(a){return this.pushStack(z(this,a||[],!1))},not:function(a){return this.pushStack(z(this,a||[],!0))},is:function(a){return!!z(this,"string"==typeof a&&w.test(a)?n(a):a||[],!1).length}});var A,B=/^(?:\s*(<[\w\W]+>)[^>]*|#([\w-]*))$/,C=n.fn.init=function(a,b,c){var e,f;if(!a)return this;if(c=c||A,"string"==typeof a){if(e="<"===a[0]&&">"===a[a.length-1]&&a.length>=3?[null,a,null]:B.exec(a),!e||!e[1]&&b)return!b||b.jquery?(b||c).find(a):this.constructor(b).find(a);if(e[1]){if(b=b instanceof n?b[0]:b,n.merge(this,n.parseHTML(e[1],b&&b.nodeType?b.ownerDocument||b:d,!0)),x.test(e[1])&&n.isPlainObject(b))for(e in b)n.isFunction(this[e])?this[e](b[e]):this.attr(e,b[e]);return this}return f=d.getElementById(e[2]),f&&f.parentNode&&(this.length=1,this[0]=f),this.context=d,this.selector=a,this}return a.nodeType?(this.context=this[0]=a,this.length=1,this):n.isFunction(a)?void 0!==c.ready?c.ready(a):a(n):(void 0!==a.selector&&(this.selector=a.selector,this.context=a.context),n.makeArray(a,this))};C.prototype=n.fn,A=n(d);var D=/^(?:parents|prev(?:Until|All))/,E={children:!0,contents:!0,next:!0,prev:!0};n.fn.extend({has:function(a){var b=n(a,this),c=b.length;return this.filter(function(){for(var a=0;c>a;a++)if(n.contains(this,b[a]))return!0})},closest:function(a,b){for(var c,d=0,e=this.length,f=[],g=w.test(a)||"string"!=typeof a?n(a,b||this.context):0;e>d;d++)for(c=this[d];c&&c!==b;c=c.parentNode)if(c.nodeType<11&&(g?g.index(c)>-1:1===c.nodeType&&n.find.matchesSelector(c,a))){f.push(c);break}return this.pushStack(f.length>1?n.uniqueSort(f):f)},index:function(a){return a?"string"==typeof a?h.call(n(a),this[0]):h.call(this,a.jquery?a[0]:a):this[0]&&this[0].parentNode?this.first().prevAll().length:-1},add:function(a,b){return this.pushStack(n.uniqueSort(n.merge(this.get(),n(a,b))))},addBack:function(a){return this.add(null==a?this.prevObject:this.prevObject.filter(a))}});function F(a,b){while((a=a[b])&&1!==a.nodeType);return a}n.each({parent:function(a){var b=a.parentNode;return b&&11!==b.nodeType?b:null},parents:function(a){return u(a,"parentNode")},parentsUntil:function(a,b,c){return u(a,"parentNode",c)},next:function(a){return F(a,"nextSibling")},prev:function(a){return F(a,"previousSibling")},nextAll:function(a){return u(a,"nextSibling")},prevAll:function(a){return u(a,"previousSibling")},nextUntil:function(a,b,c){return u(a,"nextSibling",c)},prevUntil:function(a,b,c){return u(a,"previousSibling",c)},siblings:function(a){return v((a.parentNode||{}).firstChild,a)},children:function(a){return v(a.firstChild)},contents:function(a){return a.contentDocument||n.merge([],a.childNodes)}},function(a,b){n.fn[a]=function(c,d){var e=n.map(this,b,c);return"Until"!==a.slice(-5)&&(d=c),d&&"string"==typeof d&&(e=n.filter(d,e)),this.length>1&&(E[a]||n.uniqueSort(e),D.test(a)&&e.reverse()),this.pushStack(e)}});var G=/\S+/g;function H(a){var b={};return n.each(a.match(G)||[],function(a,c){b[c]=!0}),b}n.Callbacks=function(a){a="string"==typeof a?H(a):n.extend({},a);var b,c,d,e,f=[],g=[],h=-1,i=function(){for(e=a.once,d=b=!0;g.length;h=-1){c=g.shift();while(++h<f.length)f[h].apply(c[0],c[1])===!1&&a.stopOnFalse&&(h=f.length,c=!1)}a.memory||(c=!1),b=!1,e&&(f=c?[]:"")},j={add:function(){return f&&(c&&!b&&(h=f.length-1,g.push(c)),function d(b){n.each(b,function(b,c){n.isFunction(c)?a.unique&&j.has(c)||f.push(c):c&&c.length&&"string"!==n.type(c)&&d(c)})}(arguments),c&&!b&&i()),this},remove:function(){return n.each(arguments,function(a,b){var c;while((c=n.inArray(b,f,c))>-1)f.splice(c,1),h>=c&&h--}),this},has:function(a){return a?n.inArray(a,f)>-1:f.length>0},empty:function(){return f&&(f=[]),this},disable:function(){return e=g=[],f=c="",this},disabled:function(){return!f},lock:function(){return e=g=[],c||(f=c=""),this},locked:function(){return!!e},fireWith:function(a,c){return e||(c=c||[],c=[a,c.slice?c.slice():c],g.push(c),b||i()),this},fire:function(){return j.fireWith(this,arguments),this},fired:function(){return!!d}};return j},n.extend({Deferred:function(a){var b=[["resolve","done",n.Callbacks("once memory"),"resolved"],["reject","fail",n.Callbacks("once memory"),"rejected"],["notify","progress",n.Callbacks("memory")]],c="pending",d={state:function(){return c},always:function(){return e.done(arguments).fail(arguments),this},then:function(){var a=arguments;return n.Deferred(function(c){n.each(b,function(b,f){var g=n.isFunction(a[b])&&a[b];e[f[1]](function(){var a=g&&g.apply(this,arguments);a&&n.isFunction(a.promise)?a.promise().progress(c.notify).done(c.resolve).fail(c.reject):c[f[0]+"With"](this===d?c.promise():this,g?[a]:arguments)})}),a=null}).promise()},promise:function(a){return null!=a?n.extend(a,d):d}},e={};return d.pipe=d.then,n.each(b,function(a,f){var g=f[2],h=f[3];d[f[1]]=g.add,h&&g.add(function(){c=h},b[1^a][2].disable,b[2][2].lock),e[f[0]]=function(){return e[f[0]+"With"](this===e?d:this,arguments),this},e[f[0]+"With"]=g.fireWith}),d.promise(e),a&&a.call(e,e),e},when:function(a){var b=0,c=e.call(arguments),d=c.length,f=1!==d||a&&n.isFunction(a.promise)?d:0,g=1===f?a:n.Deferred(),h=function(a,b,c){return function(d){b[a]=this,c[a]=arguments.length>1?e.call(arguments):d,c===i?g.notifyWith(b,c):--f||g.resolveWith(b,c)}},i,j,k;if(d>1)for(i=new Array(d),j=new Array(d),k=new Array(d);d>b;b++)c[b]&&n.isFunction(c[b].promise)?c[b].promise().progress(h(b,j,i)).done(h(b,k,c)).fail(g.reject):--f;return f||g.resolveWith(k,c),g.promise()}});var I;n.fn.ready=function(a){return n.ready.promise().done(a),this},n.extend({isReady:!1,readyWait:1,holdReady:function(a){a?n.readyWait++:n.ready(!0)},ready:function(a){(a===!0?--n.readyWait:n.isReady)||(n.isReady=!0,a!==!0&&--n.readyWait>0||(I.resolveWith(d,[n]),n.fn.triggerHandler&&(n(d).triggerHandler("ready"),n(d).off("ready"))))}});function J(){d.removeEventListener("DOMContentLoaded",J),a.removeEventListener("load",J),n.ready()}n.ready.promise=function(b){return I||(I=n.Deferred(),"complete"===d.readyState||"loading"!==d.readyState&&!d.documentElement.doScroll?a.setTimeout(n.ready):(d.addEventListener("DOMContentLoaded",J),a.addEventListener("load",J))),I.promise(b)},n.ready.promise();var K=function(a,b,c,d,e,f,g){var h=0,i=a.length,j=null==c;if("object"===n.type(c)){e=!0;for(h in c)K(a,b,h,c[h],!0,f,g)}else if(void 0!==d&&(e=!0,n.isFunction(d)||(g=!0),j&&(g?(b.call(a,d),b=null):(j=b,b=function(a,b,c){return j.call(n(a),c)})),b))for(;i>h;h++)b(a[h],c,g?d:d.call(a[h],h,b(a[h],c)));return e?a:j?b.call(a):i?b(a[0],c):f},L=function(a){return 1===a.nodeType||9===a.nodeType||!+a.nodeType};function M(){this.expando=n.expando+M.uid++}M.uid=1,M.prototype={register:function(a,b){var c=b||{};return a.nodeType?a[this.expando]=c:Object.defineProperty(a,this.expando,{value:c,writable:!0,configurable:!0}),a[this.expando]},cache:function(a){if(!L(a))return{};var b=a[this.expando];return b||(b={},L(a)&&(a.nodeType?a[this.expando]=b:Object.defineProperty(a,this.expando,{value:b,configurable:!0}))),b},set:function(a,b,c){var d,e=this.cache(a);if("string"==typeof b)e[b]=c;else for(d in b)e[d]=b[d];return e},get:function(a,b){return void 0===b?this.cache(a):a[this.expando]&&a[this.expando][b]},access:function(a,b,c){var d;return void 0===b||b&&"string"==typeof b&&void 0===c?(d=this.get(a,b),void 0!==d?d:this.get(a,n.camelCase(b))):(this.set(a,b,c),void 0!==c?c:b)},remove:function(a,b){var c,d,e,f=a[this.expando];if(void 0!==f){if(void 0===b)this.register(a);else{n.isArray(b)?d=b.concat(b.map(n.camelCase)):(e=n.camelCase(b),b in f?d=[b,e]:(d=e,d=d in f?[d]:d.match(G)||[])),c=d.length;while(c--)delete f[d[c]]}(void 0===b||n.isEmptyObject(f))&&(a.nodeType?a[this.expando]=void 0:delete a[this.expando])}},hasData:function(a){var b=a[this.expando];return void 0!==b&&!n.isEmptyObject(b)}};var N=new M,O=new M,P=/^(?:\{[\w\W]*\}|\[[\w\W]*\])$/,Q=/[A-Z]/g;function R(a,b,c){var d;if(void 0===c&&1===a.nodeType)if(d="data-"+b.replace(Q,"-$&").toLowerCase(),c=a.getAttribute(d),"string"==typeof c){try{c="true"===c?!0:"false"===c?!1:"null"===c?null:+c+""===c?+c:P.test(c)?n.parseJSON(c):c;
+}catch(e){}O.set(a,b,c)}else c=void 0;return c}n.extend({hasData:function(a){return O.hasData(a)||N.hasData(a)},data:function(a,b,c){return O.access(a,b,c)},removeData:function(a,b){O.remove(a,b)},_data:function(a,b,c){return N.access(a,b,c)},_removeData:function(a,b){N.remove(a,b)}}),n.fn.extend({data:function(a,b){var c,d,e,f=this[0],g=f&&f.attributes;if(void 0===a){if(this.length&&(e=O.get(f),1===f.nodeType&&!N.get(f,"hasDataAttrs"))){c=g.length;while(c--)g[c]&&(d=g[c].name,0===d.indexOf("data-")&&(d=n.camelCase(d.slice(5)),R(f,d,e[d])));N.set(f,"hasDataAttrs",!0)}return e}return"object"==typeof a?this.each(function(){O.set(this,a)}):K(this,function(b){var c,d;if(f&&void 0===b){if(c=O.get(f,a)||O.get(f,a.replace(Q,"-$&").toLowerCase()),void 0!==c)return c;if(d=n.camelCase(a),c=O.get(f,d),void 0!==c)return c;if(c=R(f,d,void 0),void 0!==c)return c}else d=n.camelCase(a),this.each(function(){var c=O.get(this,d);O.set(this,d,b),a.indexOf("-")>-1&&void 0!==c&&O.set(this,a,b)})},null,b,arguments.length>1,null,!0)},removeData:function(a){return this.each(function(){O.remove(this,a)})}}),n.extend({queue:function(a,b,c){var d;return a?(b=(b||"fx")+"queue",d=N.get(a,b),c&&(!d||n.isArray(c)?d=N.access(a,b,n.makeArray(c)):d.push(c)),d||[]):void 0},dequeue:function(a,b){b=b||"fx";var c=n.queue(a,b),d=c.length,e=c.shift(),f=n._queueHooks(a,b),g=function(){n.dequeue(a,b)};"inprogress"===e&&(e=c.shift(),d--),e&&("fx"===b&&c.unshift("inprogress"),delete f.stop,e.call(a,g,f)),!d&&f&&f.empty.fire()},_queueHooks:function(a,b){var c=b+"queueHooks";return N.get(a,c)||N.access(a,c,{empty:n.Callbacks("once memory").add(function(){N.remove(a,[b+"queue",c])})})}}),n.fn.extend({queue:function(a,b){var c=2;return"string"!=typeof a&&(b=a,a="fx",c--),arguments.length<c?n.queue(this[0],a):void 0===b?this:this.each(function(){var c=n.queue(this,a,b);n._queueHooks(this,a),"fx"===a&&"inprogress"!==c[0]&&n.dequeue(this,a)})},dequeue:function(a){return this.each(function(){n.dequeue(this,a)})},clearQueue:function(a){return this.queue(a||"fx",[])},promise:function(a,b){var c,d=1,e=n.Deferred(),f=this,g=this.length,h=function(){--d||e.resolveWith(f,[f])};"string"!=typeof a&&(b=a,a=void 0),a=a||"fx";while(g--)c=N.get(f[g],a+"queueHooks"),c&&c.empty&&(d++,c.empty.add(h));return h(),e.promise(b)}});var S=/[+-]?(?:\d*\.|)\d+(?:[eE][+-]?\d+|)/.source,T=new RegExp("^(?:([+-])=|)("+S+")([a-z%]*)$","i"),U=["Top","Right","Bottom","Left"],V=function(a,b){return a=b||a,"none"===n.css(a,"display")||!n.contains(a.ownerDocument,a)};function W(a,b,c,d){var e,f=1,g=20,h=d?function(){return d.cur()}:function(){return n.css(a,b,"")},i=h(),j=c&&c[3]||(n.cssNumber[b]?"":"px"),k=(n.cssNumber[b]||"px"!==j&&+i)&&T.exec(n.css(a,b));if(k&&k[3]!==j){j=j||k[3],c=c||[],k=+i||1;do f=f||".5",k/=f,n.style(a,b,k+j);while(f!==(f=h()/i)&&1!==f&&--g)}return c&&(k=+k||+i||0,e=c[1]?k+(c[1]+1)*c[2]:+c[2],d&&(d.unit=j,d.start=k,d.end=e)),e}var X=/^(?:checkbox|radio)$/i,Y=/<([\w:-]+)/,Z=/^$|\/(?:java|ecma)script/i,$={option:[1,"<select multiple='multiple'>","</select>"],thead:[1,"<table>","</table>"],col:[2,"<table><colgroup>","</colgroup></table>"],tr:[2,"<table><tbody>","</tbody></table>"],td:[3,"<table><tbody><tr>","</tr></tbody></table>"],_default:[0,"",""]};$.optgroup=$.option,$.tbody=$.tfoot=$.colgroup=$.caption=$.thead,$.th=$.td;function _(a,b){var c="undefined"!=typeof a.getElementsByTagName?a.getElementsByTagName(b||"*"):"undefined"!=typeof a.querySelectorAll?a.querySelectorAll(b||"*"):[];return void 0===b||b&&n.nodeName(a,b)?n.merge([a],c):c}function aa(a,b){for(var c=0,d=a.length;d>c;c++)N.set(a[c],"globalEval",!b||N.get(b[c],"globalEval"))}var ba=/<|&#?\w+;/;function ca(a,b,c,d,e){for(var f,g,h,i,j,k,l=b.createDocumentFragment(),m=[],o=0,p=a.length;p>o;o++)if(f=a[o],f||0===f)if("object"===n.type(f))n.merge(m,f.nodeType?[f]:f);else if(ba.test(f)){g=g||l.appendChild(b.createElement("div")),h=(Y.exec(f)||["",""])[1].toLowerCase(),i=$[h]||$._default,g.innerHTML=i[1]+n.htmlPrefilter(f)+i[2],k=i[0];while(k--)g=g.lastChild;n.merge(m,g.childNodes),g=l.firstChild,g.textContent=""}else m.push(b.createTextNode(f));l.textContent="",o=0;while(f=m[o++])if(d&&n.inArray(f,d)>-1)e&&e.push(f);else if(j=n.contains(f.ownerDocument,f),g=_(l.appendChild(f),"script"),j&&aa(g),c){k=0;while(f=g[k++])Z.test(f.type||"")&&c.push(f)}return l}!function(){var a=d.createDocumentFragment(),b=a.appendChild(d.createElement("div")),c=d.createElement("input");c.setAttribute("type","radio"),c.setAttribute("checked","checked"),c.setAttribute("name","t"),b.appendChild(c),l.checkClone=b.cloneNode(!0).cloneNode(!0).lastChild.checked,b.innerHTML="<textarea>x</textarea>",l.noCloneChecked=!!b.cloneNode(!0).lastChild.defaultValue}();var da=/^key/,ea=/^(?:mouse|pointer|contextmenu|drag|drop)|click/,fa=/^([^.]*)(?:\.(.+)|)/;function ga(){return!0}function ha(){return!1}function ia(){try{return d.activeElement}catch(a){}}function ja(a,b,c,d,e,f){var g,h;if("object"==typeof b){"string"!=typeof c&&(d=d||c,c=void 0);for(h in b)ja(a,h,c,d,b[h],f);return a}if(null==d&&null==e?(e=c,d=c=void 0):null==e&&("string"==typeof c?(e=d,d=void 0):(e=d,d=c,c=void 0)),e===!1)e=ha;else if(!e)return a;return 1===f&&(g=e,e=function(a){return n().off(a),g.apply(this,arguments)},e.guid=g.guid||(g.guid=n.guid++)),a.each(function(){n.event.add(this,b,e,d,c)})}n.event={global:{},add:function(a,b,c,d,e){var f,g,h,i,j,k,l,m,o,p,q,r=N.get(a);if(r){c.handler&&(f=c,c=f.handler,e=f.selector),c.guid||(c.guid=n.guid++),(i=r.events)||(i=r.events={}),(g=r.handle)||(g=r.handle=function(b){return"undefined"!=typeof n&&n.event.triggered!==b.type?n.event.dispatch.apply(a,arguments):void 0}),b=(b||"").match(G)||[""],j=b.length;while(j--)h=fa.exec(b[j])||[],o=q=h[1],p=(h[2]||"").split(".").sort(),o&&(l=n.event.special[o]||{},o=(e?l.delegateType:l.bindType)||o,l=n.event.special[o]||{},k=n.extend({type:o,origType:q,data:d,handler:c,guid:c.guid,selector:e,needsContext:e&&n.expr.match.needsContext.test(e),namespace:p.join(".")},f),(m=i[o])||(m=i[o]=[],m.delegateCount=0,l.setup&&l.setup.call(a,d,p,g)!==!1||a.addEventListener&&a.addEventListener(o,g)),l.add&&(l.add.call(a,k),k.handler.guid||(k.handler.guid=c.guid)),e?m.splice(m.delegateCount++,0,k):m.push(k),n.event.global[o]=!0)}},remove:function(a,b,c,d,e){var f,g,h,i,j,k,l,m,o,p,q,r=N.hasData(a)&&N.get(a);if(r&&(i=r.events)){b=(b||"").match(G)||[""],j=b.length;while(j--)if(h=fa.exec(b[j])||[],o=q=h[1],p=(h[2]||"").split(".").sort(),o){l=n.event.special[o]||{},o=(d?l.delegateType:l.bindType)||o,m=i[o]||[],h=h[2]&&new RegExp("(^|\\.)"+p.join("\\.(?:.*\\.|)")+"(\\.|$)"),g=f=m.length;while(f--)k=m[f],!e&&q!==k.origType||c&&c.guid!==k.guid||h&&!h.test(k.namespace)||d&&d!==k.selector&&("**"!==d||!k.selector)||(m.splice(f,1),k.selector&&m.delegateCount--,l.remove&&l.remove.call(a,k));g&&!m.length&&(l.teardown&&l.teardown.call(a,p,r.handle)!==!1||n.removeEvent(a,o,r.handle),delete i[o])}else for(o in i)n.event.remove(a,o+b[j],c,d,!0);n.isEmptyObject(i)&&N.remove(a,"handle events")}},dispatch:function(a){a=n.event.fix(a);var b,c,d,f,g,h=[],i=e.call(arguments),j=(N.get(this,"events")||{})[a.type]||[],k=n.event.special[a.type]||{};if(i[0]=a,a.delegateTarget=this,!k.preDispatch||k.preDispatch.call(this,a)!==!1){h=n.event.handlers.call(this,a,j),b=0;while((f=h[b++])&&!a.isPropagationStopped()){a.currentTarget=f.elem,c=0;while((g=f.handlers[c++])&&!a.isImmediatePropagationStopped())a.rnamespace&&!a.rnamespace.test(g.namespace)||(a.handleObj=g,a.data=g.data,d=((n.event.special[g.origType]||{}).handle||g.handler).apply(f.elem,i),void 0!==d&&(a.result=d)===!1&&(a.preventDefault(),a.stopPropagation()))}return k.postDispatch&&k.postDispatch.call(this,a),a.result}},handlers:function(a,b){var c,d,e,f,g=[],h=b.delegateCount,i=a.target;if(h&&i.nodeType&&("click"!==a.type||isNaN(a.button)||a.button<1))for(;i!==this;i=i.parentNode||this)if(1===i.nodeType&&(i.disabled!==!0||"click"!==a.type)){for(d=[],c=0;h>c;c++)f=b[c],e=f.selector+" ",void 0===d[e]&&(d[e]=f.needsContext?n(e,this).index(i)>-1:n.find(e,this,null,[i]).length),d[e]&&d.push(f);d.length&&g.push({elem:i,handlers:d})}return h<b.length&&g.push({elem:this,handlers:b.slice(h)}),g},props:"altKey bubbles cancelable ctrlKey currentTarget detail eventPhase metaKey relatedTarget shiftKey target timeStamp view which".split(" "),fixHooks:{},keyHooks:{props:"char charCode key keyCode".split(" "),filter:function(a,b){return null==a.which&&(a.which=null!=b.charCode?b.charCode:b.keyCode),a}},mouseHooks:{props:"button buttons clientX clientY offsetX offsetY pageX pageY screenX screenY toElement".split(" "),filter:function(a,b){var c,e,f,g=b.button;return null==a.pageX&&null!=b.clientX&&(c=a.target.ownerDocument||d,e=c.documentElement,f=c.body,a.pageX=b.clientX+(e&&e.scrollLeft||f&&f.scrollLeft||0)-(e&&e.clientLeft||f&&f.clientLeft||0),a.pageY=b.clientY+(e&&e.scrollTop||f&&f.scrollTop||0)-(e&&e.clientTop||f&&f.clientTop||0)),a.which||void 0===g||(a.which=1&g?1:2&g?3:4&g?2:0),a}},fix:function(a){if(a[n.expando])return a;var b,c,e,f=a.type,g=a,h=this.fixHooks[f];h||(this.fixHooks[f]=h=ea.test(f)?this.mouseHooks:da.test(f)?this.keyHooks:{}),e=h.props?this.props.concat(h.props):this.props,a=new n.Event(g),b=e.length;while(b--)c=e[b],a[c]=g[c];return a.target||(a.target=d),3===a.target.nodeType&&(a.target=a.target.parentNode),h.filter?h.filter(a,g):a},special:{load:{noBubble:!0},focus:{trigger:function(){return this!==ia()&&this.focus?(this.focus(),!1):void 0},delegateType:"focusin"},blur:{trigger:function(){return this===ia()&&this.blur?(this.blur(),!1):void 0},delegateType:"focusout"},click:{trigger:function(){return"checkbox"===this.type&&this.click&&n.nodeName(this,"input")?(this.click(),!1):void 0},_default:function(a){return n.nodeName(a.target,"a")}},beforeunload:{postDispatch:function(a){void 0!==a.result&&a.originalEvent&&(a.originalEvent.returnValue=a.result)}}}},n.removeEvent=function(a,b,c){a.removeEventListener&&a.removeEventListener(b,c)},n.Event=function(a,b){return this instanceof n.Event?(a&&a.type?(this.originalEvent=a,this.type=a.type,this.isDefaultPrevented=a.defaultPrevented||void 0===a.defaultPrevented&&a.returnValue===!1?ga:ha):this.type=a,b&&n.extend(this,b),this.timeStamp=a&&a.timeStamp||n.now(),void(this[n.expando]=!0)):new n.Event(a,b)},n.Event.prototype={constructor:n.Event,isDefaultPrevented:ha,isPropagationStopped:ha,isImmediatePropagationStopped:ha,preventDefault:function(){var a=this.originalEvent;this.isDefaultPrevented=ga,a&&a.preventDefault()},stopPropagation:function(){var a=this.originalEvent;this.isPropagationStopped=ga,a&&a.stopPropagation()},stopImmediatePropagation:function(){var a=this.originalEvent;this.isImmediatePropagationStopped=ga,a&&a.stopImmediatePropagation(),this.stopPropagation()}},n.each({mouseenter:"mouseover",mouseleave:"mouseout",pointerenter:"pointerover",pointerleave:"pointerout"},function(a,b){n.event.special[a]={delegateType:b,bindType:b,handle:function(a){var c,d=this,e=a.relatedTarget,f=a.handleObj;return e&&(e===d||n.contains(d,e))||(a.type=f.origType,c=f.handler.apply(this,arguments),a.type=b),c}}}),n.fn.extend({on:function(a,b,c,d){return ja(this,a,b,c,d)},one:function(a,b,c,d){return ja(this,a,b,c,d,1)},off:function(a,b,c){var d,e;if(a&&a.preventDefault&&a.handleObj)return d=a.handleObj,n(a.delegateTarget).off(d.namespace?d.origType+"."+d.namespace:d.origType,d.selector,d.handler),this;if("object"==typeof a){for(e in a)this.off(e,b,a[e]);return this}return b!==!1&&"function"!=typeof b||(c=b,b=void 0),c===!1&&(c=ha),this.each(function(){n.event.remove(this,a,c,b)})}});var ka=/<(?!area|br|col|embed|hr|img|input|link|meta|param)(([\w:-]+)[^>]*)\/>/gi,la=/<script|<style|<link/i,ma=/checked\s*(?:[^=]|=\s*.checked.)/i,na=/^true\/(.*)/,oa=/^\s*<!(?:\[CDATA\[|--)|(?:\]\]|--)>\s*$/g;function pa(a,b){return n.nodeName(a,"table")&&n.nodeName(11!==b.nodeType?b:b.firstChild,"tr")?a.getElementsByTagName("tbody")[0]||a.appendChild(a.ownerDocument.createElement("tbody")):a}function qa(a){return a.type=(null!==a.getAttribute("type"))+"/"+a.type,a}function ra(a){var b=na.exec(a.type);return b?a.type=b[1]:a.removeAttribute("type"),a}function sa(a,b){var c,d,e,f,g,h,i,j;if(1===b.nodeType){if(N.hasData(a)&&(f=N.access(a),g=N.set(b,f),j=f.events)){delete g.handle,g.events={};for(e in j)for(c=0,d=j[e].length;d>c;c++)n.event.add(b,e,j[e][c])}O.hasData(a)&&(h=O.access(a),i=n.extend({},h),O.set(b,i))}}function ta(a,b){var c=b.nodeName.toLowerCase();"input"===c&&X.test(a.type)?b.checked=a.checked:"input"!==c&&"textarea"!==c||(b.defaultValue=a.defaultValue)}function ua(a,b,c,d){b=f.apply([],b);var e,g,h,i,j,k,m=0,o=a.length,p=o-1,q=b[0],r=n.isFunction(q);if(r||o>1&&"string"==typeof q&&!l.checkClone&&ma.test(q))return a.each(function(e){var f=a.eq(e);r&&(b[0]=q.call(this,e,f.html())),ua(f,b,c,d)});if(o&&(e=ca(b,a[0].ownerDocument,!1,a,d),g=e.firstChild,1===e.childNodes.length&&(e=g),g||d)){for(h=n.map(_(e,"script"),qa),i=h.length;o>m;m++)j=e,m!==p&&(j=n.clone(j,!0,!0),i&&n.merge(h,_(j,"script"))),c.call(a[m],j,m);if(i)for(k=h[h.length-1].ownerDocument,n.map(h,ra),m=0;i>m;m++)j=h[m],Z.test(j.type||"")&&!N.access(j,"globalEval")&&n.contains(k,j)&&(j.src?n._evalUrl&&n._evalUrl(j.src):n.globalEval(j.textContent.replace(oa,"")))}return a}function va(a,b,c){for(var d,e=b?n.filter(b,a):a,f=0;null!=(d=e[f]);f++)c||1!==d.nodeType||n.cleanData(_(d)),d.parentNode&&(c&&n.contains(d.ownerDocument,d)&&aa(_(d,"script")),d.parentNode.removeChild(d));return a}n.extend({htmlPrefilter:function(a){return a.replace(ka,"<$1></$2>")},clone:function(a,b,c){var d,e,f,g,h=a.cloneNode(!0),i=n.contains(a.ownerDocument,a);if(!(l.noCloneChecked||1!==a.nodeType&&11!==a.nodeType||n.isXMLDoc(a)))for(g=_(h),f=_(a),d=0,e=f.length;e>d;d++)ta(f[d],g[d]);if(b)if(c)for(f=f||_(a),g=g||_(h),d=0,e=f.length;e>d;d++)sa(f[d],g[d]);else sa(a,h);return g=_(h,"script"),g.length>0&&aa(g,!i&&_(a,"script")),h},cleanData:function(a){for(var b,c,d,e=n.event.special,f=0;void 0!==(c=a[f]);f++)if(L(c)){if(b=c[N.expando]){if(b.events)for(d in b.events)e[d]?n.event.remove(c,d):n.removeEvent(c,d,b.handle);c[N.expando]=void 0}c[O.expando]&&(c[O.expando]=void 0)}}}),n.fn.extend({domManip:ua,detach:function(a){return va(this,a,!0)},remove:function(a){return va(this,a)},text:function(a){return K(this,function(a){return void 0===a?n.text(this):this.empty().each(function(){1!==this.nodeType&&11!==this.nodeType&&9!==this.nodeType||(this.textContent=a)})},null,a,arguments.length)},append:function(){return ua(this,arguments,function(a){if(1===this.nodeType||11===this.nodeType||9===this.nodeType){var b=pa(this,a);b.appendChild(a)}})},prepend:function(){return ua(this,arguments,function(a){if(1===this.nodeType||11===this.nodeType||9===this.nodeType){var b=pa(this,a);b.insertBefore(a,b.firstChild)}})},before:function(){return ua(this,arguments,function(a){this.parentNode&&this.parentNode.insertBefore(a,this)})},after:function(){return ua(this,arguments,function(a){this.parentNode&&this.parentNode.insertBefore(a,this.nextSibling)})},empty:function(){for(var a,b=0;null!=(a=this[b]);b++)1===a.nodeType&&(n.cleanData(_(a,!1)),a.textContent="");return this},clone:function(a,b){return a=null==a?!1:a,b=null==b?a:b,this.map(function(){return n.clone(this,a,b)})},html:function(a){return K(this,function(a){var b=this[0]||{},c=0,d=this.length;if(void 0===a&&1===b.nodeType)return b.innerHTML;if("string"==typeof a&&!la.test(a)&&!$[(Y.exec(a)||["",""])[1].toLowerCase()]){a=n.htmlPrefilter(a);try{for(;d>c;c++)b=this[c]||{},1===b.nodeType&&(n.cleanData(_(b,!1)),b.innerHTML=a);b=0}catch(e){}}b&&this.empty().append(a)},null,a,arguments.length)},replaceWith:function(){var a=[];return ua(this,arguments,function(b){var c=this.parentNode;n.inArray(this,a)<0&&(n.cleanData(_(this)),c&&c.replaceChild(b,this))},a)}}),n.each({appendTo:"append",prependTo:"prepend",insertBefore:"before",insertAfter:"after",replaceAll:"replaceWith"},function(a,b){n.fn[a]=function(a){for(var c,d=[],e=n(a),f=e.length-1,h=0;f>=h;h++)c=h===f?this:this.clone(!0),n(e[h])[b](c),g.apply(d,c.get());return this.pushStack(d)}});var wa,xa={HTML:"block",BODY:"block"};function ya(a,b){var c=n(b.createElement(a)).appendTo(b.body),d=n.css(c[0],"display");return c.detach(),d}function za(a){var b=d,c=xa[a];return c||(c=ya(a,b),"none"!==c&&c||(wa=(wa||n("<iframe frameborder='0' width='0' height='0'/>")).appendTo(b.documentElement),b=wa[0].contentDocument,b.write(),b.close(),c=ya(a,b),wa.detach()),xa[a]=c),c}var Aa=/^margin/,Ba=new RegExp("^("+S+")(?!px)[a-z%]+$","i"),Ca=function(b){var c=b.ownerDocument.defaultView;return c&&c.opener||(c=a),c.getComputedStyle(b)},Da=function(a,b,c,d){var e,f,g={};for(f in b)g[f]=a.style[f],a.style[f]=b[f];e=c.apply(a,d||[]);for(f in b)a.style[f]=g[f];return e},Ea=d.documentElement;!function(){var b,c,e,f,g=d.createElement("div"),h=d.createElement("div");if(h.style){h.style.backgroundClip="content-box",h.cloneNode(!0).style.backgroundClip="",l.clearCloneStyle="content-box"===h.style.backgroundClip,g.style.cssText="border:0;width:8px;height:0;top:0;left:-9999px;padding:0;margin-top:1px;position:absolute",g.appendChild(h);function i(){h.style.cssText="-webkit-box-sizing:border-box;-moz-box-sizing:border-box;box-sizing:border-box;position:relative;display:block;margin:auto;border:1px;padding:1px;top:1%;width:50%",h.innerHTML="",Ea.appendChild(g);var d=a.getComputedStyle(h);b="1%"!==d.top,f="2px"===d.marginLeft,c="4px"===d.width,h.style.marginRight="50%",e="4px"===d.marginRight,Ea.removeChild(g)}n.extend(l,{pixelPosition:function(){return i(),b},boxSizingReliable:function(){return null==c&&i(),c},pixelMarginRight:function(){return null==c&&i(),e},reliableMarginLeft:function(){return null==c&&i(),f},reliableMarginRight:function(){var b,c=h.appendChild(d.createElement("div"));return c.style.cssText=h.style.cssText="-webkit-box-sizing:content-box;box-sizing:content-box;display:block;margin:0;border:0;padding:0",c.style.marginRight=c.style.width="0",h.style.width="1px",Ea.appendChild(g),b=!parseFloat(a.getComputedStyle(c).marginRight),Ea.removeChild(g),h.removeChild(c),b}})}}();function Fa(a,b,c){var d,e,f,g,h=a.style;return c=c||Ca(a),g=c?c.getPropertyValue(b)||c[b]:void 0,""!==g&&void 0!==g||n.contains(a.ownerDocument,a)||(g=n.style(a,b)),c&&!l.pixelMarginRight()&&Ba.test(g)&&Aa.test(b)&&(d=h.width,e=h.minWidth,f=h.maxWidth,h.minWidth=h.maxWidth=h.width=g,g=c.width,h.width=d,h.minWidth=e,h.maxWidth=f),void 0!==g?g+"":g}function Ga(a,b){return{get:function(){return a()?void delete this.get:(this.get=b).apply(this,arguments)}}}var Ha=/^(none|table(?!-c[ea]).+)/,Ia={position:"absolute",visibility:"hidden",display:"block"},Ja={letterSpacing:"0",fontWeight:"400"},Ka=["Webkit","O","Moz","ms"],La=d.createElement("div").style;function Ma(a){if(a in La)return a;var b=a[0].toUpperCase()+a.slice(1),c=Ka.length;while(c--)if(a=Ka[c]+b,a in La)return a}function Na(a,b,c){var d=T.exec(b);return d?Math.max(0,d[2]-(c||0))+(d[3]||"px"):b}function Oa(a,b,c,d,e){for(var f=c===(d?"border":"content")?4:"width"===b?1:0,g=0;4>f;f+=2)"margin"===c&&(g+=n.css(a,c+U[f],!0,e)),d?("content"===c&&(g-=n.css(a,"padding"+U[f],!0,e)),"margin"!==c&&(g-=n.css(a,"border"+U[f]+"Width",!0,e))):(g+=n.css(a,"padding"+U[f],!0,e),"padding"!==c&&(g+=n.css(a,"border"+U[f]+"Width",!0,e)));return g}function Pa(b,c,e){var f=!0,g="width"===c?b.offsetWidth:b.offsetHeight,h=Ca(b),i="border-box"===n.css(b,"boxSizing",!1,h);if(d.msFullscreenElement&&a.top!==a&&b.getClientRects().length&&(g=Math.round(100*b.getBoundingClientRect()[c])),0>=g||null==g){if(g=Fa(b,c,h),(0>g||null==g)&&(g=b.style[c]),Ba.test(g))return g;f=i&&(l.boxSizingReliable()||g===b.style[c]),g=parseFloat(g)||0}return g+Oa(b,c,e||(i?"border":"content"),f,h)+"px"}function Qa(a,b){for(var c,d,e,f=[],g=0,h=a.length;h>g;g++)d=a[g],d.style&&(f[g]=N.get(d,"olddisplay"),c=d.style.display,b?(f[g]||"none"!==c||(d.style.display=""),""===d.style.display&&V(d)&&(f[g]=N.access(d,"olddisplay",za(d.nodeName)))):(e=V(d),"none"===c&&e||N.set(d,"olddisplay",e?c:n.css(d,"display"))));for(g=0;h>g;g++)d=a[g],d.style&&(b&&"none"!==d.style.display&&""!==d.style.display||(d.style.display=b?f[g]||"":"none"));return a}n.extend({cssHooks:{opacity:{get:function(a,b){if(b){var c=Fa(a,"opacity");return""===c?"1":c}}}},cssNumber:{animationIterationCount:!0,columnCount:!0,fillOpacity:!0,flexGrow:!0,flexShrink:!0,fontWeight:!0,lineHeight:!0,opacity:!0,order:!0,orphans:!0,widows:!0,zIndex:!0,zoom:!0},cssProps:{"float":"cssFloat"},style:function(a,b,c,d){if(a&&3!==a.nodeType&&8!==a.nodeType&&a.style){var e,f,g,h=n.camelCase(b),i=a.style;return b=n.cssProps[h]||(n.cssProps[h]=Ma(h)||h),g=n.cssHooks[b]||n.cssHooks[h],void 0===c?g&&"get"in g&&void 0!==(e=g.get(a,!1,d))?e:i[b]:(f=typeof c,"string"===f&&(e=T.exec(c))&&e[1]&&(c=W(a,b,e),f="number"),null!=c&&c===c&&("number"===f&&(c+=e&&e[3]||(n.cssNumber[h]?"":"px")),l.clearCloneStyle||""!==c||0!==b.indexOf("background")||(i[b]="inherit"),g&&"set"in g&&void 0===(c=g.set(a,c,d))||(i[b]=c)),void 0)}},css:function(a,b,c,d){var e,f,g,h=n.camelCase(b);return b=n.cssProps[h]||(n.cssProps[h]=Ma(h)||h),g=n.cssHooks[b]||n.cssHooks[h],g&&"get"in g&&(e=g.get(a,!0,c)),void 0===e&&(e=Fa(a,b,d)),"normal"===e&&b in Ja&&(e=Ja[b]),""===c||c?(f=parseFloat(e),c===!0||isFinite(f)?f||0:e):e}}),n.each(["height","width"],function(a,b){n.cssHooks[b]={get:function(a,c,d){return c?Ha.test(n.css(a,"display"))&&0===a.offsetWidth?Da(a,Ia,function(){return Pa(a,b,d)}):Pa(a,b,d):void 0},set:function(a,c,d){var e,f=d&&Ca(a),g=d&&Oa(a,b,d,"border-box"===n.css(a,"boxSizing",!1,f),f);return g&&(e=T.exec(c))&&"px"!==(e[3]||"px")&&(a.style[b]=c,c=n.css(a,b)),Na(a,c,g)}}}),n.cssHooks.marginLeft=Ga(l.reliableMarginLeft,function(a,b){return b?(parseFloat(Fa(a,"marginLeft"))||a.getBoundingClientRect().left-Da(a,{marginLeft:0},function(){return a.getBoundingClientRect().left}))+"px":void 0}),n.cssHooks.marginRight=Ga(l.reliableMarginRight,function(a,b){return b?Da(a,{display:"inline-block"},Fa,[a,"marginRight"]):void 0}),n.each({margin:"",padding:"",border:"Width"},function(a,b){n.cssHooks[a+b]={expand:function(c){for(var d=0,e={},f="string"==typeof c?c.split(" "):[c];4>d;d++)e[a+U[d]+b]=f[d]||f[d-2]||f[0];return e}},Aa.test(a)||(n.cssHooks[a+b].set=Na)}),n.fn.extend({css:function(a,b){return K(this,function(a,b,c){var d,e,f={},g=0;if(n.isArray(b)){for(d=Ca(a),e=b.length;e>g;g++)f[b[g]]=n.css(a,b[g],!1,d);return f}return void 0!==c?n.style(a,b,c):n.css(a,b)},a,b,arguments.length>1)},show:function(){return Qa(this,!0)},hide:function(){return Qa(this)},toggle:function(a){return"boolean"==typeof a?a?this.show():this.hide():this.each(function(){V(this)?n(this).show():n(this).hide()})}});function Ra(a,b,c,d,e){return new Ra.prototype.init(a,b,c,d,e)}n.Tween=Ra,Ra.prototype={constructor:Ra,init:function(a,b,c,d,e,f){this.elem=a,this.prop=c,this.easing=e||n.easing._default,this.options=b,this.start=this.now=this.cur(),this.end=d,this.unit=f||(n.cssNumber[c]?"":"px")},cur:function(){var a=Ra.propHooks[this.prop];return a&&a.get?a.get(this):Ra.propHooks._default.get(this)},run:function(a){var b,c=Ra.propHooks[this.prop];return this.options.duration?this.pos=b=n.easing[this.easing](a,this.options.duration*a,0,1,this.options.duration):this.pos=b=a,this.now=(this.end-this.start)*b+this.start,this.options.step&&this.options.step.call(this.elem,this.now,this),c&&c.set?c.set(this):Ra.propHooks._default.set(this),this}},Ra.prototype.init.prototype=Ra.prototype,Ra.propHooks={_default:{get:function(a){var b;return 1!==a.elem.nodeType||null!=a.elem[a.prop]&&null==a.elem.style[a.prop]?a.elem[a.prop]:(b=n.css(a.elem,a.prop,""),b&&"auto"!==b?b:0)},set:function(a){n.fx.step[a.prop]?n.fx.step[a.prop](a):1!==a.elem.nodeType||null==a.elem.style[n.cssProps[a.prop]]&&!n.cssHooks[a.prop]?a.elem[a.prop]=a.now:n.style(a.elem,a.prop,a.now+a.unit)}}},Ra.propHooks.scrollTop=Ra.propHooks.scrollLeft={set:function(a){a.elem.nodeType&&a.elem.parentNode&&(a.elem[a.prop]=a.now)}},n.easing={linear:function(a){return a},swing:function(a){return.5-Math.cos(a*Math.PI)/2},_default:"swing"},n.fx=Ra.prototype.init,n.fx.step={};var Sa,Ta,Ua=/^(?:toggle|show|hide)$/,Va=/queueHooks$/;function Wa(){return a.setTimeout(function(){Sa=void 0}),Sa=n.now()}function Xa(a,b){var c,d=0,e={height:a};for(b=b?1:0;4>d;d+=2-b)c=U[d],e["margin"+c]=e["padding"+c]=a;return b&&(e.opacity=e.width=a),e}function Ya(a,b,c){for(var d,e=(_a.tweeners[b]||[]).concat(_a.tweeners["*"]),f=0,g=e.length;g>f;f++)if(d=e[f].call(c,b,a))return d}function Za(a,b,c){var d,e,f,g,h,i,j,k,l=this,m={},o=a.style,p=a.nodeType&&V(a),q=N.get(a,"fxshow");c.queue||(h=n._queueHooks(a,"fx"),null==h.unqueued&&(h.unqueued=0,i=h.empty.fire,h.empty.fire=function(){h.unqueued||i()}),h.unqueued++,l.always(function(){l.always(function(){h.unqueued--,n.queue(a,"fx").length||h.empty.fire()})})),1===a.nodeType&&("height"in b||"width"in b)&&(c.overflow=[o.overflow,o.overflowX,o.overflowY],j=n.css(a,"display"),k="none"===j?N.get(a,"olddisplay")||za(a.nodeName):j,"inline"===k&&"none"===n.css(a,"float")&&(o.display="inline-block")),c.overflow&&(o.overflow="hidden",l.always(function(){o.overflow=c.overflow[0],o.overflowX=c.overflow[1],o.overflowY=c.overflow[2]}));for(d in b)if(e=b[d],Ua.exec(e)){if(delete b[d],f=f||"toggle"===e,e===(p?"hide":"show")){if("show"!==e||!q||void 0===q[d])continue;p=!0}m[d]=q&&q[d]||n.style(a,d)}else j=void 0;if(n.isEmptyObject(m))"inline"===("none"===j?za(a.nodeName):j)&&(o.display=j);else{q?"hidden"in q&&(p=q.hidden):q=N.access(a,"fxshow",{}),f&&(q.hidden=!p),p?n(a).show():l.done(function(){n(a).hide()}),l.done(function(){var b;N.remove(a,"fxshow");for(b in m)n.style(a,b,m[b])});for(d in m)g=Ya(p?q[d]:0,d,l),d in q||(q[d]=g.start,p&&(g.end=g.start,g.start="width"===d||"height"===d?1:0))}}function $a(a,b){var c,d,e,f,g;for(c in a)if(d=n.camelCase(c),e=b[d],f=a[c],n.isArray(f)&&(e=f[1],f=a[c]=f[0]),c!==d&&(a[d]=f,delete a[c]),g=n.cssHooks[d],g&&"expand"in g){f=g.expand(f),delete a[d];for(c in f)c in a||(a[c]=f[c],b[c]=e)}else b[d]=e}function _a(a,b,c){var d,e,f=0,g=_a.prefilters.length,h=n.Deferred().always(function(){delete i.elem}),i=function(){if(e)return!1;for(var b=Sa||Wa(),c=Math.max(0,j.startTime+j.duration-b),d=c/j.duration||0,f=1-d,g=0,i=j.tweens.length;i>g;g++)j.tweens[g].run(f);return h.notifyWith(a,[j,f,c]),1>f&&i?c:(h.resolveWith(a,[j]),!1)},j=h.promise({elem:a,props:n.extend({},b),opts:n.extend(!0,{specialEasing:{},easing:n.easing._default},c),originalProperties:b,originalOptions:c,startTime:Sa||Wa(),duration:c.duration,tweens:[],createTween:function(b,c){var d=n.Tween(a,j.opts,b,c,j.opts.specialEasing[b]||j.opts.easing);return j.tweens.push(d),d},stop:function(b){var c=0,d=b?j.tweens.length:0;if(e)return this;for(e=!0;d>c;c++)j.tweens[c].run(1);return b?(h.notifyWith(a,[j,1,0]),h.resolveWith(a,[j,b])):h.rejectWith(a,[j,b]),this}}),k=j.props;for($a(k,j.opts.specialEasing);g>f;f++)if(d=_a.prefilters[f].call(j,a,k,j.opts))return n.isFunction(d.stop)&&(n._queueHooks(j.elem,j.opts.queue).stop=n.proxy(d.stop,d)),d;return n.map(k,Ya,j),n.isFunction(j.opts.start)&&j.opts.start.call(a,j),n.fx.timer(n.extend(i,{elem:a,anim:j,queue:j.opts.queue})),j.progress(j.opts.progress).done(j.opts.done,j.opts.complete).fail(j.opts.fail).always(j.opts.always)}n.Animation=n.extend(_a,{tweeners:{"*":[function(a,b){var c=this.createTween(a,b);return W(c.elem,a,T.exec(b),c),c}]},tweener:function(a,b){n.isFunction(a)?(b=a,a=["*"]):a=a.match(G);for(var c,d=0,e=a.length;e>d;d++)c=a[d],_a.tweeners[c]=_a.tweeners[c]||[],_a.tweeners[c].unshift(b)},prefilters:[Za],prefilter:function(a,b){b?_a.prefilters.unshift(a):_a.prefilters.push(a)}}),n.speed=function(a,b,c){var d=a&&"object"==typeof a?n.extend({},a):{complete:c||!c&&b||n.isFunction(a)&&a,duration:a,easing:c&&b||b&&!n.isFunction(b)&&b};return d.duration=n.fx.off?0:"number"==typeof d.duration?d.duration:d.duration in n.fx.speeds?n.fx.speeds[d.duration]:n.fx.speeds._default,null!=d.queue&&d.queue!==!0||(d.queue="fx"),d.old=d.complete,d.complete=function(){n.isFunction(d.old)&&d.old.call(this),d.queue&&n.dequeue(this,d.queue)},d},n.fn.extend({fadeTo:function(a,b,c,d){return this.filter(V).css("opacity",0).show().end().animate({opacity:b},a,c,d)},animate:function(a,b,c,d){var e=n.isEmptyObject(a),f=n.speed(b,c,d),g=function(){var b=_a(this,n.extend({},a),f);(e||N.get(this,"finish"))&&b.stop(!0)};return g.finish=g,e||f.queue===!1?this.each(g):this.queue(f.queue,g)},stop:function(a,b,c){var d=function(a){var b=a.stop;delete a.stop,b(c)};return"string"!=typeof a&&(c=b,b=a,a=void 0),b&&a!==!1&&this.queue(a||"fx",[]),this.each(function(){var b=!0,e=null!=a&&a+"queueHooks",f=n.timers,g=N.get(this);if(e)g[e]&&g[e].stop&&d(g[e]);else for(e in g)g[e]&&g[e].stop&&Va.test(e)&&d(g[e]);for(e=f.length;e--;)f[e].elem!==this||null!=a&&f[e].queue!==a||(f[e].anim.stop(c),b=!1,f.splice(e,1));!b&&c||n.dequeue(this,a)})},finish:function(a){return a!==!1&&(a=a||"fx"),this.each(function(){var b,c=N.get(this),d=c[a+"queue"],e=c[a+"queueHooks"],f=n.timers,g=d?d.length:0;for(c.finish=!0,n.queue(this,a,[]),e&&e.stop&&e.stop.call(this,!0),b=f.length;b--;)f[b].elem===this&&f[b].queue===a&&(f[b].anim.stop(!0),f.splice(b,1));for(b=0;g>b;b++)d[b]&&d[b].finish&&d[b].finish.call(this);delete c.finish})}}),n.each(["toggle","show","hide"],function(a,b){var c=n.fn[b];n.fn[b]=function(a,d,e){return null==a||"boolean"==typeof a?c.apply(this,arguments):this.animate(Xa(b,!0),a,d,e)}}),n.each({slideDown:Xa("show"),slideUp:Xa("hide"),slideToggle:Xa("toggle"),fadeIn:{opacity:"show"},fadeOut:{opacity:"hide"},fadeToggle:{opacity:"toggle"}},function(a,b){n.fn[a]=function(a,c,d){return this.animate(b,a,c,d)}}),n.timers=[],n.fx.tick=function(){var a,b=0,c=n.timers;for(Sa=n.now();b<c.length;b++)a=c[b],a()||c[b]!==a||c.splice(b--,1);c.length||n.fx.stop(),Sa=void 0},n.fx.timer=function(a){n.timers.push(a),a()?n.fx.start():n.timers.pop()},n.fx.interval=13,n.fx.start=function(){Ta||(Ta=a.setInterval(n.fx.tick,n.fx.interval))},n.fx.stop=function(){a.clearInterval(Ta),Ta=null},n.fx.speeds={slow:600,fast:200,_default:400},n.fn.delay=function(b,c){return b=n.fx?n.fx.speeds[b]||b:b,c=c||"fx",this.queue(c,function(c,d){var e=a.setTimeout(c,b);d.stop=function(){a.clearTimeout(e)}})},function(){var a=d.createElement("input"),b=d.createElement("select"),c=b.appendChild(d.createElement("option"));a.type="checkbox",l.checkOn=""!==a.value,l.optSelected=c.selected,b.disabled=!0,l.optDisabled=!c.disabled,a=d.createElement("input"),a.value="t",a.type="radio",l.radioValue="t"===a.value}();var ab,bb=n.expr.attrHandle;n.fn.extend({attr:function(a,b){return K(this,n.attr,a,b,arguments.length>1)},removeAttr:function(a){return this.each(function(){n.removeAttr(this,a)})}}),n.extend({attr:function(a,b,c){var d,e,f=a.nodeType;if(3!==f&&8!==f&&2!==f)return"undefined"==typeof a.getAttribute?n.prop(a,b,c):(1===f&&n.isXMLDoc(a)||(b=b.toLowerCase(),e=n.attrHooks[b]||(n.expr.match.bool.test(b)?ab:void 0)),void 0!==c?null===c?void n.removeAttr(a,b):e&&"set"in e&&void 0!==(d=e.set(a,c,b))?d:(a.setAttribute(b,c+""),c):e&&"get"in e&&null!==(d=e.get(a,b))?d:(d=n.find.attr(a,b),null==d?void 0:d))},attrHooks:{type:{set:function(a,b){if(!l.radioValue&&"radio"===b&&n.nodeName(a,"input")){var c=a.value;return a.setAttribute("type",b),c&&(a.value=c),b}}}},removeAttr:function(a,b){var c,d,e=0,f=b&&b.match(G);if(f&&1===a.nodeType)while(c=f[e++])d=n.propFix[c]||c,n.expr.match.bool.test(c)&&(a[d]=!1),a.removeAttribute(c)}}),ab={set:function(a,b,c){return b===!1?n.removeAttr(a,c):a.setAttribute(c,c),c}},n.each(n.expr.match.bool.source.match(/\w+/g),function(a,b){var c=bb[b]||n.find.attr;bb[b]=function(a,b,d){var e,f;return d||(f=bb[b],bb[b]=e,e=null!=c(a,b,d)?b.toLowerCase():null,bb[b]=f),e}});var cb=/^(?:input|select|textarea|button)$/i,db=/^(?:a|area)$/i;n.fn.extend({prop:function(a,b){return K(this,n.prop,a,b,arguments.length>1)},removeProp:function(a){return this.each(function(){delete this[n.propFix[a]||a]})}}),n.extend({prop:function(a,b,c){var d,e,f=a.nodeType;if(3!==f&&8!==f&&2!==f)return 1===f&&n.isXMLDoc(a)||(b=n.propFix[b]||b,
+e=n.propHooks[b]),void 0!==c?e&&"set"in e&&void 0!==(d=e.set(a,c,b))?d:a[b]=c:e&&"get"in e&&null!==(d=e.get(a,b))?d:a[b]},propHooks:{tabIndex:{get:function(a){var b=n.find.attr(a,"tabindex");return b?parseInt(b,10):cb.test(a.nodeName)||db.test(a.nodeName)&&a.href?0:-1}}},propFix:{"for":"htmlFor","class":"className"}}),l.optSelected||(n.propHooks.selected={get:function(a){var b=a.parentNode;return b&&b.parentNode&&b.parentNode.selectedIndex,null},set:function(a){var b=a.parentNode;b&&(b.selectedIndex,b.parentNode&&b.parentNode.selectedIndex)}}),n.each(["tabIndex","readOnly","maxLength","cellSpacing","cellPadding","rowSpan","colSpan","useMap","frameBorder","contentEditable"],function(){n.propFix[this.toLowerCase()]=this});var eb=/[\t\r\n\f]/g;function fb(a){return a.getAttribute&&a.getAttribute("class")||""}n.fn.extend({addClass:function(a){var b,c,d,e,f,g,h,i=0;if(n.isFunction(a))return this.each(function(b){n(this).addClass(a.call(this,b,fb(this)))});if("string"==typeof a&&a){b=a.match(G)||[];while(c=this[i++])if(e=fb(c),d=1===c.nodeType&&(" "+e+" ").replace(eb," ")){g=0;while(f=b[g++])d.indexOf(" "+f+" ")<0&&(d+=f+" ");h=n.trim(d),e!==h&&c.setAttribute("class",h)}}return this},removeClass:function(a){var b,c,d,e,f,g,h,i=0;if(n.isFunction(a))return this.each(function(b){n(this).removeClass(a.call(this,b,fb(this)))});if(!arguments.length)return this.attr("class","");if("string"==typeof a&&a){b=a.match(G)||[];while(c=this[i++])if(e=fb(c),d=1===c.nodeType&&(" "+e+" ").replace(eb," ")){g=0;while(f=b[g++])while(d.indexOf(" "+f+" ")>-1)d=d.replace(" "+f+" "," ");h=n.trim(d),e!==h&&c.setAttribute("class",h)}}return this},toggleClass:function(a,b){var c=typeof a;return"boolean"==typeof b&&"string"===c?b?this.addClass(a):this.removeClass(a):n.isFunction(a)?this.each(function(c){n(this).toggleClass(a.call(this,c,fb(this),b),b)}):this.each(function(){var b,d,e,f;if("string"===c){d=0,e=n(this),f=a.match(G)||[];while(b=f[d++])e.hasClass(b)?e.removeClass(b):e.addClass(b)}else void 0!==a&&"boolean"!==c||(b=fb(this),b&&N.set(this,"__className__",b),this.setAttribute&&this.setAttribute("class",b||a===!1?"":N.get(this,"__className__")||""))})},hasClass:function(a){var b,c,d=0;b=" "+a+" ";while(c=this[d++])if(1===c.nodeType&&(" "+fb(c)+" ").replace(eb," ").indexOf(b)>-1)return!0;return!1}});var gb=/\r/g,hb=/[\x20\t\r\n\f]+/g;n.fn.extend({val:function(a){var b,c,d,e=this[0];{if(arguments.length)return d=n.isFunction(a),this.each(function(c){var e;1===this.nodeType&&(e=d?a.call(this,c,n(this).val()):a,null==e?e="":"number"==typeof e?e+="":n.isArray(e)&&(e=n.map(e,function(a){return null==a?"":a+""})),b=n.valHooks[this.type]||n.valHooks[this.nodeName.toLowerCase()],b&&"set"in b&&void 0!==b.set(this,e,"value")||(this.value=e))});if(e)return b=n.valHooks[e.type]||n.valHooks[e.nodeName.toLowerCase()],b&&"get"in b&&void 0!==(c=b.get(e,"value"))?c:(c=e.value,"string"==typeof c?c.replace(gb,""):null==c?"":c)}}}),n.extend({valHooks:{option:{get:function(a){var b=n.find.attr(a,"value");return null!=b?b:n.trim(n.text(a)).replace(hb," ")}},select:{get:function(a){for(var b,c,d=a.options,e=a.selectedIndex,f="select-one"===a.type||0>e,g=f?null:[],h=f?e+1:d.length,i=0>e?h:f?e:0;h>i;i++)if(c=d[i],(c.selected||i===e)&&(l.optDisabled?!c.disabled:null===c.getAttribute("disabled"))&&(!c.parentNode.disabled||!n.nodeName(c.parentNode,"optgroup"))){if(b=n(c).val(),f)return b;g.push(b)}return g},set:function(a,b){var c,d,e=a.options,f=n.makeArray(b),g=e.length;while(g--)d=e[g],(d.selected=n.inArray(n.valHooks.option.get(d),f)>-1)&&(c=!0);return c||(a.selectedIndex=-1),f}}}}),n.each(["radio","checkbox"],function(){n.valHooks[this]={set:function(a,b){return n.isArray(b)?a.checked=n.inArray(n(a).val(),b)>-1:void 0}},l.checkOn||(n.valHooks[this].get=function(a){return null===a.getAttribute("value")?"on":a.value})});var ib=/^(?:focusinfocus|focusoutblur)$/;n.extend(n.event,{trigger:function(b,c,e,f){var g,h,i,j,l,m,o,p=[e||d],q=k.call(b,"type")?b.type:b,r=k.call(b,"namespace")?b.namespace.split("."):[];if(h=i=e=e||d,3!==e.nodeType&&8!==e.nodeType&&!ib.test(q+n.event.triggered)&&(q.indexOf(".")>-1&&(r=q.split("."),q=r.shift(),r.sort()),l=q.indexOf(":")<0&&"on"+q,b=b[n.expando]?b:new n.Event(q,"object"==typeof b&&b),b.isTrigger=f?2:3,b.namespace=r.join("."),b.rnamespace=b.namespace?new RegExp("(^|\\.)"+r.join("\\.(?:.*\\.|)")+"(\\.|$)"):null,b.result=void 0,b.target||(b.target=e),c=null==c?[b]:n.makeArray(c,[b]),o=n.event.special[q]||{},f||!o.trigger||o.trigger.apply(e,c)!==!1)){if(!f&&!o.noBubble&&!n.isWindow(e)){for(j=o.delegateType||q,ib.test(j+q)||(h=h.parentNode);h;h=h.parentNode)p.push(h),i=h;i===(e.ownerDocument||d)&&p.push(i.defaultView||i.parentWindow||a)}g=0;while((h=p[g++])&&!b.isPropagationStopped())b.type=g>1?j:o.bindType||q,m=(N.get(h,"events")||{})[b.type]&&N.get(h,"handle"),m&&m.apply(h,c),m=l&&h[l],m&&m.apply&&L(h)&&(b.result=m.apply(h,c),b.result===!1&&b.preventDefault());return b.type=q,f||b.isDefaultPrevented()||o._default&&o._default.apply(p.pop(),c)!==!1||!L(e)||l&&n.isFunction(e[q])&&!n.isWindow(e)&&(i=e[l],i&&(e[l]=null),n.event.triggered=q,e[q](),n.event.triggered=void 0,i&&(e[l]=i)),b.result}},simulate:function(a,b,c){var d=n.extend(new n.Event,c,{type:a,isSimulated:!0});n.event.trigger(d,null,b),d.isDefaultPrevented()&&c.preventDefault()}}),n.fn.extend({trigger:function(a,b){return this.each(function(){n.event.trigger(a,b,this)})},triggerHandler:function(a,b){var c=this[0];return c?n.event.trigger(a,b,c,!0):void 0}}),n.each("blur focus focusin focusout load resize scroll unload click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup error contextmenu".split(" "),function(a,b){n.fn[b]=function(a,c){return arguments.length>0?this.on(b,null,a,c):this.trigger(b)}}),n.fn.extend({hover:function(a,b){return this.mouseenter(a).mouseleave(b||a)}}),l.focusin="onfocusin"in a,l.focusin||n.each({focus:"focusin",blur:"focusout"},function(a,b){var c=function(a){n.event.simulate(b,a.target,n.event.fix(a))};n.event.special[b]={setup:function(){var d=this.ownerDocument||this,e=N.access(d,b);e||d.addEventListener(a,c,!0),N.access(d,b,(e||0)+1)},teardown:function(){var d=this.ownerDocument||this,e=N.access(d,b)-1;e?N.access(d,b,e):(d.removeEventListener(a,c,!0),N.remove(d,b))}}});var jb=a.location,kb=n.now(),lb=/\?/;n.parseJSON=function(a){return JSON.parse(a+"")},n.parseXML=function(b){var c;if(!b||"string"!=typeof b)return null;try{c=(new a.DOMParser).parseFromString(b,"text/xml")}catch(d){c=void 0}return c&&!c.getElementsByTagName("parsererror").length||n.error("Invalid XML: "+b),c};var mb=/#.*$/,nb=/([?&])_=[^&]*/,ob=/^(.*?):[ \t]*([^\r\n]*)$/gm,pb=/^(?:about|app|app-storage|.+-extension|file|res|widget):$/,qb=/^(?:GET|HEAD)$/,rb=/^\/\//,sb={},tb={},ub="*/".concat("*"),vb=d.createElement("a");vb.href=jb.href;function wb(a){return function(b,c){"string"!=typeof b&&(c=b,b="*");var d,e=0,f=b.toLowerCase().match(G)||[];if(n.isFunction(c))while(d=f[e++])"+"===d[0]?(d=d.slice(1)||"*",(a[d]=a[d]||[]).unshift(c)):(a[d]=a[d]||[]).push(c)}}function xb(a,b,c,d){var e={},f=a===tb;function g(h){var i;return e[h]=!0,n.each(a[h]||[],function(a,h){var j=h(b,c,d);return"string"!=typeof j||f||e[j]?f?!(i=j):void 0:(b.dataTypes.unshift(j),g(j),!1)}),i}return g(b.dataTypes[0])||!e["*"]&&g("*")}function yb(a,b){var c,d,e=n.ajaxSettings.flatOptions||{};for(c in b)void 0!==b[c]&&((e[c]?a:d||(d={}))[c]=b[c]);return d&&n.extend(!0,a,d),a}function zb(a,b,c){var d,e,f,g,h=a.contents,i=a.dataTypes;while("*"===i[0])i.shift(),void 0===d&&(d=a.mimeType||b.getResponseHeader("Content-Type"));if(d)for(e in h)if(h[e]&&h[e].test(d)){i.unshift(e);break}if(i[0]in c)f=i[0];else{for(e in c){if(!i[0]||a.converters[e+" "+i[0]]){f=e;break}g||(g=e)}f=f||g}return f?(f!==i[0]&&i.unshift(f),c[f]):void 0}function Ab(a,b,c,d){var e,f,g,h,i,j={},k=a.dataTypes.slice();if(k[1])for(g in a.converters)j[g.toLowerCase()]=a.converters[g];f=k.shift();while(f)if(a.responseFields[f]&&(c[a.responseFields[f]]=b),!i&&d&&a.dataFilter&&(b=a.dataFilter(b,a.dataType)),i=f,f=k.shift())if("*"===f)f=i;else if("*"!==i&&i!==f){if(g=j[i+" "+f]||j["* "+f],!g)for(e in j)if(h=e.split(" "),h[1]===f&&(g=j[i+" "+h[0]]||j["* "+h[0]])){g===!0?g=j[e]:j[e]!==!0&&(f=h[0],k.unshift(h[1]));break}if(g!==!0)if(g&&a["throws"])b=g(b);else try{b=g(b)}catch(l){return{state:"parsererror",error:g?l:"No conversion from "+i+" to "+f}}}return{state:"success",data:b}}n.extend({active:0,lastModified:{},etag:{},ajaxSettings:{url:jb.href,type:"GET",isLocal:pb.test(jb.protocol),global:!0,processData:!0,async:!0,contentType:"application/x-www-form-urlencoded; charset=UTF-8",accepts:{"*":ub,text:"text/plain",html:"text/html",xml:"application/xml, text/xml",json:"application/json, text/javascript"},contents:{xml:/\bxml\b/,html:/\bhtml/,json:/\bjson\b/},responseFields:{xml:"responseXML",text:"responseText",json:"responseJSON"},converters:{"* text":String,"text html":!0,"text json":n.parseJSON,"text xml":n.parseXML},flatOptions:{url:!0,context:!0}},ajaxSetup:function(a,b){return b?yb(yb(a,n.ajaxSettings),b):yb(n.ajaxSettings,a)},ajaxPrefilter:wb(sb),ajaxTransport:wb(tb),ajax:function(b,c){"object"==typeof b&&(c=b,b=void 0),c=c||{};var e,f,g,h,i,j,k,l,m=n.ajaxSetup({},c),o=m.context||m,p=m.context&&(o.nodeType||o.jquery)?n(o):n.event,q=n.Deferred(),r=n.Callbacks("once memory"),s=m.statusCode||{},t={},u={},v=0,w="canceled",x={readyState:0,getResponseHeader:function(a){var b;if(2===v){if(!h){h={};while(b=ob.exec(g))h[b[1].toLowerCase()]=b[2]}b=h[a.toLowerCase()]}return null==b?null:b},getAllResponseHeaders:function(){return 2===v?g:null},setRequestHeader:function(a,b){var c=a.toLowerCase();return v||(a=u[c]=u[c]||a,t[a]=b),this},overrideMimeType:function(a){return v||(m.mimeType=a),this},statusCode:function(a){var b;if(a)if(2>v)for(b in a)s[b]=[s[b],a[b]];else x.always(a[x.status]);return this},abort:function(a){var b=a||w;return e&&e.abort(b),z(0,b),this}};if(q.promise(x).complete=r.add,x.success=x.done,x.error=x.fail,m.url=((b||m.url||jb.href)+"").replace(mb,"").replace(rb,jb.protocol+"//"),m.type=c.method||c.type||m.method||m.type,m.dataTypes=n.trim(m.dataType||"*").toLowerCase().match(G)||[""],null==m.crossDomain){j=d.createElement("a");try{j.href=m.url,j.href=j.href,m.crossDomain=vb.protocol+"//"+vb.host!=j.protocol+"//"+j.host}catch(y){m.crossDomain=!0}}if(m.data&&m.processData&&"string"!=typeof m.data&&(m.data=n.param(m.data,m.traditional)),xb(sb,m,c,x),2===v)return x;k=n.event&&m.global,k&&0===n.active++&&n.event.trigger("ajaxStart"),m.type=m.type.toUpperCase(),m.hasContent=!qb.test(m.type),f=m.url,m.hasContent||(m.data&&(f=m.url+=(lb.test(f)?"&":"?")+m.data,delete m.data),m.cache===!1&&(m.url=nb.test(f)?f.replace(nb,"$1_="+kb++):f+(lb.test(f)?"&":"?")+"_="+kb++)),m.ifModified&&(n.lastModified[f]&&x.setRequestHeader("If-Modified-Since",n.lastModified[f]),n.etag[f]&&x.setRequestHeader("If-None-Match",n.etag[f])),(m.data&&m.hasContent&&m.contentType!==!1||c.contentType)&&x.setRequestHeader("Content-Type",m.contentType),x.setRequestHeader("Accept",m.dataTypes[0]&&m.accepts[m.dataTypes[0]]?m.accepts[m.dataTypes[0]]+("*"!==m.dataTypes[0]?", "+ub+"; q=0.01":""):m.accepts["*"]);for(l in m.headers)x.setRequestHeader(l,m.headers[l]);if(m.beforeSend&&(m.beforeSend.call(o,x,m)===!1||2===v))return x.abort();w="abort";for(l in{success:1,error:1,complete:1})x[l](m[l]);if(e=xb(tb,m,c,x)){if(x.readyState=1,k&&p.trigger("ajaxSend",[x,m]),2===v)return x;m.async&&m.timeout>0&&(i=a.setTimeout(function(){x.abort("timeout")},m.timeout));try{v=1,e.send(t,z)}catch(y){if(!(2>v))throw y;z(-1,y)}}else z(-1,"No Transport");function z(b,c,d,h){var j,l,t,u,w,y=c;2!==v&&(v=2,i&&a.clearTimeout(i),e=void 0,g=h||"",x.readyState=b>0?4:0,j=b>=200&&300>b||304===b,d&&(u=zb(m,x,d)),u=Ab(m,u,x,j),j?(m.ifModified&&(w=x.getResponseHeader("Last-Modified"),w&&(n.lastModified[f]=w),w=x.getResponseHeader("etag"),w&&(n.etag[f]=w)),204===b||"HEAD"===m.type?y="nocontent":304===b?y="notmodified":(y=u.state,l=u.data,t=u.error,j=!t)):(t=y,!b&&y||(y="error",0>b&&(b=0))),x.status=b,x.statusText=(c||y)+"",j?q.resolveWith(o,[l,y,x]):q.rejectWith(o,[x,y,t]),x.statusCode(s),s=void 0,k&&p.trigger(j?"ajaxSuccess":"ajaxError",[x,m,j?l:t]),r.fireWith(o,[x,y]),k&&(p.trigger("ajaxComplete",[x,m]),--n.active||n.event.trigger("ajaxStop")))}return x},getJSON:function(a,b,c){return n.get(a,b,c,"json")},getScript:function(a,b){return n.get(a,void 0,b,"script")}}),n.each(["get","post"],function(a,b){n[b]=function(a,c,d,e){return n.isFunction(c)&&(e=e||d,d=c,c=void 0),n.ajax(n.extend({url:a,type:b,dataType:e,data:c,success:d},n.isPlainObject(a)&&a))}}),n._evalUrl=function(a){return n.ajax({url:a,type:"GET",dataType:"script",async:!1,global:!1,"throws":!0})},n.fn.extend({wrapAll:function(a){var b;return n.isFunction(a)?this.each(function(b){n(this).wrapAll(a.call(this,b))}):(this[0]&&(b=n(a,this[0].ownerDocument).eq(0).clone(!0),this[0].parentNode&&b.insertBefore(this[0]),b.map(function(){var a=this;while(a.firstElementChild)a=a.firstElementChild;return a}).append(this)),this)},wrapInner:function(a){return n.isFunction(a)?this.each(function(b){n(this).wrapInner(a.call(this,b))}):this.each(function(){var b=n(this),c=b.contents();c.length?c.wrapAll(a):b.append(a)})},wrap:function(a){var b=n.isFunction(a);return this.each(function(c){n(this).wrapAll(b?a.call(this,c):a)})},unwrap:function(){return this.parent().each(function(){n.nodeName(this,"body")||n(this).replaceWith(this.childNodes)}).end()}}),n.expr.filters.hidden=function(a){return!n.expr.filters.visible(a)},n.expr.filters.visible=function(a){return a.offsetWidth>0||a.offsetHeight>0||a.getClientRects().length>0};var Bb=/%20/g,Cb=/\[\]$/,Db=/\r?\n/g,Eb=/^(?:submit|button|image|reset|file)$/i,Fb=/^(?:input|select|textarea|keygen)/i;function Gb(a,b,c,d){var e;if(n.isArray(b))n.each(b,function(b,e){c||Cb.test(a)?d(a,e):Gb(a+"["+("object"==typeof e&&null!=e?b:"")+"]",e,c,d)});else if(c||"object"!==n.type(b))d(a,b);else for(e in b)Gb(a+"["+e+"]",b[e],c,d)}n.param=function(a,b){var c,d=[],e=function(a,b){b=n.isFunction(b)?b():null==b?"":b,d[d.length]=encodeURIComponent(a)+"="+encodeURIComponent(b)};if(void 0===b&&(b=n.ajaxSettings&&n.ajaxSettings.traditional),n.isArray(a)||a.jquery&&!n.isPlainObject(a))n.each(a,function(){e(this.name,this.value)});else for(c in a)Gb(c,a[c],b,e);return d.join("&").replace(Bb,"+")},n.fn.extend({serialize:function(){return n.param(this.serializeArray())},serializeArray:function(){return this.map(function(){var a=n.prop(this,"elements");return a?n.makeArray(a):this}).filter(function(){var a=this.type;return this.name&&!n(this).is(":disabled")&&Fb.test(this.nodeName)&&!Eb.test(a)&&(this.checked||!X.test(a))}).map(function(a,b){var c=n(this).val();return null==c?null:n.isArray(c)?n.map(c,function(a){return{name:b.name,value:a.replace(Db,"\r\n")}}):{name:b.name,value:c.replace(Db,"\r\n")}}).get()}}),n.ajaxSettings.xhr=function(){try{return new a.XMLHttpRequest}catch(b){}};var Hb={0:200,1223:204},Ib=n.ajaxSettings.xhr();l.cors=!!Ib&&"withCredentials"in Ib,l.ajax=Ib=!!Ib,n.ajaxTransport(function(b){var c,d;return l.cors||Ib&&!b.crossDomain?{send:function(e,f){var g,h=b.xhr();if(h.open(b.type,b.url,b.async,b.username,b.password),b.xhrFields)for(g in b.xhrFields)h[g]=b.xhrFields[g];b.mimeType&&h.overrideMimeType&&h.overrideMimeType(b.mimeType),b.crossDomain||e["X-Requested-With"]||(e["X-Requested-With"]="XMLHttpRequest");for(g in e)h.setRequestHeader(g,e[g]);c=function(a){return function(){c&&(c=d=h.onload=h.onerror=h.onabort=h.onreadystatechange=null,"abort"===a?h.abort():"error"===a?"number"!=typeof h.status?f(0,"error"):f(h.status,h.statusText):f(Hb[h.status]||h.status,h.statusText,"text"!==(h.responseType||"text")||"string"!=typeof h.responseText?{binary:h.response}:{text:h.responseText},h.getAllResponseHeaders()))}},h.onload=c(),d=h.onerror=c("error"),void 0!==h.onabort?h.onabort=d:h.onreadystatechange=function(){4===h.readyState&&a.setTimeout(function(){c&&d()})},c=c("abort");try{h.send(b.hasContent&&b.data||null)}catch(i){if(c)throw i}},abort:function(){c&&c()}}:void 0}),n.ajaxSetup({accepts:{script:"text/javascript, application/javascript, application/ecmascript, application/x-ecmascript"},contents:{script:/\b(?:java|ecma)script\b/},converters:{"text script":function(a){return n.globalEval(a),a}}}),n.ajaxPrefilter("script",function(a){void 0===a.cache&&(a.cache=!1),a.crossDomain&&(a.type="GET")}),n.ajaxTransport("script",function(a){if(a.crossDomain){var b,c;return{send:function(e,f){b=n("<script>").prop({charset:a.scriptCharset,src:a.url}).on("load error",c=function(a){b.remove(),c=null,a&&f("error"===a.type?404:200,a.type)}),d.head.appendChild(b[0])},abort:function(){c&&c()}}}});var Jb=[],Kb=/(=)\?(?=&|$)|\?\?/;n.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var a=Jb.pop()||n.expando+"_"+kb++;return this[a]=!0,a}}),n.ajaxPrefilter("json jsonp",function(b,c,d){var e,f,g,h=b.jsonp!==!1&&(Kb.test(b.url)?"url":"string"==typeof b.data&&0===(b.contentType||"").indexOf("application/x-www-form-urlencoded")&&Kb.test(b.data)&&"data");return h||"jsonp"===b.dataTypes[0]?(e=b.jsonpCallback=n.isFunction(b.jsonpCallback)?b.jsonpCallback():b.jsonpCallback,h?b[h]=b[h].replace(Kb,"$1"+e):b.jsonp!==!1&&(b.url+=(lb.test(b.url)?"&":"?")+b.jsonp+"="+e),b.converters["script json"]=function(){return g||n.error(e+" was not called"),g[0]},b.dataTypes[0]="json",f=a[e],a[e]=function(){g=arguments},d.always(function(){void 0===f?n(a).removeProp(e):a[e]=f,b[e]&&(b.jsonpCallback=c.jsonpCallback,Jb.push(e)),g&&n.isFunction(f)&&f(g[0]),g=f=void 0}),"script"):void 0}),n.parseHTML=function(a,b,c){if(!a||"string"!=typeof a)return null;"boolean"==typeof b&&(c=b,b=!1),b=b||d;var e=x.exec(a),f=!c&&[];return e?[b.createElement(e[1])]:(e=ca([a],b,f),f&&f.length&&n(f).remove(),n.merge([],e.childNodes))};var Lb=n.fn.load;n.fn.load=function(a,b,c){if("string"!=typeof a&&Lb)return Lb.apply(this,arguments);var d,e,f,g=this,h=a.indexOf(" ");return h>-1&&(d=n.trim(a.slice(h)),a=a.slice(0,h)),n.isFunction(b)?(c=b,b=void 0):b&&"object"==typeof b&&(e="POST"),g.length>0&&n.ajax({url:a,type:e||"GET",dataType:"html",data:b}).done(function(a){f=arguments,g.html(d?n("<div>").append(n.parseHTML(a)).find(d):a)}).always(c&&function(a,b){g.each(function(){c.apply(this,f||[a.responseText,b,a])})}),this},n.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(a,b){n.fn[b]=function(a){return this.on(b,a)}}),n.expr.filters.animated=function(a){return n.grep(n.timers,function(b){return a===b.elem}).length};function Mb(a){return n.isWindow(a)?a:9===a.nodeType&&a.defaultView}n.offset={setOffset:function(a,b,c){var d,e,f,g,h,i,j,k=n.css(a,"position"),l=n(a),m={};"static"===k&&(a.style.position="relative"),h=l.offset(),f=n.css(a,"top"),i=n.css(a,"left"),j=("absolute"===k||"fixed"===k)&&(f+i).indexOf("auto")>-1,j?(d=l.position(),g=d.top,e=d.left):(g=parseFloat(f)||0,e=parseFloat(i)||0),n.isFunction(b)&&(b=b.call(a,c,n.extend({},h))),null!=b.top&&(m.top=b.top-h.top+g),null!=b.left&&(m.left=b.left-h.left+e),"using"in b?b.using.call(a,m):l.css(m)}},n.fn.extend({offset:function(a){if(arguments.length)return void 0===a?this:this.each(function(b){n.offset.setOffset(this,a,b)});var b,c,d=this[0],e={top:0,left:0},f=d&&d.ownerDocument;if(f)return b=f.documentElement,n.contains(b,d)?(e=d.getBoundingClientRect(),c=Mb(f),{top:e.top+c.pageYOffset-b.clientTop,left:e.left+c.pageXOffset-b.clientLeft}):e},position:function(){if(this[0]){var a,b,c=this[0],d={top:0,left:0};return"fixed"===n.css(c,"position")?b=c.getBoundingClientRect():(a=this.offsetParent(),b=this.offset(),n.nodeName(a[0],"html")||(d=a.offset()),d.top+=n.css(a[0],"borderTopWidth",!0),d.left+=n.css(a[0],"borderLeftWidth",!0)),{top:b.top-d.top-n.css(c,"marginTop",!0),left:b.left-d.left-n.css(c,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var a=this.offsetParent;while(a&&"static"===n.css(a,"position"))a=a.offsetParent;return a||Ea})}}),n.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(a,b){var c="pageYOffset"===b;n.fn[a]=function(d){return K(this,function(a,d,e){var f=Mb(a);return void 0===e?f?f[b]:a[d]:void(f?f.scrollTo(c?f.pageXOffset:e,c?e:f.pageYOffset):a[d]=e)},a,d,arguments.length)}}),n.each(["top","left"],function(a,b){n.cssHooks[b]=Ga(l.pixelPosition,function(a,c){return c?(c=Fa(a,b),Ba.test(c)?n(a).position()[b]+"px":c):void 0})}),n.each({Height:"height",Width:"width"},function(a,b){n.each({padding:"inner"+a,content:b,"":"outer"+a},function(c,d){n.fn[d]=function(d,e){var f=arguments.length&&(c||"boolean"!=typeof d),g=c||(d===!0||e===!0?"margin":"border");return K(this,function(b,c,d){var e;return n.isWindow(b)?b.document.documentElement["client"+a]:9===b.nodeType?(e=b.documentElement,Math.max(b.body["scroll"+a],e["scroll"+a],b.body["offset"+a],e["offset"+a],e["client"+a])):void 0===d?n.css(b,c,g):n.style(b,c,d,g)},b,f?d:void 0,f,null)}})}),n.fn.extend({bind:function(a,b,c){return this.on(a,null,b,c)},unbind:function(a,b){return this.off(a,null,b)},delegate:function(a,b,c,d){return this.on(b,a,c,d)},undelegate:function(a,b,c){return 1===arguments.length?this.off(a,"**"):this.off(b,a||"**",c)},size:function(){return this.length}}),n.fn.andSelf=n.fn.addBack,"function"==typeof define&&define.amd&&define("jquery",[],function(){return n});var Nb=a.jQuery,Ob=a.$;return n.noConflict=function(b){return a.$===n&&(a.$=Ob),b&&a.jQuery===n&&(a.jQuery=Nb),n},b||(a.jQuery=a.$=n),n});
diff --git a/y2016/dashboard/www_defaults/_404.png b/y2016/dashboard/www_defaults/_404.png
new file mode 100644
index 0000000..8a43cb8
--- /dev/null
+++ b/y2016/dashboard/www_defaults/_404.png
Binary files differ
diff --git a/y2016/dashboard/www_defaults/_error.css b/y2016/dashboard/www_defaults/_error.css
new file mode 100644
index 0000000..565d0a4
--- /dev/null
+++ b/y2016/dashboard/www_defaults/_error.css
@@ -0,0 +1,60 @@
+/*
+From Seasocks version 1.1.2, under /src/main/web
+
+Copyright (c) 2013, Matt Godbolt
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+Redistributions of source code must retain the above copyright notice, this
+list of conditions and the following disclaimer.
+Redistributions in binary form must reproduce the above copyright notice, this
+list of conditions and the following disclaimer in the documentation and/or
+other materials provided with the distribution.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+body {
+ font-family: segoe ui, tahoma, arial, sans-serif;
+ color: #ffffff;
+ background-color: #c21e29;
+ text-align: center;
+}
+
+a {
+ color: #ffff00;
+}
+
+.footer {
+ font-style: italic;
+}
+
+.message {
+ display: inline-block;
+ border: 1px solid white;
+ padding: 50px;
+ font-size: 20px;
+}
+
+.headline {
+ padding: 50px;
+ font-weight: bold;
+ font-size: 32px;
+}
+
+.footer {
+ padding-top: 50px;
+ font-size: 12px;
+}
+
diff --git a/y2016/dashboard/www_defaults/_error.html b/y2016/dashboard/www_defaults/_error.html
new file mode 100644
index 0000000..e3d422d
--- /dev/null
+++ b/y2016/dashboard/www_defaults/_error.html
@@ -0,0 +1,42 @@
+<!--
+From Seasocks version 1.1.2, under /src/main/web
+
+Copyright (c) 2013, Matt Godbolt
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+Redistributions of source code must retain the above copyright notice, this
+list of conditions and the following disclaimer.
+Redistributions in binary form must reproduce the above copyright notice, this
+list of conditions and the following disclaimer in the documentation and/or
+other materials provided with the distribution.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+-->
+
+<html DOCTYPE=html>
+<head>
+ <title>%%ERRORCODE%% - %%MESSAGE%% - Keep Calm And Carry On!</title>
+ <link href="/_error.css" rel="stylesheet">
+</head>
+<body>
+ <div class="message">
+ <img src="/_404.png" height="200" width="107">
+ <div class="headline">HTTP_STATUS: %%ERRORCODE%% — %%MESSAGE%%</div>
+ <div class="info">%%BODY%%</div>
+ </div>
+
+ <div class="footer">http_status developed by 971 Spartan Robotics. Server powered by <a href="https://github.com/mattgodbolt/seasocks">SeaSocks</a>. Contact Comran Morshed(comranmorsh@gmail.com) if this 404 error should not be happening...</div>
+</body>
+</html>
diff --git a/y2016/dashboard/www_defaults/_seasocks.css b/y2016/dashboard/www_defaults/_seasocks.css
new file mode 100644
index 0000000..5f0b655
--- /dev/null
+++ b/y2016/dashboard/www_defaults/_seasocks.css
@@ -0,0 +1,49 @@
+/*
+From Seasocks version 1.1.2, under /src/main/web
+
+Copyright (c) 2013, Matt Godbolt
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+Redistributions of source code must retain the above copyright notice, this
+list of conditions and the following disclaimer.
+Redistributions in binary form must reproduce the above copyright notice, this
+list of conditions and the following disclaimer in the documentation and/or
+other materials provided with the distribution.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+body {
+ font-family: segoe ui, tahoma, arial, sans-serif;
+ font-size: 12px;
+ color: #ffffff;
+ background-color: #333333;
+ margin: 0;
+}
+
+a {
+ color: #ffff00;
+}
+
+table {
+ border-collapse: collapse;
+ width: 100%;
+ text-align: center;
+}
+
+.template {
+ display: none;
+}
+
diff --git a/y2016/dashboard/www_defaults/_stats.html b/y2016/dashboard/www_defaults/_stats.html
new file mode 100644
index 0000000..2390334
--- /dev/null
+++ b/y2016/dashboard/www_defaults/_stats.html
@@ -0,0 +1,88 @@
+<!--
+From Seasocks version 1.1.2, under /src/main/web
+
+Copyright (c) 2013, Matt Godbolt
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+
+Redistributions of source code must retain the above copyright notice, this
+list of conditions and the following disclaimer.
+Redistributions in binary form must reproduce the above copyright notice, this
+list of conditions and the following disclaimer in the documentation and/or
+other materials provided with the distribution.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
+FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
+SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
+OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+-->
+
+<html DOCTYPE=html>
+<head>
+ <title>SeaSocks Stats</title>
+ <link href="/_seasocks.css" rel="stylesheet">
+ <script src="/_jquery.min.js" type="text/javascript"></script>
+ <script>
+ function clear() {
+ $('#cx tbody tr:visible').remove();
+ }
+ function connection(stats) {
+ c = $('#cx .template').clone().removeClass('template').appendTo('#cx');
+ for (stat in stats) {
+ c.find('.' + stat).text(stats[stat]);
+ }
+ }
+ function refresh() {
+ var stats = new XMLHttpRequest();
+ stats.open("GET", "/_livestats.js", false);
+ stats.send(null);
+ eval(stats.responseText);
+ }
+ $(function() {
+ setInterval(refresh, 1000);
+ refresh();
+ });
+ </script>
+</head>
+<body><h1>SeaSocks Stats</h1></body>
+
+<h2>Connections</h2>
+<table id="cx">
+ <thead>
+ <tr>
+ <th>Connection time</th>
+ <th>Fd</th>
+ <th>Addr</th>
+ <th>URI</th>
+ <th>Username</th>
+ <th>Pending read</th>
+ <th>Bytes read</th>
+ <th>Pending send</th>
+ <th>Bytes sent</th>
+ </tr>
+ </thead>
+ <tbody>
+ <tr class="template">
+ <td class="since"></td>
+ <td class="fd"></td>
+ <td class="addr"></td>
+ <td class="uri"></td>
+ <td class="user"></td>
+ <td class="input"></td>
+ <td class="read"></td>
+ <td class="output"></td>
+ <td class="written"></td>
+ </tr>
+ </tbody>
+</table>
+
+</body>
+</html>
diff --git a/y2016/dashboard/www_defaults/favicon.ico b/y2016/dashboard/www_defaults/favicon.ico
new file mode 100644
index 0000000..bedac26
--- /dev/null
+++ b/y2016/dashboard/www_defaults/favicon.ico
Binary files differ
diff --git a/y2016/joystick_reader.cc b/y2016/joystick_reader.cc
index 0023ac8..45733ff 100644
--- a/y2016/joystick_reader.cc
+++ b/y2016/joystick_reader.cc
@@ -23,6 +23,7 @@
#include "frc971/autonomous/auto.q.h"
#include "y2016/actors/autonomous_actor.h"
#include "y2016/actors/vision_align_actor.h"
+#include "y2016/actors/superstructure_actor.h"
#include "y2016/control_loops/drivetrain/drivetrain_base.h"
using ::frc971::control_loops::drivetrain_queue;
@@ -55,7 +56,6 @@
// Buttons on the lexan driver station to get things running on bring-up day.
const ButtonLocation kIntakeDown(3, 11);
const POVLocation kFrontLong(3, 180);
-const ButtonLocation kHigherFrontLong(3, 6);
const POVLocation kBackLong(3, 0);
const POVLocation kBackFender(3, 90);
const POVLocation kFrontFender(3, 270);
@@ -67,6 +67,9 @@
const ButtonLocation kVisionAlign(3, 4);
+const ButtonLocation kExpand(3, 6);
+const ButtonLocation kWinch(3, 5);
+
class Reader : public ::aos::input::JoystickInput {
public:
Reader()
@@ -122,12 +125,19 @@
const double wheel = -data.GetAxis(kSteeringWheel);
const double throttle = -data.GetAxis(kDriveThrottle);
+ drivetrain_queue.status.FetchLatest();
- if (data.IsPressed(kVisionAlign) && vision_valid_ &&
- !vision_action_running_) {
- actors::VisionAlignActionParams params;
- action_queue_.EnqueueAction(actors::MakeVisionAlignAction(params));
- vision_action_running_ = true;
+ if (data.IsPressed(kVisionAlign)) {
+ if (vision_valid_ && !vision_action_running_) {
+ actors::VisionAlignActionParams params;
+ action_queue_.EnqueueAction(actors::MakeVisionAlignAction(params));
+ vision_action_running_ = true;
+ LOG(INFO, "Starting vision align\n");
+ } else {
+ if (!vision_valid_) {
+ LOG(INFO, "Vision align but not valid\n");
+ }
+ }
}
if (data.NegEdge(kVisionAlign)) {
@@ -138,12 +148,11 @@
}
// Don't do any normal drivetrain stuff if vision is in charge.
- if (was_running_) {
+ if (vision_action_running_) {
return;
}
if (data.PosEdge(kTurn1) || data.PosEdge(kTurn2)) {
- drivetrain_queue.status.FetchLatest();
if (drivetrain_queue.status.get()) {
left_goal = drivetrain_queue.status->estimated_left_position;
right_goal = drivetrain_queue.status->estimated_right_position;
@@ -176,6 +185,7 @@
}
void HandleTeleop(const ::aos::input::driver_station::Data &data) {
+ float voltage_climber = 0.0;
// Default the intake to up.
intake_goal_ = constants::Values::kIntakeRange.upper - 0.04;
@@ -209,41 +219,66 @@
}
}
- if (data.IsPressed(kHigherFrontLong)) {
+ if (data.IsPressed(kFrontLong)) {
// Forwards shot
shoulder_goal_ = M_PI / 2.0 + 0.1;
- wrist_goal_ = M_PI + 0.43;
- shooter_velocity_ = 640.0;
- intake_goal_ = intake_when_shooting;
- } else if (data.IsPressed(kFrontLong)) {
- // Forwards shot
- shoulder_goal_ = M_PI / 2.0 + 0.1;
- wrist_goal_ = M_PI + 0.40;
+ wrist_goal_ = M_PI + 0.41 + 0.02 - 0.005;
+ if (drivetrain_queue.status.get()) {
+ wrist_goal_ += drivetrain_queue.status->ground_angle;
+ }
shooter_velocity_ = 640.0;
intake_goal_ = intake_when_shooting;
} else if (data.IsPressed(kBackLong)) {
// Backwards shot
shoulder_goal_ = M_PI / 2.0 - 0.4;
- wrist_goal_ = -0.62;
+ wrist_goal_ = -0.62 - 0.02;
+ if (drivetrain_queue.status.get()) {
+ wrist_goal_ += drivetrain_queue.status->ground_angle;
+ }
shooter_velocity_ = 640.0;
intake_goal_ = intake_when_shooting;
} else if (data.IsPressed(kBackFender)) {
// Fender shot back
- shoulder_goal_ = 0.65;
- wrist_goal_ = -1.20;
- shooter_velocity_ = 550.0;
+ shoulder_goal_ = M_PI / 2.0 - 0.2;
+ wrist_goal_ = -0.55;
+ shooter_velocity_ = 600.0;
intake_goal_ = intake_when_shooting;
} else if (data.IsPressed(kFrontFender)) {
- // Fender shot back
- shoulder_goal_ = 1.45;
- wrist_goal_ = 2.5 + 1.7;
- shooter_velocity_ = 550.0;
+ // Forwards shot, higher
+ shoulder_goal_ = M_PI / 2.0 + 0.1;
+ wrist_goal_ = M_PI + 0.41 + 0.02 + 0.020;
+ if (drivetrain_queue.status.get()) {
+ wrist_goal_ += drivetrain_queue.status->ground_angle;
+ }
+ shooter_velocity_ = 640.0;
intake_goal_ = intake_when_shooting;
+ } else if (data.IsPressed(kExpand) || data.IsPressed(kWinch)) {
+ // Set the goals to the hanging position so when the actor finishes, we
+ // will still be at the right spot.
+ shoulder_goal_ = 1.2;
+ wrist_goal_ = 1.0;
+ intake_goal_ = 0.0;
+ if (data.PosEdge(kExpand)) {
+ is_expanding_ = true;
+ actors::SuperstructureActionParams params;
+ params.partial_angle = 0.3;
+ params.delay_time = 0.7;
+ params.full_angle = shoulder_goal_;
+ params.shooter_angle = wrist_goal_;
+ action_queue_.EnqueueAction(actors::MakeSuperstructureAction(params));
+ }
+ if (data.IsPressed(kWinch)) {
+ voltage_climber = 12.0;
+ }
} else {
wrist_goal_ = 0.0;
shoulder_goal_ = -0.010;
shooter_velocity_ = 0.0;
}
+ if (data.NegEdge(kExpand) || voltage_climber > 1.0) {
+ is_expanding_ = false;
+ action_queue_.CancelAllActions();
+ }
bool ball_detected = false;
::y2016::sensors::ball_detector.FetchLatest();
@@ -329,50 +364,59 @@
}
if (!waiting_for_zero_) {
- auto new_superstructure_goal = superstructure_queue.goal.MakeMessage();
- new_superstructure_goal->angle_intake = intake_goal_;
- new_superstructure_goal->angle_shoulder = shoulder_goal_;
- new_superstructure_goal->angle_wrist = wrist_goal_;
+ if (!is_expanding_) {
+ auto new_superstructure_goal = superstructure_queue.goal.MakeMessage();
+ new_superstructure_goal->angle_intake = intake_goal_;
+ new_superstructure_goal->angle_shoulder = shoulder_goal_;
+ new_superstructure_goal->angle_wrist = wrist_goal_;
- new_superstructure_goal->max_angular_velocity_intake = 7.0;
- new_superstructure_goal->max_angular_velocity_shoulder = 4.0;
- new_superstructure_goal->max_angular_velocity_wrist = 10.0;
- if (use_slow_profile) {
- new_superstructure_goal->max_angular_acceleration_intake = 10.0;
- } else {
- new_superstructure_goal->max_angular_acceleration_intake = 40.0;
- }
- new_superstructure_goal->max_angular_acceleration_shoulder = 10.0;
- new_superstructure_goal->max_angular_acceleration_wrist = 25.0;
+ new_superstructure_goal->max_angular_velocity_intake = 7.0;
+ new_superstructure_goal->max_angular_velocity_shoulder = 4.0;
+ new_superstructure_goal->max_angular_velocity_wrist = 10.0;
+ if (use_slow_profile) {
+ new_superstructure_goal->max_angular_acceleration_intake = 10.0;
+ } else {
+ new_superstructure_goal->max_angular_acceleration_intake = 40.0;
+ }
+ new_superstructure_goal->max_angular_acceleration_shoulder = 10.0;
+ if (shoulder_goal_ > 1.0) {
+ new_superstructure_goal->max_angular_acceleration_wrist = 45.0;
+ } else {
+ new_superstructure_goal->max_angular_acceleration_wrist = 25.0;
+ }
- // Granny mode
- /*
- new_superstructure_goal->max_angular_velocity_intake = 0.2;
- new_superstructure_goal->max_angular_velocity_shoulder = 0.2;
- new_superstructure_goal->max_angular_velocity_wrist = 0.2;
- new_superstructure_goal->max_angular_acceleration_intake = 1.0;
- new_superstructure_goal->max_angular_acceleration_shoulder = 1.0;
- new_superstructure_goal->max_angular_acceleration_wrist = 1.0;
- */
- if (is_intaking_) {
- new_superstructure_goal->voltage_top_rollers = 12.0;
- new_superstructure_goal->voltage_bottom_rollers = 12.0;
- } else if (is_outtaking_) {
- new_superstructure_goal->voltage_top_rollers = -12.0;
- new_superstructure_goal->voltage_bottom_rollers = -7.0;
- } else {
- new_superstructure_goal->voltage_top_rollers = 0.0;
- new_superstructure_goal->voltage_bottom_rollers = 0.0;
- }
+ // Granny mode
+ /*
+ new_superstructure_goal->max_angular_velocity_intake = 0.2;
+ new_superstructure_goal->max_angular_velocity_shoulder = 0.2;
+ new_superstructure_goal->max_angular_velocity_wrist = 0.2;
+ new_superstructure_goal->max_angular_acceleration_intake = 1.0;
+ new_superstructure_goal->max_angular_acceleration_shoulder = 1.0;
+ new_superstructure_goal->max_angular_acceleration_wrist = 1.0;
+ */
+ if (is_intaking_) {
+ new_superstructure_goal->voltage_top_rollers = 12.0;
+ new_superstructure_goal->voltage_bottom_rollers = 12.0;
+ } else if (is_outtaking_) {
+ new_superstructure_goal->voltage_top_rollers = -12.0;
+ new_superstructure_goal->voltage_bottom_rollers = -7.0;
+ } else {
+ new_superstructure_goal->voltage_top_rollers = 0.0;
+ new_superstructure_goal->voltage_bottom_rollers = 0.0;
+ }
- new_superstructure_goal->traverse_unlatched = traverse_unlatched_;
- new_superstructure_goal->traverse_down = traverse_down_;
+ new_superstructure_goal->traverse_unlatched = traverse_unlatched_;
+ new_superstructure_goal->unfold_climber = false;
+ new_superstructure_goal->voltage_climber = voltage_climber;
+ new_superstructure_goal->traverse_down = traverse_down_;
+ new_superstructure_goal->force_intake = true;
- if (!new_superstructure_goal.Send()) {
- LOG(ERROR, "Sending superstructure goal failed.\n");
- } else {
- LOG(DEBUG, "sending goals: intake: %f, shoulder: %f, wrist: %f\n",
- intake_goal_, shoulder_goal_, wrist_goal_);
+ if (!new_superstructure_goal.Send()) {
+ LOG(ERROR, "Sending superstructure goal failed.\n");
+ } else {
+ LOG(DEBUG, "sending goals: intake: %f, shoulder: %f, wrist: %f\n",
+ intake_goal_, shoulder_goal_, wrist_goal_);
+ }
}
if (!shooter_queue.goal.MakeWithBuilder()
@@ -380,6 +424,7 @@
.clamp_open(is_intaking_ || is_outtaking_)
.push_to_shooter(fire_)
.force_lights_on(force_lights_on)
+ .shooting_forwards(wrist_goal_ > 0)
.Send()) {
LOG(ERROR, "Sending shooter goal failed.\n");
}
@@ -441,6 +486,8 @@
const ::frc971::control_loops::drivetrain::DrivetrainConfig dt_config_;
+ bool is_expanding_ = false;
+
::aos::util::SimpleLogInterval no_drivetrain_status_ =
::aos::util::SimpleLogInterval(::aos::time::Time::InSeconds(0.2), WARNING,
"no drivetrain status");
diff --git a/y2016/plotting/responsive_plotter.js b/y2016/plotting/responsive_plotter.js
new file mode 100644
index 0000000..0840e1d
--- /dev/null
+++ b/y2016/plotting/responsive_plotter.js
@@ -0,0 +1,238 @@
+"use strict";
+
+// Create anonymous namespace to avoid leaking these functions.
+(function() {
+// Convenience function that fetches a file and extracts the array buffer.
+function fetch_ArrayBuffer(url) { // returns Promise<ArrayBuffer>
+ return fetch(url).then(function(val) { return val.arrayBuffer(); });
+}
+
+// Two dimensional vector.
+class Point2d {
+ constructor(x, y) {
+ this.x = x;
+ this.y = y;
+ }
+ sub(o) { return new Point2d(this.x - o.x, this.y - o.y); }
+ add(o) { return new Point2d(this.x + o.x, this.y + o.y); }
+};
+
+// Drag event object for updating a Point2d class by reference.
+class PointDrag {
+ constructor(point) { // point : Point2d
+ this.point = point;
+ }
+ doDrag(delta) {
+ this.point.x += delta.x;
+ this.point.y += delta.y;
+ }
+ doMouseUp(e) { return null; }
+}
+
+// Takes in a canvas and adds the ability to click and drag the offset point.
+// scaleX and scaleY are allowed to be locked or not-locked as the scroll events
+// must be handled by the user of this class.
+//
+// offset.x and offset.y are defined in reference to the model-scale, not the viewport.
+// Thus to move the viewport you need to use offset.x * scaleX, etc.
+//
+// scaleX and scaleY aren't automatically applied to the rendering context because
+// differing x and y scales mess up the line width rendering.
+class ClickDrag {
+ constructor(canvas) {
+ canvas.addEventListener('selectstart', function(e) { e.preventDefault(); return false; }, false);
+ canvas.addEventListener('mousemove', this.handleMouseMove.bind(this), true);
+ canvas.addEventListener('mousedown', this.handleMouseDown.bind(this), true);
+ canvas.addEventListener('mouseup', this.handleMouseUp.bind(this), true);
+ this.canvas = canvas;
+ this.dragger = null;
+ this.offset = new Point2d(0, 0);
+ this.scaleX = 1.0;
+ this.scaleY = 1.0;
+ this.old_point = null;
+ this.on_redraw = null;
+ }
+ translateContext(ctx) { // ctx : CanvasRenderingContext2D
+ ctx.translate(this.offset.x * this.scaleX, this.offset.y * this.scaleY);
+ }
+ handleMouseMove(e) { // e : MouseEvent
+ let pos = new Point2d(e.offsetX / this.scaleX, e.offsetY / this.scaleY);
+ if (this.old_point !== null && this.dragger !== null) {
+ this.dragger.doDrag(pos.sub(this.old_point));
+ if (this.on_redraw !== null) { this.on_redraw(); }
+ }
+ this.old_point = pos;
+ }
+ get width() { return this.canvas.width; }
+ handleMouseDown(e) { // e : MouseEvent
+ this.dragger = new PointDrag(this.offset);
+ }
+ handleMouseUp(e) { // e : MouseEvent
+ if (this.dragger === null) { return; }
+ if (this.dragger.doMouseUp !== undefined) {
+ this.dragger = this.dragger.doMouseUp(e);
+ if (this.on_redraw !== null) { this.on_redraw(); }
+ }
+ }
+ multiplyScale(evt, dx, dy) {
+ let x_cur = evt.offsetX / this.scaleX - this.offset.x;
+ let y_cur = evt.offsetY / this.scaleY - this.offset.y;
+ this.scaleX *= dx;
+ this.scaleY *= dy;
+ this.offset.x = evt.offsetX / this.scaleX - x_cur;
+ this.offset.y = evt.offsetY / this.scaleY - y_cur;
+ if (this.on_redraw !== null) { this.on_redraw(); }
+ }
+};
+
+// This represents a particular downsampling of a timeseries dataset.
+// For the base level, data = min = max.
+// This is required
+class MipMapLevel {
+ // All arrays should be the same size.
+ constructor(data, min, max, scale) { // data : Float32Array, min : Float32Array, max : Float32Array, scale : Integer
+ this.data = data;
+ this.min = min;
+ this.max = max;
+ this.scale = scale;
+ }
+ get length() { return this.data.length; }
+ // Uses box filter to downsample. Guassian may be an improvement.
+ downsample() {
+ let new_length = (this.data.length / 2) | 0;
+ let data = new Float32Array(new_length);
+ let min = new Float32Array(new_length);
+ let max = new Float32Array(new_length);
+ for (let i = 0; i < new_length; i++) {
+ let i1 = i * 2;
+ let i2 = i1 + 1
+ data[i] = (this.data[i1] + this.data[i2]) / 2.0;
+ min[i] = Math.min(this.min[i1], this.min[i2]);
+ max[i] = Math.max(this.max[i1], this.max[i2]);
+ }
+ return new MipMapLevel(data, min, max, this.scale * 2);
+ }
+ static makeBaseLevel(data) { // data : Float32Array
+ return new MipMapLevel(data, data, data, 1);
+ }
+ clipv(v) { // v : Numeric
+ return Math.min(Math.max(v|0, 0), this.length - 1);
+ }
+ draw(ctx, clickDrag) { // ctx : CanvasRenderingContext2D, clickDrag : ClickDrag
+ let scalex = clickDrag.scaleX * this.scale;
+ let scaley = clickDrag.scaleY;
+ let stx = -clickDrag.offset.x / this.scale;
+ let edx = stx + clickDrag.width / scalex;
+ let sti = this.clipv(stx - 2);
+ let edi = this.clipv(edx + 2);
+ ctx.beginPath();
+ ctx.fillStyle="#00ff00";
+ ctx.moveTo(sti * scalex, scaley * this.min[sti]);
+ for (let i = sti + 1; i <= edi; i++) {
+ ctx.lineTo(i * scalex, scaley * this.min[i]);
+ }
+ for (let i = edi; i >= sti; --i) {
+ ctx.lineTo(i * scalex, scaley * this.max[i]);
+ }
+ ctx.fill();
+ ctx.closePath();
+
+ ctx.beginPath();
+ ctx.strokeStyle="#008f00";
+ ctx.moveTo(sti * scalex, scaley * this.data[sti]);
+ for (let i = sti + 1; i <= edi; i++) {
+ ctx.lineTo(i * scalex, scaley * this.data[i]);
+ }
+ ctx.stroke();
+ ctx.closePath();
+ }
+};
+
+// This class represents all downsampled data levels.
+// This must only be used for descrite time-series data.
+class MipMapper {
+ constructor(samples) { // samples : Float32Array
+ this.levels = [];
+ let level = MipMapLevel.makeBaseLevel(samples);
+ this.levels.push(level);
+ while (level.length > 2) {
+ level = level.downsample();
+ this.levels.push(level);
+ }
+ }
+ // Find the level such that samples are spaced at most 2 pixels apart
+ getLevel(scale) { // scale : Float
+ let level = this.levels[0];
+ for (let i = 0; i < this.levels.length; ++i) {
+ // Someone who understands nyquist could probably improve this.
+ if (this.levels[i].scale * scale <= 4.0) {
+ level = this.levels[i];
+ }
+ }
+ return level;
+ }
+}
+
+// Custom HTML element for x-responsive-plotter.
+// This should be the main entry-point for this code.
+class ResponsivePlotter extends HTMLElement {
+ createdCallback() {
+ this.data = null;
+ this.canvas = document.createElement("canvas");
+ this.canvas.style["background"] = "inherit";
+ this.canvas.addEventListener("mousewheel", this.doScroll.bind(this), false);
+ this.clickDrag = new ClickDrag(this.canvas);
+ this.clickDrag.on_redraw = this.doRedraw.bind(this);
+ this.clickDrag.offset.y = 160; //320;
+ this.updateInnerData();
+ this.appendChild(this.canvas);
+ }
+ doScroll(e) {
+ let factor = (e.wheelDelta < 0) ? 0.9 : 1.1;
+ this.clickDrag.multiplyScale(e, e.shiftKey ? 1.0 : factor, e.shiftKey ? factor : 1.0);
+ e.preventDefault();
+ }
+ doRedraw() {
+ this.redraw();
+ }
+ updateInnerData() {
+ this.canvas.width = this.getAttribute("width") || 640;
+ this.canvas.height = this.getAttribute("height") || 480;
+ fetch_ArrayBuffer(this.getAttribute("data")).then(this.dataUpdated.bind(this));
+ this.redraw();
+ }
+ attributeChangedCallback(attrName, oldVal, newVal) {
+ if (attrName == "width") {
+ this.canvas.width = this.getAttribute("width") || 640;
+ this.redraw();
+ } else if (attrName == "height") {
+ this.canvas.width = this.getAttribute("height") || 480;
+ this.redraw();
+ } else if (attrName == "data") {
+ // Should this clear out the canvas if a different url is selected?
+ // Well it does.
+ this.data = null;
+ fetch_ArrayBuffer(this.getAttribute("data")).then(this.dataUpdated.bind(this));
+ }
+ }
+ dataUpdated(data) { // data : ArrayBuffer
+ this.data = new MipMapper(new Float32Array(data));
+ this.redraw();
+ }
+ redraw() {
+ let ctx = this.canvas.getContext('2d');
+ ctx.clearRect(0, 0, this.canvas.width, this.canvas.height);
+ ctx.save();
+ this.clickDrag.translateContext(ctx);
+ if (this.data !== null) {
+ let level = this.data.getLevel(this.clickDrag.scaleX);
+ level.draw(ctx, this.clickDrag);
+ }
+ ctx.restore();
+ }
+};
+
+
+// TODO(parker): This is chrome-specific v0 version of this switch to v1 when available.
+document.registerElement('x-responsive-plotter', ResponsivePlotter);
+})();
diff --git a/y2016/plotting/test.html b/y2016/plotting/test.html
new file mode 100644
index 0000000..df278b0
--- /dev/null
+++ b/y2016/plotting/test.html
@@ -0,0 +1,12 @@
+<!DOCTYPE html>
+<html>
+ <head>
+ <meta charset="UTF-8">
+ <script src="/responsive_plotter.js" type="text/javascript"></script>
+ </head>
+
+ <body style=>
+ <x-responsive-plotter width=800 data="/test_data" style="background: lightblue;">
+ </x-responsive-plotter>
+ </body>
+</html>
diff --git a/y2016/plotting/test.rb b/y2016/plotting/test.rb
new file mode 100644
index 0000000..9f2f58a
--- /dev/null
+++ b/y2016/plotting/test.rb
@@ -0,0 +1,29 @@
+require "sinatra"
+
+# Must use sinatra server for this because fetch() in javascript
+# cannot load from the filesystem.
+get '/test.html' do
+ File.read("./test.html")
+end
+
+get '/responsive_plotter.js' do
+ content_type 'text/javascript'
+ File.read("./responsive_plotter.js")
+end
+
+get '/test_data' do
+ content_type 'binary/octet-stream'
+ data = ""
+ # Use ./test_data if it exists. Otherwise random data.
+ if (File.exists?("./test_data"))
+ data = File.read("./test_data")
+ else
+ 1000.times do
+ data += (1024.times.collect do |i|
+ (rand() * 480 - 160)
+ end.pack("F*"))
+ end
+ end
+ data
+end
+
diff --git a/y2016/vision/BUILD b/y2016/vision/BUILD
index 550e605..f41ea84 100644
--- a/y2016/vision/BUILD
+++ b/y2016/vision/BUILD
@@ -92,5 +92,7 @@
':vision_data',
':stereo_geometry',
'//y2016:constants',
+ '//frc971/control_loops/drivetrain:drivetrain_queue',
+ '//aos/common:mutex',
],
)
diff --git a/y2016/vision/calibration.pb b/y2016/vision/calibration.pb
index 83fd42a..b24a6e4 100644
--- a/y2016/vision/calibration.pb
+++ b/y2016/vision/calibration.pb
@@ -1,7 +1,7 @@
calibration {
robot: "competition"
calibration: {
- focal_length: 1.116070312
+ focal_length: 1.236070312
center_center_dist: 0.27051
center_center_skew: -16.65
camera_y_skew: 20.0
@@ -15,14 +15,14 @@
camera_exposure: 10
camera_brightness: 128
camera_gain: 0
- camera_fps: 10
+ camera_fps: 20
}
}
calibration {
robot: "practice"
calibration {
- focal_length: 1.1160703125
+ focal_length: 1.236070312
center_center_dist: 0.26829
center_center_skew: 0.0
camera_y_skew: 0.0
@@ -36,7 +36,7 @@
camera_exposure: 10
camera_brightness: 128
camera_gain: 0
- camera_fps: 5
+ camera_fps: 20
}
}
diff --git a/y2016/vision/target_receiver.cc b/y2016/vision/target_receiver.cc
index b51e4ed..3967e60 100644
--- a/y2016/vision/target_receiver.cc
+++ b/y2016/vision/target_receiver.cc
@@ -4,12 +4,19 @@
#include <vector>
#include <memory>
+#include <array>
+#include <thread>
+#include <atomic>
+#include <limits>
#include "aos/linux_code/init.h"
#include "aos/common/time.h"
#include "aos/common/logging/logging.h"
#include "aos/common/logging/queue_logging.h"
#include "aos/vision/events/udp.h"
+#include "aos/common/mutex.h"
+
+#include "frc971/control_loops/drivetrain/drivetrain.q.h"
#include "y2016/vision/vision.q.h"
#include "y2016/vision/vision_data.pb.h"
@@ -19,7 +26,8 @@
namespace y2016 {
namespace vision {
-::aos::vision::Vector<2> CreateCenterFromTarget(double lx, double ly, double rx, double ry) {
+::aos::vision::Vector<2> CreateCenterFromTarget(double lx, double ly, double rx,
+ double ry) {
return ::aos::vision::Vector<2>((lx + rx) / 2.0, (ly + ry) / 2.0);
}
@@ -32,7 +40,8 @@
void SelectTargets(const VisionData &left_target,
const VisionData &right_target,
::aos::vision::Vector<2> *center_left,
- ::aos::vision::Vector<2> *center_right) {
+ ::aos::vision::Vector<2> *center_right, double *angle_left,
+ double *angle_right) {
// No good targets. Let the caller decide defaults.
if (right_target.target_size() == 0 || left_target.target_size() == 0) {
return;
@@ -67,6 +76,7 @@
const double angle = h / wid1;
if (min_angle == -1.0 || ::std::abs(angle) < ::std::abs(min_angle)) {
min_angle = angle;
+ *angle_left = angle;
left_index = i;
}
}
@@ -77,19 +87,21 @@
double good_ang = min_angle;
double min_ang_err = -1.0;
int right_index = -1;
- // Now pick the bottom edge angle from the right that lines up best with the left.
+ // Now pick the bottom edge angle from the right that lines up best with the
+ // left.
for (int j = 0; j < right_target.target_size(); j++) {
double wid2 = TargetWidth(right_target.target(j).left_corner_x(),
- right_target.target(j).left_corner_y(),
- right_target.target(j).right_corner_x(),
- right_target.target(j).right_corner_y());
+ right_target.target(j).left_corner_y(),
+ right_target.target(j).right_corner_x(),
+ right_target.target(j).right_corner_y());
h = right_target.target(j).left_corner_y() -
right_target.target(j).right_corner_y();
- double ang = h/ wid2;
+ double ang = h / wid2;
double ang_err = ::std::abs(good_ang - ang);
if (min_ang_err == -1.0 || min_ang_err > ang_err) {
min_ang_err = ang_err;
right_index = j;
+ *angle_right = ang;
}
}
@@ -105,86 +117,294 @@
right_target.target(right_index).right_corner_y());
}
+class CameraHandler {
+ public:
+ void Received(const VisionData &target, ::aos::time::Time now) {
+ if (current_.received) {
+ last_ = current_;
+ }
+ current_.target = target;
+ current_.rx_time = now;
+ current_.capture_time = now -
+ ::aos::time::Time::InNS(target.send_timestamp() -
+ target.image_timestamp()) +
+ // It takes a bit to shoot a frame. Push the frame
+ // further back in time.
+ ::aos::time::Time::InMS(10);
+ current_.received = true;
+ }
+
+ void CheckStale(::aos::time::Time now) {
+ if (now > current_.rx_time + ::aos::time::Time::InMS(50)) {
+ current_.received = false;
+ last_.received = false;
+ }
+ }
+
+ bool received_both() const { return current_.received && last_.received; }
+
+ bool is_valid() const {
+ return current_.target.target_size() > 0 && last_.target.target_size() > 0;
+ }
+
+ const VisionData &target() const { return current_.target; }
+ const VisionData &last_target() const { return last_.target; }
+
+ ::aos::time::Time capture_time() const { return current_.capture_time; }
+ ::aos::time::Time last_capture_time() const { return last_.capture_time; }
+
+ private:
+ struct TargetWithTimes {
+ VisionData target;
+ ::aos::time::Time rx_time{0, 0};
+ ::aos::time::Time capture_time{0, 0};
+ bool received = false;
+ };
+
+ TargetWithTimes current_;
+ TargetWithTimes last_;
+};
+
+void CalculateFiltered(const CameraHandler &older, const CameraHandler &newer,
+ const ::aos::vision::Vector<2> &newer_center,
+ const ::aos::vision::Vector<2> &last_newer_center,
+ double angle, double last_angle,
+ ::aos::vision::Vector<2> *interpolated_result,
+ double *interpolated_angle) {
+ const double age_ratio =
+ (older.capture_time() - newer.last_capture_time()).ToSeconds() /
+ (newer.capture_time() - newer.last_capture_time()).ToSeconds();
+ interpolated_result->Set(
+ newer_center.x() * age_ratio + (1 - age_ratio) * last_newer_center.x(),
+ newer_center.y() * age_ratio + (1 - age_ratio) * last_newer_center.y());
+
+ *interpolated_angle = angle * age_ratio + (1 - age_ratio) * last_angle;
+}
+
+// Handles calculating drivetrain offsets.
+class DrivetrainOffsetCalculator {
+ public:
+ // To be called by ::std::thread.
+ void operator()() {
+ auto &status = ::frc971::control_loops::drivetrain_queue.status;
+ while (run_) {
+ status.FetchAnother();
+
+ ::aos::MutexLocker locker(&lock_);
+ data_[data_index_].time = status->sent_time;
+ data_[data_index_].left = status->estimated_left_position;
+ data_[data_index_].right = status->estimated_right_position;
+ ++data_index_;
+ if (data_index_ == data_.size()) data_index_ = 0;
+ if (valid_data_ < data_.size()) ++valid_data_;
+ }
+ }
+
+ // Takes a vision status message with everything except
+ // drivetrain_{left,right}_position set and sets those.
+ // Returns false if it doesn't have enough data to fill them out.
+ bool CompleteVisionStatus(::y2016::vision::VisionStatus *status) {
+ if (valid_data_ == 0) return false;
+
+ const ::aos::time::Time capture_time =
+ ::aos::time::Time::InNS(status->target_time);
+ DrivetrainData before, after;
+ FindBeforeAfter(&before, &after, capture_time);
+
+ if (before.time == after.time) {
+ status->drivetrain_left_position = before.left;
+ status->drivetrain_right_position = before.right;
+ } else {
+ const double age_ratio = (capture_time - before.time).ToSeconds() /
+ (after.time - before.time).ToSeconds();
+ status->drivetrain_left_position =
+ before.left * (1 - age_ratio) + after.left * age_ratio;
+ status->drivetrain_right_position =
+ before.right * (1 - age_ratio) + after.right * age_ratio;
+ }
+
+ return true;
+ }
+
+ void Quit() { run_ = false; }
+
+ private:
+ struct DrivetrainData {
+ ::aos::time::Time time;
+ double left, right;
+ };
+
+ // Fills out before and after with the data surrounding capture_time.
+ // They might be identical if that's the closest approximation.
+ // Do not call this if valid_data_ is 0.
+ void FindBeforeAfter(DrivetrainData *before, DrivetrainData *after,
+ ::aos::time::Time capture_time) {
+ ::aos::MutexLocker locker(&lock_);
+ size_t location = 0;
+ while (true) {
+ // We hit the end of our data. Just fill them both out as the last data
+ // point.
+ if (location >= valid_data_) {
+ *before = *after =
+ data_[previous_index((valid_data_ + data_index_) % data_.size())];
+ return;
+ }
+
+ // The index into data_ corresponding to location positions after
+ // (data_index_ - 1).
+ const size_t index = previous_index(location + data_index_);
+
+ // If we've found the one we want.
+ if (data_[index].time > capture_time) {
+ *after = data_[index];
+ if (location == 0) {
+ // If this is the first one and it's already after, just return the
+ // same thing for both.
+ *before = data_[index];
+ } else {
+ *before = data_[previous_index(index)];
+ }
+ return;
+ }
+
+ ++location;
+ }
+ }
+
+ size_t previous_index(size_t index) const {
+ if (index == 0) {
+ return data_.size() - 1;
+ } else {
+ return index - 1;
+ }
+ }
+
+ ::std::array<DrivetrainData, 200> data_;
+ // The index into data_ the next data point is going at.
+ size_t data_index_ = 0;
+ // How many elemets of data_ are valid.
+ size_t valid_data_ = 0;
+
+ ::aos::Mutex lock_;
+
+ ::std::atomic<bool> run_{true};
+};
void Main() {
StereoGeometry stereo(constants::GetValues().vision_name);
LOG(INFO, "calibration: %s\n",
stereo.calibration().ShortDebugString().c_str());
- VisionData left_target;
- aos::time::Time left_rx_time{0, 0};
+ DrivetrainOffsetCalculator drivetrain_offset;
+ ::std::thread drivetrain_offset_thread(::std::ref(drivetrain_offset));
- VisionData right_target;
- aos::time::Time right_rx_time{0, 0};
+ CameraHandler left;
+ CameraHandler right;
::aos::vision::RXUdpSocket recv(8080);
char rawData[65507];
- bool got_left = false;
- bool got_right = false;
while (true) {
// TODO(austin): Don't malloc.
VisionData target;
int size = recv.Recv(rawData, 65507);
- aos::time::Time now = aos::time::Time::Now();
+ ::aos::time::Time now = ::aos::time::Time::Now();
if (target.ParseFromArray(rawData, size)) {
if (target.camera_index() == 0) {
- left_target = target;
- left_rx_time = now;
- got_left = true;
+ left.Received(target, now);
} else {
- right_target = target;
- right_rx_time = now;
- got_right = true;
+ right.Received(target, now);
}
} else {
LOG(ERROR, "oh noes: parse error\n");
continue;
}
- if (now > left_rx_time + aos::time::Time::InMS(50)) {
- got_left = false;
- }
- if (now > right_rx_time + aos::time::Time::InMS(50)) {
- got_right = false;
- }
+ left.CheckStale(now);
+ right.CheckStale(now);
- if (got_left && got_right) {
- bool left_image_valid = left_target.target_size() > 0;
- bool right_image_valid = right_target.target_size() > 0;
+ if (left.received_both() && right.received_both()) {
+ const bool left_image_valid = left.is_valid();
+ const bool right_image_valid = right.is_valid();
auto new_vision_status = vision_status.MakeMessage();
new_vision_status->left_image_valid = left_image_valid;
new_vision_status->right_image_valid = right_image_valid;
if (left_image_valid && right_image_valid) {
- ::aos::vision::Vector<2> center0(0.0, 0.0);
- ::aos::vision::Vector<2> center1(0.0, 0.0);
- SelectTargets(left_target, right_target, ¢er0, ¢er1);
+ ::aos::vision::Vector<2> center_left(0.0, 0.0);
+ ::aos::vision::Vector<2> center_right(0.0, 0.0);
+ double angle_left;
+ double angle_right;
+ SelectTargets(left.target(), right.target(), ¢er_left,
+ ¢er_right, &angle_left, &angle_right);
+
+ // TODO(Ben): Remember this from last time instead of recalculating it
+ // each time.
+ ::aos::vision::Vector<2> last_center_left(0.0, 0.0);
+ ::aos::vision::Vector<2> last_center_right(0.0, 0.0);
+ double last_angle_left;
+ double last_angle_right;
+ SelectTargets(left.last_target(), right.last_target(),
+ &last_center_left, &last_center_right,
+ &last_angle_left, &last_angle_right);
+
+ ::aos::vision::Vector<2> filtered_center_left(0.0, 0.0);
+ ::aos::vision::Vector<2> filtered_center_right(0.0, 0.0);
+ double filtered_angle_left;
+ double filtered_angle_right;
+ if (left.capture_time() < right.capture_time()) {
+ filtered_center_left = center_left;
+ filtered_angle_left = angle_left;
+ new_vision_status->target_time = left.capture_time().ToNSec();
+ CalculateFiltered(left, right, center_right, last_center_right,
+ angle_right, last_angle_right,
+ &filtered_center_right, &filtered_angle_right);
+ } else {
+ filtered_center_right = center_right;
+ filtered_angle_right = angle_right;
+ new_vision_status->target_time = right.capture_time().ToNSec();
+ CalculateFiltered(right, left, center_left, last_center_left,
+ angle_left, last_angle_left, &filtered_center_left,
+ &filtered_angle_left);
+ }
+
double distance, horizontal_angle, vertical_angle;
- stereo.Process(center0, center1, &distance, &horizontal_angle,
- &vertical_angle);
- new_vision_status->left_image_timestamp = left_target.image_timestamp();
- new_vision_status->right_image_timestamp = right_target.image_timestamp();
- new_vision_status->left_send_timestamp = left_target.send_timestamp();
- new_vision_status->right_send_timestamp = right_target.send_timestamp();
+ stereo.Process(filtered_center_left, filtered_center_right, &distance,
+ &horizontal_angle, &vertical_angle);
+ new_vision_status->left_image_timestamp =
+ left.target().image_timestamp();
+ new_vision_status->right_image_timestamp =
+ right.target().image_timestamp();
+ new_vision_status->left_send_timestamp = left.target().send_timestamp();
+ new_vision_status->right_send_timestamp = right.target().send_timestamp();
new_vision_status->horizontal_angle = horizontal_angle;
new_vision_status->vertical_angle = vertical_angle;
new_vision_status->distance = distance;
+ new_vision_status->angle =
+ (filtered_angle_left + filtered_angle_right) / 2.0;
}
- LOG_STRUCT(DEBUG, "vision", *new_vision_status);
- if (!new_vision_status.Send()) {
- LOG(ERROR, "Failed to send vision information\n");
+ if (drivetrain_offset.CompleteVisionStatus(new_vision_status.get())) {
+ LOG_STRUCT(DEBUG, "vision", *new_vision_status);
+ if (!new_vision_status.Send()) {
+ LOG(ERROR, "Failed to send vision information\n");
+ }
+ } else {
+ LOG_STRUCT(WARNING, "vision without drivetrain", *new_vision_status);
}
}
if (target.camera_index() == 0) {
- LOG(DEBUG, "left_target: %s\n", left_target.ShortDebugString().c_str());
+ LOG(DEBUG, "left_target: %s\n", left.target().ShortDebugString().c_str());
} else {
- LOG(DEBUG, "right_target: %s\n", right_target.ShortDebugString().c_str());
+ LOG(DEBUG, "right_target: %s\n",
+ right.target().ShortDebugString().c_str());
}
}
+
+ drivetrain_offset.Quit();
+ drivetrain_offset_thread.join();
}
} // namespace vision
diff --git a/y2016/vision/vision.q b/y2016/vision/vision.q
index 2d95c3c..872c9ae 100644
--- a/y2016/vision/vision.q
+++ b/y2016/vision/vision.q
@@ -20,5 +20,17 @@
double vertical_angle;
// Distance to the target in meters.
double distance;
+ // The angle in radians of the bottom of the target.
+ double angle;
+
+ // Capture time of the angle using the clock behind Time::Now().
+ int64_t target_time;
+
+ // The estimated positions of both sides of the drivetrain when the frame
+ // was captured.
+ // These are the estimated_left_position and estimated_right_position members
+ // of the drivetrain queue.
+ double drivetrain_left_position;
+ double drivetrain_right_position;
};
queue VisionStatus vision_status;
diff --git a/y2016/wpilib/wpilib_interface.cc b/y2016/wpilib/wpilib_interface.cc
index 8273bf9..acf820f 100644
--- a/y2016/wpilib/wpilib_interface.cc
+++ b/y2016/wpilib/wpilib_interface.cc
@@ -428,14 +428,14 @@
compressor_ = ::std::move(compressor);
}
- void set_drivetrain_left(
+ void set_drivetrain_shifter(
::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
- drivetrain_left_ = ::std::move(s);
+ drivetrain_shifter_ = ::std::move(s);
}
- void set_drivetrain_right(
+ void set_climber_trigger(
::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> s) {
- drivetrain_right_ = ::std::move(s);
+ climber_trigger_ = ::std::move(s);
}
void set_traverse(
@@ -487,8 +487,8 @@
drivetrain_.FetchLatest();
if (drivetrain_.get()) {
LOG_STRUCT(DEBUG, "solenoids", *drivetrain_);
- drivetrain_left_->Set(!drivetrain_->left_high);
- drivetrain_right_->Set(!drivetrain_->right_high);
+ drivetrain_shifter_->Set(
+ !(drivetrain_->left_high || drivetrain_->right_high));
}
}
@@ -499,14 +499,29 @@
shooter_clamp_->Set(shooter_->clamp_open);
shooter_pusher_->Set(shooter_->push_to_shooter);
lights_->Set(shooter_->lights_on);
- flashlight_->Set(shooter_->lights_on ? Relay::kForward : Relay::kOff);
+ if (shooter_->forwards_flashlight) {
+ if (shooter_->backwards_flashlight) {
+ flashlight_->Set(Relay::kOn);
+ } else {
+ flashlight_->Set(Relay::kReverse);
+ }
+ } else {
+ if (shooter_->backwards_flashlight) {
+ flashlight_->Set(Relay::kForward);
+ } else {
+ flashlight_->Set(Relay::kOff);
+ }
+ }
}
}
{
superstructure_.FetchLatest();
if (superstructure_.get()) {
- LOG_STRUCT(DEBUG, "solenoids", *shooter_);
+ LOG_STRUCT(DEBUG, "solenoids", *superstructure_);
+
+ climber_trigger_->Set(superstructure_->unfold_climber);
+
traverse_->Set(superstructure_->traverse_down);
traverse_latch_->Set(superstructure_->traverse_unlatched);
}
@@ -530,9 +545,9 @@
private:
const ::std::unique_ptr<::frc971::wpilib::BufferedPcm> &pcm_;
- ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> drivetrain_left_,
- drivetrain_right_, shooter_clamp_, shooter_pusher_, lights_, traverse_,
- traverse_latch_;
+ ::std::unique_ptr<::frc971::wpilib::BufferedSolenoid> drivetrain_shifter_,
+ shooter_clamp_, shooter_pusher_, lights_, traverse_, traverse_latch_,
+ climber_trigger_;
::std::unique_ptr<Relay> flashlight_;
::std::unique_ptr<Compressor> compressor_;
@@ -630,6 +645,10 @@
bottom_rollers_talon_ = ::std::move(t);
}
+ void set_climber_talon(::std::unique_ptr<Talon> t) {
+ climber_talon_ = ::std::move(t);
+ }
+
private:
virtual void Read() override {
::y2016::control_loops::superstructure_queue.output.FetchAnother();
@@ -649,6 +668,7 @@
12.0);
top_rollers_talon_->Set(-queue->voltage_top_rollers / 12.0);
bottom_rollers_talon_->Set(-queue->voltage_bottom_rollers / 12.0);
+ climber_talon_->Set(-queue->voltage_climber / 12.0);
}
virtual void Stop() override {
@@ -659,7 +679,7 @@
}
::std::unique_ptr<Talon> intake_talon_, shoulder_talon_, wrist_talon_,
- top_rollers_talon_, bottom_rollers_talon_;
+ top_rollers_talon_, bottom_rollers_talon_, climber_talon_;
};
class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
@@ -685,14 +705,14 @@
reader.set_drivetrain_left_hall(make_unique<AnalogInput>(5));
reader.set_drivetrain_right_hall(make_unique<AnalogInput>(6));
- reader.set_shooter_left_encoder(make_encoder(3));
- reader.set_shooter_right_encoder(make_encoder(4));
+ reader.set_shooter_left_encoder(make_encoder(7));
+ reader.set_shooter_right_encoder(make_encoder(-3));
reader.set_intake_encoder(make_encoder(0));
reader.set_intake_index(make_unique<DigitalInput>(0));
reader.set_intake_potentiometer(make_unique<AnalogInput>(0));
- reader.set_shoulder_encoder(make_encoder(2));
+ reader.set_shoulder_encoder(make_encoder(4));
reader.set_shoulder_index(make_unique<DigitalInput>(2));
reader.set_shoulder_potentiometer(make_unique<AnalogInput>(2));
@@ -713,11 +733,9 @@
::frc971::wpilib::GyroSender gyro_sender;
::std::thread gyro_thread(::std::ref(gyro_sender));
-#if 0
- auto imu_trigger = make_unique<DigitalInput>(100);
- ::frc971::wpilib::ADIS16448 imu(SPI::Port::kOnboardCS1, imu_trigger.get());
+ auto imu_trigger = make_unique<DigitalInput>(3);
+ ::frc971::wpilib::ADIS16448 imu(SPI::Port::kMXP, imu_trigger.get());
::std::thread imu_thread(::std::ref(imu));
-#endif
DrivetrainWriter drivetrain_writer;
drivetrain_writer.set_drivetrain_left_talon(
@@ -744,19 +762,21 @@
::std::unique_ptr<Talon>(new Talon(1)));
superstructure_writer.set_bottom_rollers_talon(
::std::unique_ptr<Talon>(new Talon(0)));
+ superstructure_writer.set_climber_talon(
+ ::std::unique_ptr<Talon>(new Talon(7)));
::std::thread superstructure_writer_thread(
::std::ref(superstructure_writer));
::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
new ::frc971::wpilib::BufferedPcm());
SolenoidWriter solenoid_writer(pcm);
- solenoid_writer.set_drivetrain_left(pcm->MakeSolenoid(1));
- solenoid_writer.set_drivetrain_right(pcm->MakeSolenoid(0));
+ solenoid_writer.set_drivetrain_shifter(pcm->MakeSolenoid(0));
solenoid_writer.set_traverse_latch(pcm->MakeSolenoid(2));
solenoid_writer.set_traverse(pcm->MakeSolenoid(3));
solenoid_writer.set_shooter_clamp(pcm->MakeSolenoid(4));
solenoid_writer.set_shooter_pusher(pcm->MakeSolenoid(5));
solenoid_writer.set_lights(pcm->MakeSolenoid(6));
+ solenoid_writer.set_climber_trigger(pcm->MakeSolenoid(1));
solenoid_writer.set_flashlight(make_unique<Relay>(0));
solenoid_writer.set_compressor(make_unique<Compressor>());
@@ -783,10 +803,8 @@
reader_thread.join();
gyro_sender.Quit();
gyro_thread.join();
-#if 0
imu.Quit();
imu_thread.join();
-#endif
drivetrain_writer.Quit();
drivetrain_writer_thread.join();