Move 2015-specific code to its own folder.
Known issues:
-I didn't change the namespace for it, but I am open to discussion
on doing that in a separate change.
-There are a couple of files which should get split out into
year-specific and not-year-specific files to reduce how much needs
to get copied around each year still.
-The control loop python code doesn't yet generate code with the
right #include etc paths.
Change-Id: Iabf078e75107c283247f58a5ffceb4dbd6a0815f
diff --git a/frc971/actors/actors.gyp b/frc971/actors/actors.gyp
deleted file mode 100644
index d1ede7a..0000000
--- a/frc971/actors/actors.gyp
+++ /dev/null
@@ -1,630 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'binaries',
- 'type': 'none',
- 'dependencies': [
- 'drivetrain_action',
- 'score_action',
- 'score_action_test',
- 'pickup_action',
- 'stack_action',
- 'stack_and_lift_action',
- 'stack_and_hold_action',
- 'held_to_lift_action',
- 'can_pickup_action',
- 'horizontal_can_pickup_action',
- 'lift_action',
- 'stack_action_test',
- ],
- },
- {
- 'target_name': 'drivetrain_action_queue',
- 'type': 'static_library',
- 'sources': ['drivetrain_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'drivetrain_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'drivetrain_actor.cc',
- ],
- 'dependencies': [
- 'drivetrain_action_queue',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(AOS)/common/logging/logging.gyp:queue_logging',
- '<(EXTERNALS):eigen',
- '<(AOS)/common/util/util.gyp:trapezoid_profile',
- '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'drivetrain_action_queue',
- ],
- },
- {
- 'target_name': 'drivetrain_action',
- 'type': 'executable',
- 'sources': [
- 'drivetrain_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'drivetrain_action_queue',
- 'drivetrain_action_lib',
- ],
- },
- {
- 'target_name' : 'fridge_profile_lib',
- 'type' : 'static_library',
- 'sources' : [
- 'fridge_profile_lib.cc',
- ],
- 'dependencies' : [
- '<(AOS)/build/aos.gyp:logging_interface',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- ],
- 'export_dependent_settings' : [
- '<(AOS)/build/aos.gyp:logging_interface',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- ],
- },
- {
- 'target_name': 'score_action_queue',
- 'type': 'static_library',
- 'sources': ['score_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'score_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'score_actor.cc',
- ],
- 'dependencies': [
- 'score_action_queue',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(EXTERNALS):eigen',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'score_action_queue',
- '<(EXTERNALS):eigen',
- ],
- },
- {
- 'target_name': 'score_action',
- 'type': 'executable',
- 'sources': [
- 'score_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'score_action_queue',
- 'score_action_lib',
- ],
- },
- {
- 'target_name': 'score_action_test',
- 'type': 'executable',
- 'sources': [
- 'score_actor_test.cc',
- ],
- 'dependencies': [
- '<(EXTERNALS):gtest',
- '<(AOS)/common/common.gyp:queue_testutils',
- '<(AOS)/common/logging/logging.gyp:queue_logging',
- '<(AOS)/common/common.gyp:queues',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
- 'score_action_queue',
- 'score_action_lib',
- ],
- },
- {
- 'target_name': 'pickup_action_queue',
- 'type': 'static_library',
- 'sources': ['pickup_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'pickup_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'pickup_actor.cc',
- ],
- 'dependencies': [
- 'pickup_action_queue',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'pickup_action_queue',
- ],
- },
- {
- 'target_name': 'pickup_action',
- 'type': 'executable',
- 'sources': [
- 'pickup_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'pickup_action_queue',
- 'pickup_action_lib',
- ],
- },
- {
- 'target_name': 'can_pickup_action_queue',
- 'type': 'static_library',
- 'sources': ['can_pickup_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'can_pickup_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'can_pickup_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'can_pickup_action_queue',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- ],
- 'export_dependent_settings': [
- 'fridge_profile_lib',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'can_pickup_action_queue',
- ],
- },
- {
- 'target_name': 'can_pickup_action',
- 'type': 'executable',
- 'sources': [
- 'can_pickup_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'can_pickup_action_queue',
- 'can_pickup_action_lib',
- ],
- },
- {
- 'target_name': 'horizontal_can_pickup_action_queue',
- 'type': 'static_library',
- 'sources': ['horizontal_can_pickup_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'horizontal_can_pickup_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'horizontal_can_pickup_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'horizontal_can_pickup_action_queue',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- ],
- 'export_dependent_settings': [
- 'fridge_profile_lib',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'horizontal_can_pickup_action_queue',
- ],
- },
- {
- 'target_name': 'horizontal_can_pickup_action',
- 'type': 'executable',
- 'sources': [
- 'horizontal_can_pickup_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'horizontal_can_pickup_action_queue',
- 'horizontal_can_pickup_action_lib',
- ],
- },
- {
- 'target_name': 'held_to_lift_action_queue',
- 'type': 'static_library',
- 'sources': ['held_to_lift_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'lift_action_params',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'lift_action_params',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'held_to_lift_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'held_to_lift_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'held_to_lift_action_queue',
- 'lift_action_lib',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'held_to_lift_action_queue',
- 'fridge_profile_lib',
- ],
- },
- {
- 'target_name': 'held_to_lift_action',
- 'type': 'executable',
- 'sources': [
- 'held_to_lift_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'held_to_lift_action_queue',
- 'held_to_lift_action_lib',
- ],
- },
- {
- 'target_name': 'stack_and_hold_action_queue',
- 'type': 'static_library',
- 'sources': ['stack_and_hold_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'stack_action_params',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'stack_action_params',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'stack_and_hold_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'stack_and_hold_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'stack_and_hold_action_queue',
- 'stack_action_lib',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'stack_and_hold_action_queue',
- 'fridge_profile_lib',
- ],
- },
- {
- 'target_name': 'stack_and_hold_action',
- 'type': 'executable',
- 'sources': [
- 'stack_and_hold_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'stack_and_hold_action_queue',
- 'stack_and_hold_action_lib',
- ],
- },
- {
- 'target_name': 'stack_and_lift_action_queue',
- 'type': 'static_library',
- 'sources': ['stack_and_lift_action.q'],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'stack_action_params',
- 'lift_action_params',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'stack_action_params',
- 'lift_action_params',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'stack_and_lift_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'stack_and_lift_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'stack_and_lift_action_queue',
- 'stack_action_lib',
- 'lift_action_lib',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'stack_and_lift_action_queue',
- 'fridge_profile_lib',
- ],
- },
- {
- 'target_name': 'stack_and_lift_action',
- 'type': 'executable',
- 'sources': [
- 'stack_and_lift_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'stack_and_lift_action_queue',
- 'stack_and_lift_action_lib',
- ],
- },
- {
- # This is a wrapper target to avoid adding the directory with a stale
- # stack_action_params.q.h to the compiler's include path.
- 'target_name': 'stack_action_queue',
- 'type': 'none',
- 'dependencies': ['stack_action_queue_real'],
- 'export_dependent_settings': ['stack_action_queue_real'],
- },
- {
- 'target_name': 'stack_action_queue_real',
- 'type': 'static_library',
- 'sources': [
- 'stack_action.q',
- ],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'stack_action_params',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'stack_action_params',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'stack_action_params',
- 'type': 'static_library',
- 'sources': [
- 'stack_action_params.q',
- ],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'stack_action_test',
- 'type': 'executable',
- 'sources': [
- 'stack_actor_test.cc',
- ],
- 'dependencies': [
- '<(EXTERNALS):gtest',
- '<(AOS)/common/common.gyp:queue_testutils',
- '<(AOS)/common/logging/logging.gyp:queue_logging',
- '<(AOS)/common/common.gyp:queues',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
- 'stack_action_queue',
- 'stack_action_lib',
- ],
- },
- {
- 'target_name': 'stack_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'stack_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'stack_action_queue',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- ],
- 'export_dependent_settings': [
- 'fridge_profile_lib',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'stack_action_queue',
- ],
- },
- {
- 'target_name': 'stack_action',
- 'type': 'executable',
- 'sources': [
- 'stack_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'stack_action_queue',
- 'stack_action_lib',
- ],
- },
- {
- # This is a wrapper target to avoid adding the directory with a stale
- # lift_action_params.q.h to the compiler's include path.
- 'target_name': 'lift_action_queue',
- 'type': 'none',
- 'dependencies': ['lift_action_queue_real'],
- 'export_dependent_settings': ['lift_action_queue_real'],
- },
- {
- 'target_name': 'lift_action_queue_real',
- 'type': 'static_library',
- 'sources': [
- 'lift_action.q',
- ],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'dependencies': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'lift_action_params',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/actions/actions.gyp:action_queue',
- 'lift_action_params',
- ],
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'lift_action_params',
- 'type': 'static_library',
- 'sources': [
- 'lift_action_params.q',
- ],
- 'variables': {
- 'header_path': 'frc971/actors',
- },
- 'includes': ['../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'lift_action_lib',
- 'type': 'static_library',
- 'sources': [
- 'lift_actor.cc',
- ],
- 'dependencies': [
- 'fridge_profile_lib',
- 'lift_action_queue',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- ],
- 'export_dependent_settings': [
- 'fridge_profile_lib',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'lift_action_queue',
- ],
- },
- {
- 'target_name': 'lift_action',
- 'type': 'executable',
- 'sources': [
- 'lift_actor_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/actions/actions.gyp:action_lib',
- 'lift_action_queue',
- 'lift_action_lib',
- ],
- },
- ],
-}
diff --git a/frc971/actors/can_pickup_action.q b/frc971/actors/can_pickup_action.q
deleted file mode 100644
index 4846722..0000000
--- a/frc971/actors/can_pickup_action.q
+++ /dev/null
@@ -1,40 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-
-// Parameters to send with start.
-// This action picks a right side up can from the claw.
-// It starts by lifting up, then moving the arm out, then lifting the can out of
-// the claw, and then ends with the can inside the bot.
-struct CanPickupParams {
- // X position for the fridge when picking up.
- double pickup_x;
- // Y position for the fridge when picking up.
- double pickup_y;
- // Height to move the elevator to to lift the can out of the claw.
- double lift_height;
- // Height to use when lifting before moving it back.
- double pickup_goal_before_move_height;
- // The height at which to start pulling back.
- double before_place_height;
-
- // X at which to start lowering the can.
- double start_lowering_x;
- // End position with the can.
- double end_height;
- double end_angle;
-};
-
-queue_group CanPickupActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- CanPickupParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group CanPickupActionQueueGroup can_pickup_action;
diff --git a/frc971/actors/can_pickup_actor.cc b/frc971/actors/can_pickup_actor.cc
deleted file mode 100644
index f1ae568..0000000
--- a/frc971/actors/can_pickup_actor.cc
+++ /dev/null
@@ -1,122 +0,0 @@
-#include <math.h>
-
-#include "aos/common/time.h"
-#include "aos/common/util/phased_loop.h"
-
-#include "frc971/actors/can_pickup_actor.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-using ::frc971::control_loops::fridge_queue;
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr ProfileParams kHorizontalMove{1.1, 1.8};
-constexpr ProfileParams kVerticalMove{0.3, 2.0};
-constexpr ProfileParams kFastHorizontalMove{1.25, 5.0};
-constexpr ProfileParams kFastVerticalMove{0.40, 2.0};
-constexpr ProfileParams kPureVerticalMove{1.20, 5.0};
-} // namespace
-
-CanPickupActor::CanPickupActor(CanPickupActionQueueGroup *queues)
- : FridgeActorBase<CanPickupActionQueueGroup>(queues) {}
-
-double CanPickupActor::CurrentGoalX() {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return 0.0;
- }
-
- return fridge_queue.status->goal_x;
-}
-
-double CanPickupActor::CurrentGoalHeight() {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return 0.0;
- }
-
- return fridge_queue.status->goal_y;
-}
-
-bool CanPickupActor::RunAction(const CanPickupParams ¶ms) {
- // Make sure the claw is down.
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = 0.0;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
- message->max_velocity = 6.0;
- message->max_acceleration = 10.0;
-
- LOG_STRUCT(DEBUG, "Sending claw down goal", *message);
- message.Send();
- }
-
- // Go around the can.
- DoFridgeXYProfile(params.pickup_x, params.pickup_y, kFastHorizontalMove,
- kFastVerticalMove, true, false, false);
- if (ShouldCancel()) return true;
-
- if (!StartFridgeXYProfile(
- params.pickup_x, params.pickup_goal_before_move_height,
- kHorizontalMove, kPureVerticalMove, true, true, true)) {
- return false;
- }
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = 0.0;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = false;
- message->max_velocity = 6.0;
- message->max_acceleration = 10.0;
-
- LOG_STRUCT(DEBUG, "Sending claw down goal", *message);
- message.Send();
- }
-
- bool above_claw = false;
- while (true) {
- if (CurrentGoalHeight() > params.lift_height && !above_claw) {
- if (!StartFridgeXYProfile(0.0, params.before_place_height,
- kHorizontalMove, kVerticalMove, true, true,
- true)) {
- return false;
- }
- above_claw = true;
- }
- if (CurrentGoalX() < params.start_lowering_x) {
- // Getting close, start lowering.
- LOG(DEBUG, "Starting to lower the can onto the tray.\n");
- break;
- }
- ProfileStatus status =
- IterateXYProfile(0.0, params.before_place_height, kHorizontalMove,
- kVerticalMove, true, true, true);
- if (status == DONE || status == CANCELED) {
- break;
- }
- }
- if (ShouldCancel()) return true;
-
- // Lower it.
- DoFridgeXYProfile(0.0, params.end_height, kHorizontalMove, kPureVerticalMove,
- true);
- if (ShouldCancel()) return true;
-
- return true;
-}
-
-::std::unique_ptr<CanPickupAction> MakeCanPickupAction(
- const CanPickupParams ¶ms) {
- return ::std::unique_ptr<CanPickupAction>(
- new CanPickupAction(&::frc971::actors::can_pickup_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/can_pickup_actor.h b/frc971/actors/can_pickup_actor.h
deleted file mode 100644
index 3e109d1..0000000
--- a/frc971/actors/can_pickup_actor.h
+++ /dev/null
@@ -1,37 +0,0 @@
-#ifndef FRC971_ACTORS_CAN_PICKUP_ACTOR_H_
-#define FRC971_ACTORS_CAN_PICKUP_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/can_pickup_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class CanPickupActor : public FridgeActorBase<CanPickupActionQueueGroup> {
- public:
- explicit CanPickupActor(CanPickupActionQueueGroup *queues);
-
- bool RunAction(const CanPickupParams ¶ms) override;
-
- private:
- double CurrentGoalHeight();
- double CurrentGoalX();
-};
-
-typedef aos::common::actions::TypedAction<CanPickupActionQueueGroup>
- CanPickupAction;
-
-// Makes a new CanPickupActor action.
-::std::unique_ptr<CanPickupAction> MakeCanPickupAction(
- const CanPickupParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif
diff --git a/frc971/actors/can_pickup_actor_main.cc b/frc971/actors/can_pickup_actor_main.cc
deleted file mode 100644
index e784d94..0000000
--- a/frc971/actors/can_pickup_actor_main.cc
+++ /dev/null
@@ -1,15 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/can_pickup_action.q.h"
-#include "frc971/actors/can_pickup_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::CanPickupActor can_pickup(&::frc971::actors::can_pickup_action);
- can_pickup.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/drivetrain_action.q b/frc971/actors/drivetrain_action.q
deleted file mode 100644
index 9ad55d3..0000000
--- a/frc971/actors/drivetrain_action.q
+++ /dev/null
@@ -1,29 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-
-// Parameters to send with start.
-struct DrivetrainActionParams {
- double left_initial_position;
- double right_initial_position;
- double y_offset;
- double theta_offset;
- double maximum_velocity;
- double maximum_acceleration;
- double maximum_turn_velocity;
- double maximum_turn_acceleration;
-};
-
-queue_group DrivetrainActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- DrivetrainActionParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group DrivetrainActionQueueGroup drivetrain_action;
diff --git a/frc971/actors/drivetrain_actor.cc b/frc971/actors/drivetrain_actor.cc
deleted file mode 100644
index 9b72cb1..0000000
--- a/frc971/actors/drivetrain_actor.cc
+++ /dev/null
@@ -1,168 +0,0 @@
-#include "frc971/actors/drivetrain_actor.h"
-
-#include <functional>
-#include <numeric>
-
-#include <Eigen/Dense>
-
-#include "aos/common/util/phased_loop.h"
-#include "aos/common/logging/logging.h"
-#include "aos/common/util/trapezoid_profile.h"
-#include "aos/common/commonmath.h"
-#include "aos/common/time.h"
-
-#include "frc971/actors/drivetrain_actor.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-
-namespace frc971 {
-namespace actors {
-
-DrivetrainActor::DrivetrainActor(actors::DrivetrainActionQueueGroup* s)
- : aos::common::actions::ActorBase<actors::DrivetrainActionQueueGroup>(s) {}
-
-bool DrivetrainActor::RunAction(const actors::DrivetrainActionParams ¶ms) {
- static const auto K = constants::GetValues().make_drivetrain_loop().K();
-
- const double yoffset = params.y_offset;
- const double turn_offset =
- params.theta_offset * constants::GetValues().turn_width / 2.0;
- LOG(INFO, "Going to move %f and turn %f\n", yoffset, turn_offset);
-
- // Measured conversion to get the distance right.
- ::aos::util::TrapezoidProfile profile(::aos::time::Time::InMS(5));
- ::aos::util::TrapezoidProfile turn_profile(::aos::time::Time::InMS(5));
- const double goal_velocity = 0.0;
- const double epsilon = 0.01;
- ::Eigen::Matrix<double, 2, 1> left_goal_state, right_goal_state;
-
- profile.set_maximum_acceleration(params.maximum_acceleration);
- profile.set_maximum_velocity(params.maximum_velocity);
- turn_profile.set_maximum_acceleration(params.maximum_turn_acceleration *
- constants::GetValues().turn_width /
- 2.0);
- turn_profile.set_maximum_velocity(params.maximum_turn_velocity *
- constants::GetValues().turn_width / 2.0);
-
- while (true) {
- ::aos::time::PhasedLoopXMS(5, 2500);
-
- control_loops::drivetrain_queue.status.FetchLatest();
- if (control_loops::drivetrain_queue.status.get()) {
- const auto& status = *control_loops::drivetrain_queue.status;
- if (::std::abs(status.uncapped_left_voltage -
- status.uncapped_right_voltage) > 24) {
- LOG(DEBUG, "spinning in place\n");
- // They're more than 24V apart, so stop moving forwards and let it deal
- // with spinning first.
- profile.SetGoal(
- (status.filtered_left_position + status.filtered_right_position -
- params.left_initial_position - params.right_initial_position) /
- 2.0);
- } else {
- static const double divisor = K(0, 0) + K(0, 2);
- double dx_left, dx_right;
- if (status.uncapped_left_voltage > 12.0) {
- dx_left = (status.uncapped_left_voltage - 12.0) / divisor;
- } else if (status.uncapped_left_voltage < -12.0) {
- dx_left = (status.uncapped_left_voltage + 12.0) / divisor;
- } else {
- dx_left = 0;
- }
- if (status.uncapped_right_voltage > 12.0) {
- dx_right = (status.uncapped_right_voltage - 12.0) / divisor;
- } else if (status.uncapped_right_voltage < -12.0) {
- dx_right = (status.uncapped_right_voltage + 12.0) / divisor;
- } else {
- dx_right = 0;
- }
- double dx;
- if (dx_left == 0 && dx_right == 0) {
- dx = 0;
- } else if (dx_left != 0 && dx_right != 0 &&
- ::aos::sign(dx_left) != ::aos::sign(dx_right)) {
- // Both saturating in opposite directions. Don't do anything.
- LOG(DEBUG, "Saturating opposite ways, not adjusting\n");
- dx = 0;
- } else if (::std::abs(dx_left) > ::std::abs(dx_right)) {
- dx = dx_left;
- } else {
- dx = dx_right;
- }
- if (dx != 0) {
- LOG(DEBUG, "adjusting goal by %f\n", dx);
- profile.MoveGoal(-dx);
- }
- }
- } else {
- // If we ever get here, that's bad and we should just give up
- LOG(ERROR, "no drivetrain status!\n");
- return false;
- }
-
- const auto drive_profile_goal_state =
- profile.Update(yoffset, goal_velocity);
- const auto turn_profile_goal_state = turn_profile.Update(turn_offset, 0.0);
- left_goal_state = drive_profile_goal_state - turn_profile_goal_state;
- right_goal_state = drive_profile_goal_state + turn_profile_goal_state;
-
- if (::std::abs(drive_profile_goal_state(0, 0) - yoffset) < epsilon &&
- ::std::abs(turn_profile_goal_state(0, 0) - turn_offset) < epsilon) {
- break;
- }
-
- if (ShouldCancel()) return true;
-
- LOG(DEBUG, "Driving left to %f, right to %f\n",
- left_goal_state(0, 0) + params.left_initial_position,
- right_goal_state(0, 0) + params.right_initial_position);
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
- .control_loop_driving(true)
- //.highgear(false)
- .left_goal(left_goal_state(0, 0) + params.left_initial_position)
- .right_goal(right_goal_state(0, 0) + params.right_initial_position)
- .left_velocity_goal(left_goal_state(1, 0))
- .right_velocity_goal(right_goal_state(1, 0))
- .Send();
- }
- if (ShouldCancel()) return true;
- control_loops::drivetrain_queue.status.FetchLatest();
- while (!control_loops::drivetrain_queue.status.get()) {
- LOG(WARNING,
- "No previous drivetrain status packet, trying to fetch again\n");
- control_loops::drivetrain_queue.status.FetchNextBlocking();
- if (ShouldCancel()) return true;
- }
- while (true) {
- if (ShouldCancel()) return true;
- const double kPositionThreshold = 0.05;
-
- const double left_error = ::std::abs(
- control_loops::drivetrain_queue.status->filtered_left_position -
- (left_goal_state(0, 0) + params.left_initial_position));
- const double right_error = ::std::abs(
- control_loops::drivetrain_queue.status->filtered_right_position -
- (right_goal_state(0, 0) + params.right_initial_position));
- const double velocity_error =
- ::std::abs(control_loops::drivetrain_queue.status->robot_speed);
- if (left_error < kPositionThreshold && right_error < kPositionThreshold &&
- velocity_error < 0.2) {
- break;
- } else {
- LOG(DEBUG, "Drivetrain error is %f, %f, %f\n", left_error, right_error,
- velocity_error);
- }
- control_loops::drivetrain_queue.status.FetchNextBlocking();
- }
- LOG(INFO, "Done moving\n");
- return true;
-}
-
-::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
- const ::frc971::actors::DrivetrainActionParams& params) {
- return ::std::unique_ptr<DrivetrainAction>(
- new DrivetrainAction(&::frc971::actors::drivetrain_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/drivetrain_actor.h b/frc971/actors/drivetrain_actor.h
deleted file mode 100644
index c035002..0000000
--- a/frc971/actors/drivetrain_actor.h
+++ /dev/null
@@ -1,31 +0,0 @@
-#ifndef FRC971_ACTIONS_DRIVETRAIN_ACTION_H_
-#define FRC971_ACTIONS_DRIVETRAIN_ACTION_H_
-
-#include <memory>
-
-#include "frc971/actors/drivetrain_action.q.h"
-#include "aos/common/actions/actor.h"
-#include "aos/common/actions/actions.h"
-
-namespace frc971 {
-namespace actors {
-
-class DrivetrainActor
- : public aos::common::actions::ActorBase<DrivetrainActionQueueGroup> {
- public:
- explicit DrivetrainActor(DrivetrainActionQueueGroup* s);
-
- bool RunAction(const actors::DrivetrainActionParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<DrivetrainActionQueueGroup>
- DrivetrainAction;
-
-// Makes a new DrivetrainActor action.
-::std::unique_ptr<DrivetrainAction> MakeDrivetrainAction(
- const ::frc971::actors::DrivetrainActionParams& params);
-
-} // namespace actors
-} // namespace frc971
-
-#endif
diff --git a/frc971/actors/drivetrain_actor_main.cc b/frc971/actors/drivetrain_actor_main.cc
deleted file mode 100644
index 5337745..0000000
--- a/frc971/actors/drivetrain_actor_main.cc
+++ /dev/null
@@ -1,18 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/drivetrain_action.q.h"
-#include "frc971/actors/drivetrain_actor.h"
-
-using ::aos::time::Time;
-
-int main(int /*argc*/, char * /*argv*/[]) {
- ::aos::Init();
-
- frc971::actors::DrivetrainActor drivetrain(
- &::frc971::actors::drivetrain_action);
- drivetrain.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/fridge_profile_lib.cc b/frc971/actors/fridge_profile_lib.cc
deleted file mode 100644
index c6ad8e3..0000000
--- a/frc971/actors/fridge_profile_lib.cc
+++ /dev/null
@@ -1 +0,0 @@
-#include "frc971/actors/fridge_profile_lib.h"
diff --git a/frc971/actors/fridge_profile_lib.h b/frc971/actors/fridge_profile_lib.h
deleted file mode 100644
index 2e0dcc2..0000000
--- a/frc971/actors/fridge_profile_lib.h
+++ /dev/null
@@ -1,285 +0,0 @@
-#ifndef FRC971_ACTORS_FRIDGE_PROFILE_LIB_H_
-#define FRC971_ACTORS_FRIDGE_PROFILE_LIB_H_
-
-#include <cmath>
-
-#include "aos/common/actions/actor.h"
-#include "aos/common/util/phased_loop.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-
-namespace frc971 {
-namespace actors {
-
-struct ProfileParams {
- double velocity;
- double acceleration;
-};
-
-// Base class to provide helper utilities to all Actors who want to control the
-// fridge.
-template <typename T>
-class FridgeActorBase : public aos::common::actions::ActorBase<T> {
- public:
- FridgeActorBase(T *queues) : aos::common::actions::ActorBase<T>(queues) {}
-
- protected:
- void DoFridgeProfile(double height, double angle,
- ProfileParams elevator_parameters,
- ProfileParams arm_parameters, bool grabbers) {
- DoFridgeProfile(height, angle, elevator_parameters, arm_parameters,
- grabbers, grabbers, grabbers);
- }
-
- bool StartFridgeProfile(double height, double angle,
- ProfileParams elevator_parameters,
- ProfileParams arm_parameters, bool top_grabbers,
- bool front_grabbers, bool back_grabbers) {
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- new_fridge_goal->profiling_type = 0;
- new_fridge_goal->max_velocity = elevator_parameters.velocity;
- new_fridge_goal->max_acceleration = elevator_parameters.acceleration;
- new_fridge_goal->height = height;
- new_fridge_goal->velocity = 0.0;
- new_fridge_goal->max_angular_velocity = arm_parameters.velocity;
- new_fridge_goal->max_angular_acceleration = arm_parameters.acceleration;
- new_fridge_goal->angle = angle;
- new_fridge_goal->angular_velocity = 0.0;
- new_fridge_goal->grabbers.top_front = top_grabbers;
- new_fridge_goal->grabbers.top_back = top_grabbers;
- new_fridge_goal->grabbers.bottom_front = front_grabbers;
- new_fridge_goal->grabbers.bottom_back = back_grabbers;
- LOG(INFO, "Starting profile to %f, %f\n", height, angle);
-
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Failed to send fridge goal\n");
- return false;
- }
- return true;
- }
-
- enum ProfileStatus { RUNNING, DONE, CANCELED };
-
- ProfileStatus IterateProfile(double height, double angle,
- ProfileParams elevator_parameters,
- ProfileParams arm_parameters, bool top_grabbers,
- bool front_grabbers, bool back_grabbers) {
- if (this->ShouldCancel()) {
- LOG(INFO, "Canceling fridge movement\n");
- if (!control_loops::fridge_queue.status.get()) {
- LOG(WARNING, "no fridge status so can't really cancel\n");
- return CANCELED;
- }
-
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- new_fridge_goal->profiling_type = 0;
- new_fridge_goal->max_velocity = elevator_parameters.velocity;
- new_fridge_goal->max_acceleration = elevator_parameters.acceleration;
- new_fridge_goal->height =
- control_loops::fridge_queue.status->height +
- (control_loops::fridge_queue.status->goal_velocity *
- ::std::abs(control_loops::fridge_queue.status->goal_velocity)) /
- (2.0 * new_fridge_goal->max_acceleration);
- height = new_fridge_goal->height;
- new_fridge_goal->velocity = 0.0;
- new_fridge_goal->max_angular_velocity = arm_parameters.velocity;
- new_fridge_goal->max_angular_acceleration = arm_parameters.acceleration;
- new_fridge_goal->angle =
- control_loops::fridge_queue.status->angle +
- (control_loops::fridge_queue.status->goal_angular_velocity *
- ::std::abs(
- control_loops::fridge_queue.status->goal_angular_velocity)) /
- (2.0 * new_fridge_goal->max_angular_acceleration);
- angle = new_fridge_goal->angle;
- new_fridge_goal->angular_velocity = 0.0;
- new_fridge_goal->grabbers.top_front = top_grabbers;
- new_fridge_goal->grabbers.top_back = top_grabbers;
- new_fridge_goal->grabbers.bottom_front = front_grabbers;
- new_fridge_goal->grabbers.bottom_back = back_grabbers;
-
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Failed to send fridge goal\n");
- }
- return CANCELED;
- }
- control_loops::fridge_queue.status.FetchAnother();
-
- constexpr double kProfileError = 1e-5;
- constexpr double kAngleEpsilon = 0.02, kHeightEpsilon = 0.015;
-
- if (control_loops::fridge_queue.status->state != 4) {
- LOG(ERROR, "Fridge no longer running, aborting action\n");
- return CANCELED;
- }
-
- if (::std::abs(control_loops::fridge_queue.status->goal_angle - angle) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_height - height) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_angular_velocity) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_velocity) <
- kProfileError) {
- LOG(INFO, "Profile done.\n");
- if (::std::abs(control_loops::fridge_queue.status->angle - angle) <
- kAngleEpsilon &&
- ::std::abs(control_loops::fridge_queue.status->height -
- height) < kHeightEpsilon) {
- LOG(INFO, "Near goal, done.\n");
- return DONE;
- }
- }
-
- return RUNNING;
- }
-
- void DoFridgeProfile(double height, double angle,
- ProfileParams elevator_parameters,
- ProfileParams arm_parameters, bool top_grabbers,
- bool front_grabbers, bool back_grabbers) {
- if (!StartFridgeProfile(height, angle, elevator_parameters, arm_parameters,
- top_grabbers, front_grabbers, back_grabbers)) {
- return;
- }
-
- while (true) {
- ProfileStatus status =
- IterateProfile(height, angle, elevator_parameters, arm_parameters,
- top_grabbers, front_grabbers, back_grabbers);
- if (status == DONE || status == CANCELED) {
- return;
- }
- }
- }
-
- void DoFridgeXYProfile(double x, double y, ProfileParams x_parameters,
- ProfileParams y_parameters, bool grabbers) {
- DoFridgeXYProfile(x, y, x_parameters, y_parameters, grabbers, grabbers,
- grabbers);
- }
-
- void DoFridgeXYProfile(double x, double y, ProfileParams x_parameters,
- ProfileParams y_parameters, bool top_grabbers,
- bool front_grabbers, bool back_grabbers) {
- if (!StartFridgeXYProfile(x, y, x_parameters, y_parameters, top_grabbers,
- front_grabbers, back_grabbers)) {
- return;
- }
-
- while (true) {
- ProfileStatus status =
- IterateXYProfile(x, y, x_parameters, y_parameters, top_grabbers,
- front_grabbers, back_grabbers);
- if (status == DONE || status == CANCELED) {
- return;
- }
- }
- }
-
- void CancelXYMotion(ProfileParams x_parameters, ProfileParams y_parameters,
- bool top_grabbers, bool front_grabbers,
- bool back_grabbers) {
- LOG(INFO, "Canceling fridge movement\n");
- if (!control_loops::fridge_queue.status.get()) {
- LOG(WARNING, "no fridge status so can't really cancel\n");
- return;
- }
-
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- new_fridge_goal->profiling_type = 1;
- new_fridge_goal->max_x_velocity = x_parameters.velocity;
- new_fridge_goal->max_x_acceleration = x_parameters.acceleration;
- new_fridge_goal->x =
- control_loops::fridge_queue.status->x +
- (control_loops::fridge_queue.status->goal_x_velocity *
- ::std::abs(control_loops::fridge_queue.status->goal_x_velocity)) /
- (2.0 * new_fridge_goal->max_x_acceleration);
- new_fridge_goal->x_velocity = 0.0;
-
- new_fridge_goal->max_y_velocity = y_parameters.velocity;
- new_fridge_goal->max_y_acceleration = y_parameters.acceleration;
- new_fridge_goal->y =
- control_loops::fridge_queue.status->y +
- (control_loops::fridge_queue.status->goal_y_velocity *
- ::std::abs(control_loops::fridge_queue.status->goal_y_velocity)) /
- (2.0 * new_fridge_goal->max_y_acceleration);
- new_fridge_goal->y_velocity = 0.0;
-
- new_fridge_goal->grabbers.top_front = top_grabbers;
- new_fridge_goal->grabbers.top_back = top_grabbers;
- new_fridge_goal->grabbers.bottom_front = front_grabbers;
- new_fridge_goal->grabbers.bottom_back = back_grabbers;
-
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Failed to send fridge goal\n");
- }
- }
-
- ProfileStatus IterateXYProfile(double x, double y, ProfileParams x_parameters,
- ProfileParams y_parameters, bool top_grabbers,
- bool front_grabbers, bool back_grabbers) {
- if (this->ShouldCancel()) {
- CancelXYMotion(x_parameters, y_parameters, top_grabbers, front_grabbers,
- back_grabbers);
- return CANCELED;
- }
- control_loops::fridge_queue.status.FetchAnother();
-
- constexpr double kProfileError = 1e-5;
- constexpr double kXEpsilon = 0.02, kYEpsilon = 0.02;
-
- if (control_loops::fridge_queue.status->state != 4) {
- LOG(ERROR, "Fridge no longer running, aborting action\n");
- return CANCELED;
- }
-
- if (::std::abs(control_loops::fridge_queue.status->goal_x - x) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_y - y) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_x_velocity) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_y_velocity) <
- kProfileError) {
- LOG(INFO, "Profile done.\n");
- if (::std::abs(control_loops::fridge_queue.status->x - x) < kXEpsilon &&
- ::std::abs(control_loops::fridge_queue.status->y - y) < kYEpsilon) {
- LOG(INFO, "Near goal, done.\n");
- return DONE;
- }
- }
-
- return RUNNING;
- }
-
- bool StartFridgeXYProfile(double x, double y, ProfileParams x_parameters,
- ProfileParams y_parameters, bool top_grabbers,
- bool front_grabbers, bool back_grabbers) {
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- new_fridge_goal->profiling_type = 1;
- new_fridge_goal->max_x_velocity = x_parameters.velocity;
- new_fridge_goal->max_x_acceleration = x_parameters.acceleration;
- new_fridge_goal->x = x;
- new_fridge_goal->x_velocity = 0.0;
-
- new_fridge_goal->max_y_velocity = y_parameters.velocity;
- new_fridge_goal->max_y_acceleration = y_parameters.acceleration;
- new_fridge_goal->y = y;
- new_fridge_goal->y_velocity = 0.0;
- new_fridge_goal->grabbers.top_front = top_grabbers;
- new_fridge_goal->grabbers.top_back = top_grabbers;
- new_fridge_goal->grabbers.bottom_front = front_grabbers;
- new_fridge_goal->grabbers.bottom_back = back_grabbers;
- LOG(INFO, "Starting xy profile to %f, %f\n", x, y);
-
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Failed to send fridge goal\n");
- return false;
- }
- return true;
- }
-};
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_FRIDGE_PROFILE_LIB_H_
diff --git a/frc971/actors/held_to_lift_action.q b/frc971/actors/held_to_lift_action.q
deleted file mode 100644
index 3825ac8..0000000
--- a/frc971/actors/held_to_lift_action.q
+++ /dev/null
@@ -1,36 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-import "frc971/actors/lift_action_params.q";
-
-// Parameters to send with start.
-struct HeldToLiftParams {
- // The maximum claw value to avoid collisions.
- double claw_out_angle;
-
- // The value to move the arm forwards to clear the stack when lowering.
- double arm_clearance;
- // End height.
- double bottom_height;
- // Amount to wait for the elevator to settle before lifting.
- double before_lift_settle_time;
- // Amount to wait to clamp.
- double clamp_pause_time;
-
- // Lift parameters
- LiftParams lift_params;
-};
-
-queue_group HeldToLiftActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- HeldToLiftParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group HeldToLiftActionQueueGroup held_to_lift_action;
diff --git a/frc971/actors/held_to_lift_actor.cc b/frc971/actors/held_to_lift_actor.cc
deleted file mode 100644
index 2bd4a88..0000000
--- a/frc971/actors/held_to_lift_actor.cc
+++ /dev/null
@@ -1,114 +0,0 @@
-#include "frc971/actors/held_to_lift_actor.h"
-
-#include <math.h>
-
-#include "aos/common/time.h"
-#include "frc971/constants.h"
-#include "frc971/actors/fridge_profile_lib.h"
-#include "frc971/actors/lift_actor.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr ProfileParams kArmMove{0.6, 2.0};
-constexpr ProfileParams kFastArmMove{1.2, 4.0};
-constexpr ProfileParams kElevatorMove{0.9, 3.0};
-constexpr ProfileParams kFastElevatorMove{1.2, 5.0};
-} // namespace
-
-HeldToLiftActor::HeldToLiftActor(HeldToLiftActionQueueGroup *queues)
- : FridgeActorBase<HeldToLiftActionQueueGroup>(queues) {}
-
-bool HeldToLiftActor::RunAction(const HeldToLiftParams ¶ms) {
- control_loops::fridge_queue.status.FetchLatest();
- if (!control_loops::fridge_queue.status.get()) {
- return false;
- }
-
- // Move claw out of the way.
- {
- bool send_goal = true;
- double claw_goal = params.claw_out_angle;
- control_loops::claw_queue.status.FetchLatest();
- if (control_loops::claw_queue.status.get()) {
- if (control_loops::claw_queue.status->goal_angle < claw_goal) {
- send_goal = false;
- }
- }
- if (send_goal) {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.claw_out_angle;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->max_velocity = 6.0;
- message->max_acceleration = 10.0;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
- }
-
- control_loops::fridge_queue.status.FetchLatest();
- if (!control_loops::fridge_queue.status.get()) {
- return false;
- }
-
- if (control_loops::fridge_queue.status->goal_height != params.bottom_height ||
- control_loops::fridge_queue.status->goal_angle != 0.0) {
- // Lower with the fridge clamps open and move it forwards slightly to clear.
- DoFridgeProfile(control_loops::fridge_queue.status->goal_height,
- params.arm_clearance, kFastElevatorMove, kFastArmMove,
- false);
- if (ShouldCancel()) return true;
-
- DoFridgeProfile(params.bottom_height, params.arm_clearance,
- kFastElevatorMove, kFastArmMove, false);
- if (ShouldCancel()) return true;
-
- // Move it back to the storage location.
- DoFridgeProfile(params.bottom_height, 0.0, kElevatorMove, kArmMove, false);
- if (ShouldCancel()) return true;
-
- if (!WaitOrCancel(
- aos::time::Time::InSeconds(params.before_lift_settle_time))) {
- return true;
- }
-
- // Clamp
- DoFridgeProfile(params.bottom_height, 0.0, kElevatorMove, kArmMove, true);
- if (ShouldCancel()) return true;
-
- if (!WaitOrCancel(aos::time::Time::InSeconds(params.clamp_pause_time))) {
- return true;
- }
- }
-
- {
- ::std::unique_ptr<LiftAction> lift_action =
- MakeLiftAction(params.lift_params);
- lift_action->Start();
- while (lift_action->Running()) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(),
- 2500);
-
- if (ShouldCancel()) {
- lift_action->Cancel();
- LOG(WARNING, "Cancelling fridge and claw.\n");
- return true;
- }
- }
- }
-
- return true;
-}
-
-::std::unique_ptr<HeldToLiftAction> MakeHeldToLiftAction(
- const HeldToLiftParams ¶ms) {
- return ::std::unique_ptr<HeldToLiftAction>(
- new HeldToLiftAction(&::frc971::actors::held_to_lift_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/held_to_lift_actor.h b/frc971/actors/held_to_lift_actor.h
deleted file mode 100644
index 4b3c22a..0000000
--- a/frc971/actors/held_to_lift_actor.h
+++ /dev/null
@@ -1,33 +0,0 @@
-#ifndef FRC971_ACTORS_HELD_TO_LIFT_ACTOR_H_
-#define FRC971_ACTORS_HELD_TO_LIFT_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/held_to_lift_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class HeldToLiftActor : public FridgeActorBase<HeldToLiftActionQueueGroup> {
- public:
- explicit HeldToLiftActor(HeldToLiftActionQueueGroup *queues);
-
- bool RunAction(const HeldToLiftParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<HeldToLiftActionQueueGroup>
- HeldToLiftAction;
-
-// Makes a new HeldToLiftActor action.
-::std::unique_ptr<HeldToLiftAction> MakeHeldToLiftAction(
- const HeldToLiftParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_HELD_TO_LIFT_ACTOR_H_
diff --git a/frc971/actors/held_to_lift_actor_main.cc b/frc971/actors/held_to_lift_actor_main.cc
deleted file mode 100644
index ad3e20c..0000000
--- a/frc971/actors/held_to_lift_actor_main.cc
+++ /dev/null
@@ -1,16 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/held_to_lift_action.q.h"
-#include "frc971/actors/held_to_lift_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::HeldToLiftActor lift(
- &::frc971::actors::held_to_lift_action);
- lift.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/horizontal_can_pickup_action.q b/frc971/actors/horizontal_can_pickup_action.q
deleted file mode 100644
index c1a1c55..0000000
--- a/frc971/actors/horizontal_can_pickup_action.q
+++ /dev/null
@@ -1,48 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-
-// Parameters to send with start.
-// This action picks a horizontal can from the claw.
-struct HorizontalCanPickupParams {
- // Elevator catch height.
- double elevator_height;
- // Angle to move the claw to when placing the base of the can on the robot.
- double pickup_angle;
-
- // Time and power to spit the can out before lifting.
- double spit_time;
- double spit_power;
-
- // Time and power to pull the can in when lifted.
- double suck_time;
- double suck_power;
-
- // Time to push down and suck in to slide the claw down on the can.
- double claw_settle_time;
- double claw_settle_power;
-
- // Angle to lift the claw to to lift the can.
- double claw_full_lift_angle;
-
- // Angle to move the claw back down to.
- double claw_end_angle;
-
- // The end arm and elevator position once we are done lifting.
- double elevator_end_height;
- double arm_end_angle;
-};
-
-queue_group HorizontalCanPickupActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- HorizontalCanPickupParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group HorizontalCanPickupActionQueueGroup horizontal_can_pickup_action;
diff --git a/frc971/actors/horizontal_can_pickup_actor.cc b/frc971/actors/horizontal_can_pickup_actor.cc
deleted file mode 100644
index ab2c8cf..0000000
--- a/frc971/actors/horizontal_can_pickup_actor.cc
+++ /dev/null
@@ -1,161 +0,0 @@
-#include <math.h>
-
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/time.h"
-#include "aos/common/util/phased_loop.h"
-
-#include "frc971/actors/horizontal_can_pickup_actor.h"
-#include "frc971/actors/fridge_profile_lib.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr ProfileParams kClawPickup{3.0, 2.0};
-constexpr ProfileParams kClawBackDown{7.0, 10.0};
-constexpr ProfileParams kClawInitialLift{7.0, 8.0};
-
-constexpr ProfileParams kArmMove{1.0, 1.6};
-constexpr ProfileParams kElevatorMove{0.6, 2.2};
-
-constexpr ProfileParams kFastArmMove{2.0, 3.0};
-constexpr ProfileParams kFastElevatorMove{1.0, 3.0};
-
-constexpr double kAngleEpsilon = 0.10;
-constexpr double kGoalAngleEpsilon = 0.01;
-
-} // namespace
-
-HorizontalCanPickupActor::HorizontalCanPickupActor(
- HorizontalCanPickupActionQueueGroup *queues)
- : FridgeActorBase<HorizontalCanPickupActionQueueGroup>(queues) {}
-
-bool HorizontalCanPickupActor::WaitUntilGoalNear(double angle) {
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- if (ShouldCancel()) return false;
- const double goal_angle = control_loops::claw_queue.status->goal_angle;
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
-
- if (::std::abs(goal_angle - angle) < kGoalAngleEpsilon) {
- return true;
- }
- }
-}
-
-bool HorizontalCanPickupActor::WaitUntilNear(double angle) {
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- if (ShouldCancel()) return false;
- const double current_angle = control_loops::claw_queue.status->angle;
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
-
- if (::std::abs(current_angle - angle) < kAngleEpsilon) {
- return true;
- }
- }
-}
-void HorizontalCanPickupActor::MoveArm(double angle, double intake_power) {
- MoveArm(angle, intake_power, kClawPickup);
-}
-
-void HorizontalCanPickupActor::MoveArm(double angle, double intake_power,
- const ProfileParams profile_params) {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = angle;
- message->max_velocity = profile_params.velocity;
- message->max_acceleration = profile_params.acceleration;
- message->angular_velocity = 0.0;
- message->intake = intake_power;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
-}
-
-bool HorizontalCanPickupActor::RunAction(
- const HorizontalCanPickupParams ¶ms) {
- // Go around the can.
- if (!StartFridgeProfile(params.elevator_height, 0.0, kFastElevatorMove,
- kFastArmMove, false, false, true)) {
- return true;
- }
-
- control_loops::claw_queue.status.FetchAnother();
-
- MoveArm(control_loops::claw_queue.status->angle, params.spit_power);
-
- if (!WaitOrCancel(aos::time::Time::InSeconds(params.spit_time))) {
- return true;
- }
-
- MoveArm(params.pickup_angle, 0.0, kClawInitialLift);
-
- if (!WaitUntilNear(params.pickup_angle)) {
- return true;
- }
-
- MoveArm(params.pickup_angle, params.suck_power);
-
- if (!WaitOrCancel(aos::time::Time::InSeconds(params.suck_time))) {
- return true;
- }
-
- MoveArm(0.0, 0.0, kClawBackDown);
-
- if (!WaitUntilGoalNear(0.0)) {
- return true;
- }
-
- MoveArm(0.0, params.claw_settle_power);
-
- if (!WaitOrCancel(aos::time::Time::InSeconds(params.claw_settle_time))) {
- return true;
- }
-
- while (true) {
- ProfileStatus status =
- IterateProfile(params.elevator_height, 0.0, kFastElevatorMove,
- kFastArmMove, false, false, true);
- if (status == DONE) {
- break;
- } else if (status == CANCELED) {
- return true;
- }
- }
-
- MoveArm(params.claw_full_lift_angle, 0.0);
-
- if (!WaitUntilNear(params.claw_full_lift_angle)) {
- return true;
- }
-
- DoFridgeProfile(params.elevator_height, 0.0, kElevatorMove, kArmMove, false,
- true, true);
- if (ShouldCancel()) return true;
-
- MoveArm(params.claw_end_angle, 7.0);
-
- if (!WaitUntilNear(params.claw_end_angle)) {
- return true;
- }
- MoveArm(params.claw_end_angle, 0.0);
-
- if (ShouldCancel()) return true;
-
- DoFridgeProfile(params.elevator_end_height, params.arm_end_angle,
- kElevatorMove, kArmMove, false, true, true);
-
- return true;
-}
-
-::std::unique_ptr<HorizontalCanPickupAction> MakeHorizontalCanPickupAction(
- const HorizontalCanPickupParams ¶ms) {
- return ::std::unique_ptr<HorizontalCanPickupAction>(
- new HorizontalCanPickupAction(
- &::frc971::actors::horizontal_can_pickup_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/horizontal_can_pickup_actor.h b/frc971/actors/horizontal_can_pickup_actor.h
deleted file mode 100644
index f3bb0f0..0000000
--- a/frc971/actors/horizontal_can_pickup_actor.h
+++ /dev/null
@@ -1,45 +0,0 @@
-#ifndef FRC971_ACTORS_HORIZONTAL_CAN_PICKUP_ACTOR_H_
-#define FRC971_ACTORS_HORIZONTAL_CAN_PICKUP_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/horizontal_can_pickup_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class HorizontalCanPickupActor
- : public FridgeActorBase<HorizontalCanPickupActionQueueGroup> {
- public:
- explicit HorizontalCanPickupActor(
- HorizontalCanPickupActionQueueGroup *queues);
-
- bool RunAction(const HorizontalCanPickupParams ¶ms) override;
-
- private:
- // Waits until we are near the angle.
- // Returns false if we should cancel.
- bool WaitUntilNear(double angle);
- bool WaitUntilGoalNear(double angle);
-
- void MoveArm(double angle, double intake_power);
- void MoveArm(double angle, double intake_power,
- const ProfileParams profile_params);
-};
-
-typedef aos::common::actions::TypedAction<HorizontalCanPickupActionQueueGroup>
- HorizontalCanPickupAction;
-
-// Makes a new HorizontalCanPickupActor action.
-::std::unique_ptr<HorizontalCanPickupAction> MakeHorizontalCanPickupAction(
- const HorizontalCanPickupParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_HORIZONTAL_CAN_PICKUP_ACTOR_H_
diff --git a/frc971/actors/horizontal_can_pickup_actor_main.cc b/frc971/actors/horizontal_can_pickup_actor_main.cc
deleted file mode 100644
index c8e1d3c..0000000
--- a/frc971/actors/horizontal_can_pickup_actor_main.cc
+++ /dev/null
@@ -1,16 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/horizontal_can_pickup_action.q.h"
-#include "frc971/actors/horizontal_can_pickup_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::HorizontalCanPickupActor horizontal_can_pickup(
- &::frc971::actors::horizontal_can_pickup_action);
- horizontal_can_pickup.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/lift_action.q b/frc971/actors/lift_action.q
deleted file mode 100644
index bb5615a..0000000
--- a/frc971/actors/lift_action.q
+++ /dev/null
@@ -1,18 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-import "frc971/actors/lift_action_params.q";
-
-queue_group LiftActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- LiftParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group LiftActionQueueGroup lift_action;
diff --git a/frc971/actors/lift_action_params.q b/frc971/actors/lift_action_params.q
deleted file mode 100644
index b31982b..0000000
--- a/frc971/actors/lift_action_params.q
+++ /dev/null
@@ -1,19 +0,0 @@
-package frc971.actors;
-
-// Parameters to send with start.
-struct LiftParams {
- // Lift height
- double lift_height;
- // Arm goal.
- double lift_arm;
-
- // If true, do the second lift.
- bool second_lift;
- // Arm goal.
- double intermediate_lift_height;
-
- // True to move the claw in the middle of the lift.
- bool pack_claw;
- // Iff pack_claw is true, the angle to move the claw to.
- double pack_claw_angle;
-};
diff --git a/frc971/actors/lift_actor.cc b/frc971/actors/lift_actor.cc
deleted file mode 100644
index ff36bef..0000000
--- a/frc971/actors/lift_actor.cc
+++ /dev/null
@@ -1,92 +0,0 @@
-#include <math.h>
-
-#include "aos/common/time.h"
-#include "frc971/actors/lift_actor.h"
-#include "frc971/constants.h"
-#include "frc971/actors/fridge_profile_lib.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr ProfileParams kArmMove{0.6, 1.0};
-constexpr ProfileParams kElevatorMove{0.9, 3.0};
-constexpr ProfileParams kElevatorFixMove{0.9, 2.0};
-} // namespace
-
-LiftActor::LiftActor(LiftActionQueueGroup *queues)
- : FridgeActorBase<LiftActionQueueGroup>(queues) {}
-
-bool LiftActor::RunAction(const LiftParams ¶ms) {
- control_loops::fridge_queue.status.FetchLatest();
- if (!control_loops::fridge_queue.status.get()) {
- return false;
- }
-
- double goal_height = params.lift_height;
- double goal_angle = 0.0;
-
- if (params.second_lift) {
- DoFridgeProfile(params.intermediate_lift_height, 0.0, kElevatorFixMove,
- kArmMove,
- control_loops::fridge_queue.status->grabbers.top_front,
- control_loops::fridge_queue.status->grabbers.bottom_front,
- control_loops::fridge_queue.status->grabbers.bottom_back);
- if (ShouldCancel()) return true;
- }
-
- if (!StartFridgeProfile(
- params.lift_height, 0.0, kElevatorMove, kArmMove,
- control_loops::fridge_queue.status->grabbers.top_front,
- control_loops::fridge_queue.status->grabbers.bottom_front,
- control_loops::fridge_queue.status->grabbers.bottom_back)) {
- return true;
- }
-
- bool has_started_back = false;
- while (true) {
- if (control_loops::fridge_queue.status->goal_height > 0.1) {
- if (!has_started_back) {
- if (!StartFridgeProfile(
- params.lift_height, params.lift_arm, kElevatorMove, kArmMove,
- control_loops::fridge_queue.status->grabbers.top_front,
- control_loops::fridge_queue.status->grabbers.bottom_front,
- control_loops::fridge_queue.status->grabbers.bottom_back)) {
- return true;
- }
- goal_angle = params.lift_arm;
- has_started_back = true;
- if (params.pack_claw) {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.pack_claw_angle;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
- message->max_velocity = 6.0;
- message->max_acceleration = 10.0;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
- }
- }
-
- ProfileStatus status = IterateProfile(
- goal_height, goal_angle, kElevatorMove, kArmMove,
- control_loops::fridge_queue.status->grabbers.top_front,
- control_loops::fridge_queue.status->grabbers.bottom_front,
- control_loops::fridge_queue.status->grabbers.bottom_back);
- if (status == DONE || status == CANCELED) {
- return true;
- }
- }
- return true;
-}
-
-::std::unique_ptr<LiftAction> MakeLiftAction(const LiftParams ¶ms) {
- return ::std::unique_ptr<LiftAction>(
- new LiftAction(&::frc971::actors::lift_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/lift_actor.h b/frc971/actors/lift_actor.h
deleted file mode 100644
index 86af35c..0000000
--- a/frc971/actors/lift_actor.h
+++ /dev/null
@@ -1,31 +0,0 @@
-#ifndef FRC971_ACTORS_LIFT_ACTOR_H_
-#define FRC971_ACTORS_LIFT_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/lift_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class LiftActor : public FridgeActorBase<LiftActionQueueGroup> {
- public:
- explicit LiftActor(LiftActionQueueGroup *queues);
-
- bool RunAction(const LiftParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<LiftActionQueueGroup> LiftAction;
-
-// Makes a new LiftActor action.
-::std::unique_ptr<LiftAction> MakeLiftAction(const LiftParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_LIFT_ACTOR_H_
diff --git a/frc971/actors/lift_actor_main.cc b/frc971/actors/lift_actor_main.cc
deleted file mode 100644
index 792f535..0000000
--- a/frc971/actors/lift_actor_main.cc
+++ /dev/null
@@ -1,15 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/lift_action.q.h"
-#include "frc971/actors/lift_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::LiftActor lift(&::frc971::actors::lift_action);
- lift.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/pickup_action.q b/frc971/actors/pickup_action.q
deleted file mode 100644
index 237337a..0000000
--- a/frc971/actors/pickup_action.q
+++ /dev/null
@@ -1,33 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-
-// Parameters to send with start.
-struct PickupParams {
- // Angle to pull in at the top.
- double pickup_angle;
- // Angle to start sucking in above.
- double suck_angle;
- // Angle to finish sucking at.
- double suck_angle_finish;
- // Angle to go to once we get to the top to finish pulling in.
- double pickup_finish_angle;
- // Power to pull the bin in at the top.
- double intake_voltage;
- // Time to pull the bin in for.
- double intake_time;
-};
-
-queue_group PickupActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- PickupParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group PickupActionQueueGroup pickup_action;
diff --git a/frc971/actors/pickup_actor.cc b/frc971/actors/pickup_actor.cc
deleted file mode 100644
index 8afdfab..0000000
--- a/frc971/actors/pickup_actor.cc
+++ /dev/null
@@ -1,149 +0,0 @@
-#include "frc971/actors/pickup_actor.h"
-
-#include <cmath>
-
-#include "aos/common/logging/logging.h"
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/util/phased_loop.h"
-#include "aos/common/time.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr double kClawPickupVelocity = 3.00;
-constexpr double kClawPickupAcceleration = 3.5;
-constexpr double kClawMoveDownVelocity = 7.00;
-constexpr double kClawMoveDownAcceleration = 15.0;
-constexpr double kClawMoveUpVelocity = 8.0;
-constexpr double kClawMoveUpAcceleration = 25.0;
-} // namespace
-
-PickupActor::PickupActor(PickupActionQueueGroup* queues)
- : aos::common::actions::ActorBase<PickupActionQueueGroup>(queues) {}
-
-bool PickupActor::RunAction(const PickupParams& params) {
- constexpr double kAngleEpsilon = 0.10;
- // Start lifting the tote.
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.pickup_angle;
- message->max_velocity = kClawPickupVelocity;
- message->max_acceleration = kClawPickupAcceleration;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- if (ShouldCancel()) return true;
- const double current_angle = control_loops::claw_queue.status->angle;
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
-
- if (current_angle > params.suck_angle ||
- ::std::abs(current_angle - params.pickup_angle) < kAngleEpsilon) {
- break;
- }
- }
-
- // Once above params.suck_angle, start sucking while lifting.
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.pickup_angle;
- message->max_velocity = kClawPickupVelocity;
- message->max_acceleration = kClawPickupAcceleration;
- message->angular_velocity = 0.0;
- message->intake = params.intake_voltage;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
-
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- if (ShouldCancel()) return true;
- const double current_angle = control_loops::claw_queue.status->angle;
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
-
- if (::std::abs(current_angle - params.pickup_angle) < kAngleEpsilon) {
- break;
- }
- }
-
- // Now that we have reached the upper height, come back down while intaking.
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.suck_angle_finish;
- message->max_velocity = kClawMoveDownVelocity;
- message->max_acceleration = kClawMoveDownAcceleration;
- message->angular_velocity = 0.0;
- message->intake = params.intake_voltage;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
-
- // Pull in for params.intake_time.
- ::aos::time::Time end_time =
- ::aos::time::Time::Now() + aos::time::Time::InSeconds(params.intake_time);
- while ( ::aos::time::Time::Now() <= end_time) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(), 2500);
- if (ShouldCancel()) return true;
- }
-
- // Lift the claw back up to pack the box back in.
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.pickup_finish_angle;
- message->max_velocity = kClawMoveUpVelocity;
- message->max_acceleration = kClawMoveUpAcceleration;
- message->angular_velocity = 0.0;
- message->intake = params.intake_voltage;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
-
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- if (ShouldCancel()) return true;
- const double current_angle = control_loops::claw_queue.status->angle;
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
-
- if (::std::abs(current_angle - params.pickup_finish_angle) <
- kAngleEpsilon) {
- break;
- }
- }
-
- // Stop the motors...
- {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.pickup_finish_angle;
- message->max_velocity = kClawMoveUpVelocity;
- message->max_acceleration = kClawMoveUpAcceleration;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
-
-
- return true;
-}
-
-::std::unique_ptr<PickupAction> MakePickupAction(const PickupParams& params) {
- return ::std::unique_ptr<PickupAction>(
- new PickupAction(&::frc971::actors::pickup_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/pickup_actor.h b/frc971/actors/pickup_actor.h
deleted file mode 100644
index 66988d1..0000000
--- a/frc971/actors/pickup_actor.h
+++ /dev/null
@@ -1,27 +0,0 @@
-#ifndef FRC971_ACTORS_PICKUP_ACTOR_H_
-#define FRC971_ACTORS_PICKUP_ACTOR_H_
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/pickup_action.q.h"
-
-namespace frc971 {
-namespace actors {
-
-class PickupActor
- : public aos::common::actions::ActorBase<PickupActionQueueGroup> {
- public:
- explicit PickupActor(PickupActionQueueGroup *queues);
-
- bool RunAction(const PickupParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<PickupActionQueueGroup> PickupAction;
-
-// Makes a new PickupActor action.
-::std::unique_ptr<PickupAction> MakePickupAction(const PickupParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_PICKUP_ACTOR_H_
diff --git a/frc971/actors/pickup_actor_main.cc b/frc971/actors/pickup_actor_main.cc
deleted file mode 100644
index d5bc169..0000000
--- a/frc971/actors/pickup_actor_main.cc
+++ /dev/null
@@ -1,15 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/pickup_action.q.h"
-#include "frc971/actors/pickup_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- frc971::actors::PickupActor pickup(&::frc971::actors::pickup_action);
- pickup.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/score_action.q b/frc971/actors/score_action.q
deleted file mode 100644
index 5b14210..0000000
--- a/frc971/actors/score_action.q
+++ /dev/null
@@ -1,34 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-
-// Parameters to send with start.
-struct ScoreParams {
- // If true, move the stack first.
- bool move_the_stack;
- // If true, place the stack (possibly after moving it).
- bool place_the_stack;
-
- // TODO(Brian): Comments (by somebody who knows what these all mean).
- double upper_move_height;
- double begin_horizontal_move_height;
- double horizontal_move_target;
- double horizontal_start_lowering;
- double place_height;
- double home_lift_horizontal_start_position;
- double home_return_height;
-};
-
-queue_group ScoreActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- ScoreParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group ScoreActionQueueGroup score_action;
diff --git a/frc971/actors/score_actor.cc b/frc971/actors/score_actor.cc
deleted file mode 100644
index d650bb6..0000000
--- a/frc971/actors/score_actor.cc
+++ /dev/null
@@ -1,295 +0,0 @@
-#include "frc971/actors/score_actor.h"
-
-#include <cmath>
-
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/logging/logging.h"
-#include "aos/common/util/phased_loop.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "aos/common/logging/queue_logging.h"
-
-using ::frc971::control_loops::fridge_queue;
-
-namespace frc971 {
-namespace actors {
-namespace {
-
-const double kSlowMaxXVelocity = 0.80;
-const double kSlowMaxYVelocity = 0.40;
-const double kFastMaxXVelocity = 0.80;
-const double kFastMaxYVelocity = 0.30;
-const double kReallyFastMaxXVelocity = 1.0;
-const double kReallyFastMaxYVelocity = 0.6;
-
-const double kMaxXAcceleration = 0.5;
-const double kMaxYAcceleration = 0.7;
-const double kLiftYAcceleration = 2.0;
-const double kLowerYAcceleration = 2.0;
-const double kFastMaxXAcceleration = 1.5;
-const double kFastMaxYAcceleration = 1.5;
-const double kSlowMaxXAcceleration = 0.3;
-const double kSlowMaxYAcceleration = 0.5;
-
-} // namespace
-
-ScoreActor::ScoreActor(ScoreActionQueueGroup* queues)
- : aos::common::actions::ActorBase<ScoreActionQueueGroup>(queues),
- kinematics_(constants::GetValues().fridge.arm_length,
- constants::GetValues().fridge.elevator.upper_limit,
- constants::GetValues().fridge.elevator.lower_limit,
- constants::GetValues().fridge.arm.upper_limit,
- constants::GetValues().fridge.arm.lower_limit) {}
-
-bool ScoreActor::RunAction(const ScoreParams& params) {
- if (params.move_the_stack) {
- LOG(INFO, "moving stack\n");
- if (!MoveStackIntoPosition(params)) return false;
- LOG(INFO, "done moving stack\n");
- if (ShouldCancel()) return true;
- }
- if (params.place_the_stack) {
- LOG(INFO, "placing stack\n");
- if (!PlaceTheStack(params)) return false;
- LOG(INFO, "done placing stack\n");
- if (ShouldCancel()) return true;
- }
- return true;
-}
-
-bool ScoreActor::MoveStackIntoPosition(const ScoreParams& params) {
- // Move the fridge up a little bit.
- if (!SendGoal(0.0, params.upper_move_height, true, kSlowMaxXVelocity,
- kSlowMaxYVelocity, kMaxXAcceleration, kLiftYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
-
- while (true) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(), 2500);
- if (ShouldCancel()) {
- return true;
- }
-
- // Move on when it is clear of the tote knobs.
- if (CurrentGoalHeight() > params.begin_horizontal_move_height) {
- LOG(INFO, "moving on to horizontal move\n");
- break;
- }
- }
-
- // Move the fridge out.
- if (!SendGoal(params.horizontal_move_target,
- params.begin_horizontal_move_height, true, kSlowMaxXVelocity,
- kFastMaxYVelocity, kSlowMaxXAcceleration,
- kSlowMaxYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
-
- bool started_lowering = false;
-
- while (true) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(), 2500);
- if (ShouldCancel()) {
- return true;
- }
- // Round the moving out corner and start setting down.
- if (params.place_the_stack && !started_lowering) {
- if (CurrentGoalX() < params.horizontal_start_lowering) {
- if (!SendGoal(params.horizontal_move_target, params.place_height, true,
- kSlowMaxXVelocity, kFastMaxYVelocity,
- kSlowMaxXAcceleration, kMaxYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
- started_lowering = true;
- }
- }
-
- if (NearHorizontalGoal(params.horizontal_move_target)) {
- LOG(INFO, "reached goal\n");
- break;
- }
- }
-
- if (ShouldCancel()) return true;
-
- return true;
-}
-
-bool ScoreActor::PlaceTheStack(const ScoreParams& params) {
- // Once the fridge is way out, put it on the ground.
- if (!SendGoal(params.horizontal_move_target, params.place_height, true,
- kFastMaxXVelocity, kFastMaxYVelocity, kMaxXAcceleration,
- kLowerYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
-
- while (true) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(), 2500);
- if (ShouldCancel()) {
- return true;
- }
-
- if (NearGoal(params.horizontal_move_target, params.place_height)) {
- break;
- }
- }
-
- // Release and give the grabers a chance to get out of the way.
- if (!SendGoal(params.horizontal_move_target, params.place_height, false,
- kFastMaxXVelocity, kFastMaxYVelocity, kMaxXAcceleration,
- kLowerYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
- if (!WaitOrCancel(::aos::time::Time::InSeconds(0.1))) return true;
-
- // Go back to the home position.
- if (!SendGoal(0.0, params.place_height, false, kReallyFastMaxXVelocity,
- kReallyFastMaxYVelocity, kFastMaxXAcceleration,
- kFastMaxYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
-
- bool has_lifted = false;
- while (true) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(), 2500);
- if (ShouldCancel()) {
- return true;
- }
-
- if (!has_lifted &&
- CurrentGoalX() > params.home_lift_horizontal_start_position) {
- if (!SendGoal(0.0, params.home_return_height, false,
- kReallyFastMaxXVelocity, kReallyFastMaxYVelocity,
- kFastMaxXAcceleration, kFastMaxYAcceleration)) {
- LOG(ERROR, "Sending fridge message failed.\n");
- return false;
- }
- has_lifted = true;
- }
-
- if (NearGoal(0.0, params.home_return_height)) {
- break;
- }
- }
-
- return true;
-}
-
-double ScoreActor::CurrentHeight() {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return false;
- }
-
- ::aos::util::ElevatorArmKinematics::KinematicResult results;
- kinematics_.ForwardKinematic(fridge_queue.status->height,
- fridge_queue.status->angle, 0.0, 0.0, &results);
-
- return results.fridge_h;
-}
-
-double ScoreActor::CurrentGoalHeight() {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return 0.0;
- }
-
- ::aos::util::ElevatorArmKinematics::KinematicResult results;
- kinematics_.ForwardKinematic(fridge_queue.status->goal_height,
- fridge_queue.status->goal_angle, 0.0, 0.0,
- &results);
-
- return results.fridge_h;
-}
-
-double ScoreActor::CurrentX() {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return false;
- }
-
- return fridge_queue.status->x;
-}
-
-double ScoreActor::CurrentGoalX() {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return 0.0;
- }
-
- return fridge_queue.status->goal_x;
-}
-
-bool ScoreActor::SendGoal(double x, double y, bool grabbers_enabled,
- double max_x_velocity, double max_y_velocity,
- double max_x_acceleration,
- double max_y_acceleration) {
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- new_fridge_goal->x = x;
- new_fridge_goal->y = y;
- new_fridge_goal->profiling_type = 1;
- new_fridge_goal->angular_velocity = 0.0;
- new_fridge_goal->velocity = 0.0;
- new_fridge_goal->grabbers.top_front = grabbers_enabled;
- new_fridge_goal->grabbers.top_back = grabbers_enabled;
- new_fridge_goal->grabbers.bottom_front = grabbers_enabled;
- new_fridge_goal->grabbers.bottom_back = grabbers_enabled;
- new_fridge_goal->max_x_velocity = max_x_velocity;
- new_fridge_goal->max_y_velocity = max_y_velocity;
- new_fridge_goal->max_x_acceleration = max_x_acceleration;
- new_fridge_goal->max_y_acceleration = max_y_acceleration;
- LOG_STRUCT(INFO, "sending fridge goal", *new_fridge_goal);
-
- return new_fridge_goal.Send();
-}
-
-bool ScoreActor::NearHorizontalGoal(double x) {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return false;
- }
-
- ::aos::util::ElevatorArmKinematics::KinematicResult results;
- ::aos::util::ElevatorArmKinematics::KinematicResult goal_results;
- kinematics_.ForwardKinematic(fridge_queue.status->height,
- fridge_queue.status->angle, 0.0, 0.0, &results);
- kinematics_.ForwardKinematic(fridge_queue.status->goal_height,
- fridge_queue.status->goal_angle, 0.0, 0.0,
- &goal_results);
-
- return (::std::abs(results.fridge_x - x) < 0.020 &&
- ::std::abs(goal_results.fridge_x - x) < 0.0001);
-}
-
-bool ScoreActor::NearGoal(double x, double y) {
- fridge_queue.status.FetchLatest();
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Reading from fridge status queue failed.\n");
- return false;
- }
-
- const auto &status = *fridge_queue.status;
- return (::std::abs(status.x - x) < 0.020 &&
- ::std::abs(status.y - y) < 0.020 &&
- ::std::abs(status.goal_x - x) < 0.0001 &&
- ::std::abs(status.goal_y - y) < 0.0001);
-}
-
-::std::unique_ptr<ScoreAction> MakeScoreAction(const ScoreParams& params) {
- return ::std::unique_ptr<ScoreAction>(
- new ScoreAction(&::frc971::actors::score_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/score_actor.h b/frc971/actors/score_actor.h
deleted file mode 100644
index a524d36..0000000
--- a/frc971/actors/score_actor.h
+++ /dev/null
@@ -1,43 +0,0 @@
-#ifndef FRC971_ACTORS_SCORE_ACTOR_H_
-#define FRC971_ACTORS_SCORE_ACTOR_H_
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "aos/common/util/kinematics.h"
-#include "frc971/actors/score_action.q.h"
-
-namespace frc971 {
-namespace actors {
-
-class ScoreActor
- : public ::aos::common::actions::ActorBase<ScoreActionQueueGroup> {
- public:
- explicit ScoreActor(ScoreActionQueueGroup *queues);
-
- bool RunAction(const ScoreParams ¶ms) override;
-
- private:
-
- ::aos::util::ElevatorArmKinematics kinematics_;
- bool NearGoal(double x, double y);
- bool NearHorizontalGoal(double x);
- bool PlaceTheStack(const ScoreParams ¶ms);
- bool MoveStackIntoPosition(const ScoreParams ¶ms);
- bool SendGoal(double x, double y, bool grabbers_enabled,
- double max_x_velocity, double max_y_velocity,
- double max_x_acceleration, double max_y_acceleration);
- double CurrentHeight();
- double CurrentGoalHeight();
- double CurrentX();
- double CurrentGoalX();
-};
-
-typedef aos::common::actions::TypedAction<ScoreActionQueueGroup> ScoreAction;
-
-// Makes a new ScoreActor action.
-::std::unique_ptr<ScoreAction> MakeScoreAction(const ScoreParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif
diff --git a/frc971/actors/score_actor_main.cc b/frc971/actors/score_actor_main.cc
deleted file mode 100644
index ce4548c..0000000
--- a/frc971/actors/score_actor_main.cc
+++ /dev/null
@@ -1,15 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/score_action.q.h"
-#include "frc971/actors/score_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- frc971::actors::ScoreActor score(&::frc971::actors::score_action);
- score.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/score_actor_test.cc b/frc971/actors/score_actor_test.cc
deleted file mode 100644
index 450939f..0000000
--- a/frc971/actors/score_actor_test.cc
+++ /dev/null
@@ -1,98 +0,0 @@
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/queue.h"
-#include "aos/common/queue_testutils.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/score_action.q.h"
-#include "frc971/actors/score_actor.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "frc971/control_loops/team_number_test_environment.h"
-
-using ::aos::time::Time;
-
-namespace frc971 {
-namespace actors {
-namespace testing {
-
-class ScoreActionTest : public ::testing::Test {
- protected:
- ScoreActionTest() {
- frc971::actors::score_action.goal.Clear();
- frc971::actors::score_action.status.Clear();
- control_loops::fridge_queue.status.Clear();
- control_loops::fridge_queue.goal.Clear();
- }
-
- virtual ~ScoreActionTest() {
- frc971::actors::score_action.goal.Clear();
- frc971::actors::score_action.status.Clear();
- control_loops::fridge_queue.status.Clear();
- control_loops::fridge_queue.goal.Clear();
- }
-
- // Bring up and down Core.
- ::aos::common::testing::GlobalCoreInstance my_core;
-};
-
-// Tests that cancel stops not only the score action, but also the underlying
-// profile action.
-TEST_F(ScoreActionTest, PlaceTheStackCancel) {
- ScoreActor score(&frc971::actors::score_action);
-
- frc971::actors::score_action.goal.MakeWithBuilder().run(true).Send();
-
- // Tell it the fridge is zeroed.
- ASSERT_TRUE(control_loops::fridge_queue.status.MakeWithBuilder()
- .zeroed(true)
- .angle(0.0)
- .height(0.0)
- .Send());
-
- // do the action and it will post to the goal queue
- score.WaitForActionRequest();
-
- // the action has started, so now cancel it and it should cancel
- // the underlying profile
- frc971::actors::score_action.goal.MakeWithBuilder().run(false).Send();
-
- // let the action start running, if we return from this call it has worked.
- const ScoreParams params = {true, true, 0.14, 0.13, -0.7, -0.7, -0.10, -0.5, 0.1};
- score.RunAction(params);
-
- SUCCEED();
-}
-
-// Tests that cancel stops not only the score action, but also the underlying
-// profile action.
-TEST_F(ScoreActionTest, MoveStackIntoPositionCancel) {
- ScoreActor score(&frc971::actors::score_action);
-
- frc971::actors::score_action.goal.MakeWithBuilder().run(true).Send();
-
- // Tell it the fridge is zeroed.
- ASSERT_TRUE(control_loops::fridge_queue.status.MakeWithBuilder()
- .zeroed(true)
- .angle(0.0)
- .height(0.0)
- .Send());
-
- // do the action and it will post to the goal queue
- score.WaitForActionRequest();
-
- // the action has started, so now cancel it and it should cancel
- // the underlying profile
- frc971::actors::score_action.goal.MakeWithBuilder().run(false).Send();
-
- // let the action start running, if we return from this call it has worked.
- const ScoreParams params = {false, true, 0.14, 0.13, -0.7, -0.7, -0.10, -0.5, 0.1};
- score.RunAction(params);
-
- SUCCEED();
-}
-
-} // namespace testing
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/stack_action.q b/frc971/actors/stack_action.q
deleted file mode 100644
index 122afc9..0000000
--- a/frc971/actors/stack_action.q
+++ /dev/null
@@ -1,18 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-import "frc971/actors/stack_action_params.q";
-
-queue_group StackActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- StackParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group StackActionQueueGroup stack_action;
diff --git a/frc971/actors/stack_action_params.q b/frc971/actors/stack_action_params.q
deleted file mode 100644
index 3958f7d..0000000
--- a/frc971/actors/stack_action_params.q
+++ /dev/null
@@ -1,17 +0,0 @@
-package frc971.actors;
-
-// Parameters to send with start.
-struct StackParams {
- // If true, don't grab the lower tote after lowering.
- bool only_place;
-
- // The angle to move the arm to while lowering it.
- double arm_clearance;
-
- double claw_out_angle;
- // The height just above the box to move before lowering.
- double over_box_before_place_height;
-
- // Bottom position.
- double bottom;
-};
diff --git a/frc971/actors/stack_actor.cc b/frc971/actors/stack_actor.cc
deleted file mode 100644
index c9622c2..0000000
--- a/frc971/actors/stack_actor.cc
+++ /dev/null
@@ -1,96 +0,0 @@
-#include "frc971/actors/stack_actor.h"
-
-#include <math.h>
-
-#include "aos/common/time.h"
-#include "aos/common/util/phased_loop.h"
-
-#include "frc971/constants.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr ProfileParams kArmWithStackMove{1.75, 4.20};
-constexpr ProfileParams kSlowArmMove{1.3, 1.4};
-constexpr ProfileParams kSlowElevatorMove{1.0, 3.0};
-
-constexpr ProfileParams kFastArmMove{0.8, 4.0};
-constexpr ProfileParams kFastElevatorMove{1.2, 5.0};
-constexpr ProfileParams kReallyFastElevatorMove{1.2, 6.0};
-} // namespace
-
-StackActor::StackActor(StackActionQueueGroup *queues)
- : FridgeActorBase<StackActionQueueGroup>(queues) {}
-
-bool StackActor::RunAction(const StackParams ¶ms) {
- const auto &values = constants::GetValues();
-
- control_loops::fridge_queue.status.FetchLatest();
- if (!control_loops::fridge_queue.status.get()) {
- LOG(ERROR, "Got no fridge status packet.\n");
- return false;
- }
-
- // If we are really high, probably have a can. Move over before down.
- if (control_loops::fridge_queue.status->goal_height >
- params.over_box_before_place_height + 0.1) {
- // Set the current stack down on top of the bottom box.
- DoFridgeProfile(control_loops::fridge_queue.status->goal_height, 0.0,
- kSlowElevatorMove, kArmWithStackMove, true);
- if (ShouldCancel()) return true;
- }
-
- // Set the current stack down on top of the bottom box.
- DoFridgeProfile(params.bottom + values.tote_height, 0.0, kSlowElevatorMove,
- kSlowArmMove, true);
- if (ShouldCancel()) return true;
-
- // Clamp.
- if (!params.only_place) {
- // Move the claw out of the way only if we are supposed to pick up.
- bool send_goal = true;
- control_loops::claw_queue.status.FetchLatest();
- if (control_loops::claw_queue.status.get()) {
- if (control_loops::claw_queue.status->goal_angle <
- params.claw_out_angle) {
- send_goal = false;
- }
- }
- if (send_goal) {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.claw_out_angle;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
- message->max_velocity = 6.0;
- message->max_acceleration = 10.0;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
- }
-
- if (params.only_place) {
- // open grabber for place only
- DoFridgeProfile(params.bottom + values.tote_height, 0.0, kFastElevatorMove,
- kFastArmMove, false);
- // Finish early if we aren't supposed to grab.
- return true;
- }
-
- if (ShouldCancel()) return true;
- // grab can (if in fang mode the grabber stays closed)
- DoFridgeProfile(params.bottom, 0.0, kReallyFastElevatorMove, kFastArmMove, true,
- true, true);
-
- return true;
-}
-
-::std::unique_ptr<StackAction> MakeStackAction(const StackParams ¶ms) {
- return ::std::unique_ptr<StackAction>(
- new StackAction(&::frc971::actors::stack_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/stack_actor.h b/frc971/actors/stack_actor.h
deleted file mode 100644
index 0d637bc..0000000
--- a/frc971/actors/stack_actor.h
+++ /dev/null
@@ -1,31 +0,0 @@
-#ifndef FRC971_ACTORS_STACK_ACTOR_H_
-#define FRC971_ACTORS_STACK_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/stack_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class StackActor : public FridgeActorBase<StackActionQueueGroup> {
- public:
- explicit StackActor(StackActionQueueGroup *queues);
-
- bool RunAction(const StackParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<StackActionQueueGroup> StackAction;
-
-// Makes a new stackActor action.
-::std::unique_ptr<StackAction> MakeStackAction(const StackParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif
diff --git a/frc971/actors/stack_actor_main.cc b/frc971/actors/stack_actor_main.cc
deleted file mode 100644
index 9a65352..0000000
--- a/frc971/actors/stack_actor_main.cc
+++ /dev/null
@@ -1,15 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/stack_action.q.h"
-#include "frc971/actors/stack_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::StackActor stack(&::frc971::actors::stack_action);
- stack.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/stack_actor_test.cc b/frc971/actors/stack_actor_test.cc
deleted file mode 100644
index b14ac1e..0000000
--- a/frc971/actors/stack_actor_test.cc
+++ /dev/null
@@ -1,72 +0,0 @@
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/queue.h"
-#include "aos/common/queue_testutils.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/stack_action.q.h"
-#include "frc971/actors/stack_actor.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-
-#include "aos/common/controls/control_loop_test.h"
-#include "frc971/control_loops/team_number_test_environment.h"
-
-using ::aos::time::Time;
-
-namespace frc971 {
-namespace actors {
-namespace testing {
-
-class StackActionTest : public ::testing::Test {
- protected:
- StackActionTest() {
- frc971::actors::stack_action.goal.Clear();
- frc971::actors::stack_action.status.Clear();
- control_loops::fridge_queue.status.Clear();
- control_loops::fridge_queue.goal.Clear();
- }
-
- virtual ~StackActionTest() {
- frc971::actors::stack_action.goal.Clear();
- frc971::actors::stack_action.status.Clear();
- control_loops::fridge_queue.status.Clear();
- control_loops::fridge_queue.goal.Clear();
- }
-
- // Bring up and down Core.
- ::aos::common::testing::GlobalCoreInstance my_core;
-};
-
-// Tests that cancel stops not only the stack action, but the underlying profile
-// action.
-TEST_F(StackActionTest, StackCancel) {
- StackActor stack(&frc971::actors::stack_action);
-
- frc971::actors::stack_action.goal.MakeWithBuilder().run(true).Send();
-
- // tell it the fridge is zeroed
- control_loops::fridge_queue.status.MakeWithBuilder()
- .zeroed(true)
- .angle(0.0)
- .height(0.0)
- .Send();
-
- // do the action and it will post to the goal queue
- stack.WaitForActionRequest();
-
- // the action has started, so now cancel it and it should cancel
- // the underlying profile
- frc971::actors::stack_action.goal.MakeWithBuilder().run(false).Send();
-
- // let the action start running, if we return from this call it has worked.
- StackParams s;
- stack.RunAction(s);
-
- SUCCEED();
-}
-
-} // namespace testing
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/stack_and_hold_action.q b/frc971/actors/stack_and_hold_action.q
deleted file mode 100644
index 7042096..0000000
--- a/frc971/actors/stack_and_hold_action.q
+++ /dev/null
@@ -1,42 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-import "frc971/actors/stack_action_params.q";
-
-// Parameters to send with start.
-struct StackAndHoldParams {
- // If true, there is no tote on the tray, and we should place instead.
- bool place_not_stack;
-
- double claw_out_angle;
- // The height just above the box to move before lowering.
- double over_box_before_place_height;
-
- // Bottom position.
- double bottom;
-
- // If we are placing, clamp the stack with the claw.
- double claw_clamp_angle;
-
- // Amount to wait to release.
- double clamp_pause_time;
-
- // The value to move the arm forwards to clear the stack when lifting.
- double arm_clearance;
- // Hold height
- double hold_height;
-};
-
-queue_group StackAndHoldActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- StackAndHoldParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group StackAndHoldActionQueueGroup stack_and_hold_action;
diff --git a/frc971/actors/stack_and_hold_actor.cc b/frc971/actors/stack_and_hold_actor.cc
deleted file mode 100644
index ab9b077..0000000
--- a/frc971/actors/stack_and_hold_actor.cc
+++ /dev/null
@@ -1,132 +0,0 @@
-#include "frc971/actors/stack_and_hold_actor.h"
-
-#include <math.h>
-
-#include "aos/common/time.h"
-#include "aos/common/util/phased_loop.h"
-
-#include "frc971/constants.h"
-#include "frc971/control_loops/claw/claw.q.h"
-#include "frc971/actors/stack_actor.h"
-
-namespace frc971 {
-namespace actors {
-namespace {
-constexpr ProfileParams kReallySlowArmMove{0.1, 1.0};
-constexpr ProfileParams kReallySlowElevatorMove{0.10, 1.0};
-
-constexpr ProfileParams kFastArmMove{0.8, 4.0};
-constexpr ProfileParams kFastElevatorMove{1.2, 4.0};
-} // namespace
-
-StackAndHoldActor::StackAndHoldActor(StackAndHoldActionQueueGroup *queues)
- : FridgeActorBase<StackAndHoldActionQueueGroup>(queues) {}
-
-bool StackAndHoldActor::RunAction(const StackAndHoldParams ¶ms) {
- // TODO(ben)): this action is no longer used (source Cameron) and my be broken
- // by the stack action having the grabbers closed at the end for the fangs. So
- // here I am disabling it until further information is provided.
- if (params.place_not_stack) {
- // Move the arm out of the way.
- {
- bool send_goal = true;
- control_loops::claw_queue.status.FetchLatest();
- if (control_loops::claw_queue.status.get()) {
- if (control_loops::claw_queue.status->goal_angle <
- params.claw_out_angle) {
- send_goal = false;
- }
- }
- if (send_goal) {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.claw_out_angle;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
- message->max_velocity = 6.0;
- message->max_acceleration = 10.0;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
- }
-
- // Get close, but keep the arm forwards
- DoFridgeProfile(params.bottom + 0.04, -0.05, kFastArmMove,
- kFastElevatorMove, true);
-
- // Lower and pull back.
- if (ShouldCancel()) return true;
- DoFridgeProfile(params.bottom, 0.0, kReallySlowArmMove,
- kReallySlowElevatorMove, true, true, false);
-
- // Release.
- if (ShouldCancel()) return true;
- DoFridgeProfile(params.bottom, 0.0, kReallySlowArmMove,
- kReallySlowElevatorMove, false);
- } else {
- StackParams stack_params;
- stack_params.only_place = true;
- stack_params.arm_clearance = params.arm_clearance;
- stack_params.claw_out_angle = params.claw_out_angle;
- stack_params.over_box_before_place_height =
- params.over_box_before_place_height;
- stack_params.bottom = params.bottom;
- ::std::unique_ptr<StackAction> stack_action =
- MakeStackAction(stack_params);
- stack_action->Start();
- while (stack_action->Running()) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(),
- 2500);
-
- if (ShouldCancel()) {
- stack_action->Cancel();
- LOG(WARNING, "Cancelling fridge and claw.\n");
- return true;
- }
- }
- }
-
- if (!WaitOrCancel(aos::time::Time::InSeconds(params.clamp_pause_time))) {
- return true;
- }
-
- // Go up.
- DoFridgeProfile(params.hold_height, params.arm_clearance, kFastArmMove,
- kFastElevatorMove, false);
-
- if (ShouldCancel()) return true;
-
- if (params.place_not_stack) {
- // Clamp the stack with the claw.
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = params.claw_clamp_angle;
- message->angular_velocity = 0.0;
- message->intake = 0.0;
- message->rollers_closed = true;
- message->max_velocity = 6.0;
- message->max_acceleration = 6.0;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
- }
- // Move back
- DoFridgeProfile(params.hold_height, 0.0, kFastArmMove, kFastElevatorMove,
- false);
- if (ShouldCancel()) return true;
- // Grab
- DoFridgeProfile(params.hold_height, 0.0, kFastArmMove, kFastElevatorMove,
- true);
- if (ShouldCancel()) return true;
-
- return true;
-}
-
-::std::unique_ptr<StackAndHoldAction> MakeStackAndHoldAction(
- const StackAndHoldParams ¶ms) {
- return ::std::unique_ptr<StackAndHoldAction>(
- new StackAndHoldAction(&::frc971::actors::stack_and_hold_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/stack_and_hold_actor.h b/frc971/actors/stack_and_hold_actor.h
deleted file mode 100644
index bfc877b..0000000
--- a/frc971/actors/stack_and_hold_actor.h
+++ /dev/null
@@ -1,33 +0,0 @@
-#ifndef FRC971_ACTORS_STACK_AND_HOLD_ACTOR_H_
-#define FRC971_ACTORS_STACK_AND_HOLD_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/stack_and_hold_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class StackAndHoldActor : public FridgeActorBase<StackAndHoldActionQueueGroup> {
- public:
- explicit StackAndHoldActor(StackAndHoldActionQueueGroup *queues);
-
- bool RunAction(const StackAndHoldParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<StackAndHoldActionQueueGroup>
- StackAndHoldAction;
-
-// Makes a new stackActor action.
-::std::unique_ptr<StackAndHoldAction> MakeStackAndHoldAction(
- const StackAndHoldParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_STACK_AND_HOLD_ACTOR_H_
diff --git a/frc971/actors/stack_and_hold_actor_main.cc b/frc971/actors/stack_and_hold_actor_main.cc
deleted file mode 100644
index 2bd63bb..0000000
--- a/frc971/actors/stack_and_hold_actor_main.cc
+++ /dev/null
@@ -1,16 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/stack_and_hold_action.q.h"
-#include "frc971/actors/stack_and_hold_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::StackAndHoldActor stack_and_hold(
- &::frc971::actors::stack_and_hold_action);
- stack_and_hold.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/actors/stack_and_lift_action.q b/frc971/actors/stack_and_lift_action.q
deleted file mode 100644
index f61ac32..0000000
--- a/frc971/actors/stack_and_lift_action.q
+++ /dev/null
@@ -1,34 +0,0 @@
-package frc971.actors;
-
-import "aos/common/actions/actions.q";
-
-import "frc971/actors/stack_action_params.q";
-import "frc971/actors/lift_action_params.q";
-
-// Parameters to send with start.
-struct StackAndLiftParams {
- // Stack parameters
- StackParams stack_params;
- // True if the fridge should be clamped while lifting.
- bool grab_after_stack;
- // The time after clamping to pause.
- double clamp_pause_time;
- // Lift parameters
- LiftParams lift_params;
- // True if the fridge should be clamped when done.
- bool grab_after_lift;
-};
-
-queue_group StackAndLiftActionQueueGroup {
- implements aos.common.actions.ActionQueueGroup;
-
- message Goal {
- uint32_t run;
- StackAndLiftParams params;
- };
-
- queue Goal goal;
- queue aos.common.actions.Status status;
-};
-
-queue_group StackAndLiftActionQueueGroup stack_and_lift_action;
diff --git a/frc971/actors/stack_and_lift_actor.cc b/frc971/actors/stack_and_lift_actor.cc
deleted file mode 100644
index 273f352..0000000
--- a/frc971/actors/stack_and_lift_actor.cc
+++ /dev/null
@@ -1,115 +0,0 @@
-#include "frc971/actors/stack_and_lift_actor.h"
-
-#include <math.h>
-
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/time.h"
-#include "aos/common/util/phased_loop.h"
-
-#include "frc971/constants.h"
-#include "frc971/control_loops/claw/claw.q.h"
-#include "frc971/actors/stack_actor.h"
-#include "frc971/actors/lift_actor.h"
-
-namespace frc971 {
-namespace actors {
-
-StackAndLiftActor::StackAndLiftActor(StackAndLiftActionQueueGroup *queues)
- : FridgeActorBase<StackAndLiftActionQueueGroup>(queues) {}
-
-bool StackAndLiftActor::RunAction(const StackAndLiftParams ¶ms) {
- control_loops::claw_queue.goal.FetchLatest();
- double claw_goal_start;
- bool have_claw_goal_start;
- if (control_loops::claw_queue.goal.get()) {
- claw_goal_start = control_loops::claw_queue.goal->angle;
- have_claw_goal_start = true;
- } else {
- claw_goal_start = 0;
- have_claw_goal_start = false;
- }
-
- {
- StackParams stack_params = params.stack_params;
- stack_params.only_place = false;
- ::std::unique_ptr<StackAction> stack_action =
- MakeStackAction(stack_params);
- stack_action->Start();
- while (stack_action->Running()) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(),
- 2500);
-
- if (ShouldCancel()) {
- stack_action->Cancel();
- LOG(WARNING, "Cancelling fridge and claw.\n");
- return true;
- }
- }
- }
-
- {
- control_loops::fridge_queue.goal.FetchLatest();
- if (!control_loops::fridge_queue.goal.get()) {
- return false;
- }
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- *new_fridge_goal = *control_loops::fridge_queue.goal;
- new_fridge_goal->grabbers.top_front = params.grab_after_stack;
- new_fridge_goal->grabbers.top_back = params.grab_after_stack;
- new_fridge_goal->grabbers.bottom_front = params.grab_after_stack;
- new_fridge_goal->grabbers.bottom_back = params.grab_after_stack;
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Failed to send fridge close.\n");
- return false;
- }
- }
-
- if (!WaitOrCancel(aos::time::Time::InSeconds(params.clamp_pause_time))) {
- return true;
- }
-
- {
- auto lift_params = params.lift_params;
- lift_params.pack_claw = have_claw_goal_start;
- lift_params.pack_claw_angle = claw_goal_start;
- ::std::unique_ptr<LiftAction> lift_action = MakeLiftAction(lift_params);
- lift_action->Start();
- while (lift_action->Running()) {
- ::aos::time::PhasedLoopXMS(::aos::controls::kLoopFrequency.ToMSec(),
- 2500);
-
- if (ShouldCancel()) {
- lift_action->Cancel();
- LOG(WARNING, "Cancelling fridge and claw.\n");
- return true;
- }
- }
- }
-
- {
- control_loops::fridge_queue.goal.FetchLatest();
- if (!control_loops::fridge_queue.goal.get()) {
- return false;
- }
- auto new_fridge_goal = control_loops::fridge_queue.goal.MakeMessage();
- *new_fridge_goal = *control_loops::fridge_queue.goal;
- new_fridge_goal->grabbers.top_front = params.grab_after_lift;
- new_fridge_goal->grabbers.top_back = params.grab_after_lift;
- new_fridge_goal->grabbers.bottom_front = params.grab_after_lift;
- new_fridge_goal->grabbers.bottom_back = params.grab_after_lift;
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Failed to send fridge close.\n");
- return false;
- }
- }
- return true;
-}
-
-::std::unique_ptr<StackAndLiftAction> MakeStackAndLiftAction(
- const StackAndLiftParams ¶ms) {
- return ::std::unique_ptr<StackAndLiftAction>(
- new StackAndLiftAction(&::frc971::actors::stack_and_lift_action, params));
-}
-
-} // namespace actors
-} // namespace frc971
diff --git a/frc971/actors/stack_and_lift_actor.h b/frc971/actors/stack_and_lift_actor.h
deleted file mode 100644
index 7dcaba5..0000000
--- a/frc971/actors/stack_and_lift_actor.h
+++ /dev/null
@@ -1,33 +0,0 @@
-#ifndef FRC971_ACTORS_STACK_AND_LIFT_ACTOR_H_
-#define FRC971_ACTORS_STACK_AND_LIFT_ACTOR_H_
-
-#include <stdint.h>
-
-#include <memory>
-
-#include "aos/common/actions/actions.h"
-#include "aos/common/actions/actor.h"
-#include "frc971/actors/stack_and_lift_action.q.h"
-#include "frc971/actors/fridge_profile_lib.h"
-
-namespace frc971 {
-namespace actors {
-
-class StackAndLiftActor : public FridgeActorBase<StackAndLiftActionQueueGroup> {
- public:
- explicit StackAndLiftActor(StackAndLiftActionQueueGroup *queues);
-
- bool RunAction(const StackAndLiftParams ¶ms) override;
-};
-
-typedef aos::common::actions::TypedAction<StackAndLiftActionQueueGroup>
- StackAndLiftAction;
-
-// Makes a new stackActor action.
-::std::unique_ptr<StackAndLiftAction> MakeStackAndLiftAction(
- const StackAndLiftParams ¶ms);
-
-} // namespace actors
-} // namespace frc971
-
-#endif // FRC971_ACTORS_STACK_AND_LIFT_ACTOR_H_
diff --git a/frc971/actors/stack_and_lift_actor_main.cc b/frc971/actors/stack_and_lift_actor_main.cc
deleted file mode 100644
index 882d9d7..0000000
--- a/frc971/actors/stack_and_lift_actor_main.cc
+++ /dev/null
@@ -1,16 +0,0 @@
-#include <stdio.h>
-
-#include "aos/linux_code/init.h"
-#include "frc971/actors/stack_and_lift_action.q.h"
-#include "frc971/actors/stack_and_lift_actor.h"
-
-int main(int /*argc*/, char* /*argv*/ []) {
- ::aos::Init();
-
- ::frc971::actors::StackAndLiftActor stack_and_lift(
- &::frc971::actors::stack_and_lift_action);
- stack_and_lift.Run();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/autonomous/auto.cc b/frc971/autonomous/auto.cc
deleted file mode 100644
index d040756..0000000
--- a/frc971/autonomous/auto.cc
+++ /dev/null
@@ -1,558 +0,0 @@
-#include <stdio.h>
-
-#include <memory>
-
-#include "aos/common/util/phased_loop.h"
-#include "aos/common/time.h"
-#include "aos/common/util/trapezoid_profile.h"
-#include "aos/common/logging/logging.h"
-#include "aos/common/logging/queue_logging.h"
-
-#include "frc971/autonomous/auto.q.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/actors/drivetrain_actor.h"
-#include "frc971/control_loops/claw/claw.q.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "frc971/actors/pickup_actor.h"
-#include "frc971/actors/stack_actor.h"
-#include "frc971/actors/held_to_lift_actor.h"
-
-using ::aos::time::Time;
-using ::frc971::control_loops::claw_queue;
-using ::frc971::control_loops::fridge_queue;
-using ::frc971::control_loops::drivetrain_queue;
-
-namespace frc971 {
-namespace autonomous {
-
-constexpr double kClawAutoVelocity = 3.00;
-constexpr double kClawAutoAcceleration = 6.0;
-constexpr double kAngleEpsilon = 0.10;
-const double kClawTotePackAngle = 0.90;
-const double kArmRaiseLowerClearance = -0.08;
-const double kClawStackClearance = 0.55;
-const double kStackUpHeight = 0.60;
-const double kStackUpArm = 0.0;
-
-struct ProfileParams {
- double velocity;
- double acceleration;
-};
-
-namespace time = ::aos::time;
-
-static double left_initial_position, right_initial_position;
-
-bool ShouldExitAuto() {
- ::frc971::autonomous::autonomous.FetchLatest();
- bool ans = !::frc971::autonomous::autonomous->run_auto;
- if (ans) {
- LOG(INFO, "Time to exit auto mode\n");
- }
- return ans;
-}
-
-void StopDrivetrain() {
- LOG(INFO, "Stopping the drivetrain\n");
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
- .control_loop_driving(true)
- .left_goal(left_initial_position)
- .left_velocity_goal(0)
- .right_goal(right_initial_position)
- .right_velocity_goal(0)
- .quickturn(false)
- .Send();
-}
-
-void ResetDrivetrain() {
- LOG(INFO, "resetting the drivetrain\n");
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
- .control_loop_driving(false)
- //.highgear(false)
- .steering(0.0)
- .throttle(0.0)
- .left_goal(left_initial_position)
- .left_velocity_goal(0)
- .right_goal(right_initial_position)
- .right_velocity_goal(0)
- .Send();
-}
-
-void WaitUntilDoneOrCanceled(
- ::std::unique_ptr<aos::common::actions::Action> action) {
- if (!action) {
- LOG(ERROR, "No action, not waiting\n");
- return;
- }
- while (true) {
- // Poll the running bit and auto done bits.
- ::aos::time::PhasedLoopXMS(5, 2500);
- if (!action->Running() || ShouldExitAuto()) {
- return;
- }
- }
-}
-
-void StepDrive(double distance, double theta) {
- double left_goal = (left_initial_position + distance -
- theta * constants::GetValues().turn_width / 2.0);
- double right_goal = (right_initial_position + distance +
- theta * constants::GetValues().turn_width / 2.0);
- control_loops::drivetrain_queue.goal.MakeWithBuilder()
- .control_loop_driving(true)
- .left_goal(left_goal)
- .right_goal(right_goal)
- .left_velocity_goal(0.0)
- .right_velocity_goal(0.0)
- .Send();
- left_initial_position = left_goal;
- right_initial_position = right_goal;
-}
-
-void WaitUntilNear(double distance) {
- while (true) {
- if (ShouldExitAuto()) return;
- control_loops::drivetrain_queue.status.FetchAnother();
- double left_error = ::std::abs(
- left_initial_position -
- control_loops::drivetrain_queue.status->filtered_left_position);
- double right_error = ::std::abs(
- right_initial_position -
- control_loops::drivetrain_queue.status->filtered_right_position);
- const double kPositionThreshold = 0.05 + distance;
- if (right_error < kPositionThreshold && left_error < kPositionThreshold) {
- LOG(INFO, "At the goal\n");
- return;
- }
- }
-}
-
-const ProfileParams kFastDrive = {2.0, 3.5};
-const ProfileParams kFastKnockDrive = {2.0, 3.0};
-const ProfileParams kStackingSecondDrive = {2.0, 1.5};
-const ProfileParams kFastTurn = {3.0, 10.0};
-const ProfileParams kStackingFirstTurn = {1.0, 1.0};
-const ProfileParams kStackingSecondTurn = {2.0, 6.0};
-const ProfileParams kComboTurn = {1.2, 8.0};
-const ProfileParams kRaceTurn = {4.0, 10.0};
-const ProfileParams kRaceDrive = {2.0, 2.0};
-const ProfileParams kRaceBackupDrive = {2.0, 5.0};
-
-::std::unique_ptr<::frc971::actors::DrivetrainAction> SetDriveGoal(
- double distance, const ProfileParams drive_params, double theta = 0, const ProfileParams &turn_params = kFastTurn) {
- LOG(INFO, "Driving to %f\n", distance);
-
- ::frc971::actors::DrivetrainActionParams params;
- params.left_initial_position = left_initial_position;
- params.right_initial_position = right_initial_position;
- params.y_offset = distance;
- params.theta_offset = theta;
- params.maximum_turn_acceleration = turn_params.acceleration;
- params.maximum_turn_velocity = turn_params.velocity;
- params.maximum_velocity = drive_params.velocity;
- params.maximum_acceleration = drive_params.acceleration;
- auto drivetrain_action = actors::MakeDrivetrainAction(params);
-
- drivetrain_action->Start();
- left_initial_position +=
- distance - theta * constants::GetValues().turn_width / 2.0;
- right_initial_position +=
- distance + theta * constants::GetValues().turn_width / 2.0;
- return ::std::move(drivetrain_action);
-}
-
-const ProfileParams kFridgeYProfile{1.0, 4.0};
-const ProfileParams kFridgeXProfile{1.0, 2.0};
-const ProfileParams kFridgeFastXProfile{1.2, 5.0};
-
-static double fridge_goal_x = 0.0;
-static double fridge_goal_y = 0.0;
-
-void MoveFridge(double x, double y, bool grabbers, const ProfileParams x_params,
- const ProfileParams y_params) {
- auto new_fridge_goal = fridge_queue.goal.MakeMessage();
- new_fridge_goal->profiling_type = 1;
-
- new_fridge_goal->max_y_velocity = y_params.velocity;
- new_fridge_goal->max_y_acceleration = y_params.acceleration;
- new_fridge_goal->y = y;
- fridge_goal_y = y;
- new_fridge_goal->y_velocity = 0.0;
-
- new_fridge_goal->max_x_velocity = x_params.velocity;
- new_fridge_goal->max_x_acceleration = x_params.acceleration;
- new_fridge_goal->x = x;
- fridge_goal_x = x;
- new_fridge_goal->x_velocity = 0.0;
-
- new_fridge_goal->grabbers.top_front = grabbers;
- new_fridge_goal->grabbers.top_back = grabbers;
- new_fridge_goal->grabbers.bottom_front = grabbers;
- new_fridge_goal->grabbers.bottom_back = grabbers;
-
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Sending fridge goal failed.\n");
- return;
- }
-}
-
-void WaitForFridge() {
- while (true) {
- if (ShouldExitAuto()) return;
- control_loops::fridge_queue.status.FetchAnother();
-
- constexpr double kProfileError = 1e-5;
- constexpr double kXEpsilon = 0.03, kYEpsilon = 0.03;
-
- if (control_loops::fridge_queue.status->state != 4) {
- LOG(ERROR, "Fridge no longer running, aborting action\n");
- return;
- }
-
- if (::std::abs(control_loops::fridge_queue.status->goal_x - fridge_goal_x) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_y - fridge_goal_y) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_x_velocity) <
- kProfileError &&
- ::std::abs(control_loops::fridge_queue.status->goal_y_velocity) <
- kProfileError) {
- LOG(INFO, "Profile done.\n");
- if (::std::abs(control_loops::fridge_queue.status->x - fridge_goal_x) <
- kXEpsilon &&
- ::std::abs(control_loops::fridge_queue.status->y - fridge_goal_y) <
- kYEpsilon) {
- LOG(INFO, "Near goal, done.\n");
- return;
- }
- }
- }
-}
-
-void InitializeEncoders() {
- control_loops::drivetrain_queue.status.FetchAnother();
- left_initial_position =
- control_loops::drivetrain_queue.status->filtered_left_position;
- right_initial_position =
- control_loops::drivetrain_queue.status->filtered_right_position;
-}
-
-void WaitForClawZero() {
- LOG(INFO, "Waiting for claw to zero.\n");
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
- if (control_loops::claw_queue.status->zeroed) {
- LOG(INFO, "Claw zeroed\n");
- return;
- }
-
- if (ShouldExitAuto()) return;
- }
-}
-
-void WaitForFridgeZero() {
- LOG(INFO, "Waiting for claw to zero.\n");
- while (true) {
- control_loops::fridge_queue.status.FetchAnother();
- LOG_STRUCT(DEBUG, "Got fridge status", *control_loops::fridge_queue.status);
- if (control_loops::fridge_queue.status->zeroed) {
- LOG(INFO, "Fridge zeroed\n");
- return;
- }
-
- if (ShouldExitAuto()) return;
- }
-}
-
-constexpr ProfileParams kDefaultClawParams = {kClawAutoVelocity,
- kClawAutoAcceleration};
-
-// Move the claw in a very small number of cycles.
-constexpr ProfileParams kInstantaneousClaw = {100.0, 100.0};
-constexpr ProfileParams kFastClaw = {8.0, 20.0};
-
-void SetClawStateNoWait(double angle, double intake_voltage,
- double rollers_closed,
- const ProfileParams &claw_params = kDefaultClawParams) {
- auto message = control_loops::claw_queue.goal.MakeMessage();
- message->angle = angle;
- message->max_velocity = claw_params.velocity;
- message->max_acceleration = claw_params.acceleration;
- message->angular_velocity = 0.0;
- message->intake = intake_voltage;
- message->rollers_closed = rollers_closed;
-
- LOG_STRUCT(DEBUG, "Sending claw goal", *message);
- message.Send();
-}
-
-void SetClawState(double angle, double intake_voltage, double rollers_closed,
- const ProfileParams &claw_params = kDefaultClawParams) {
- SetClawStateNoWait(angle, intake_voltage, rollers_closed, claw_params);
- while (true) {
- control_loops::claw_queue.status.FetchAnother();
- const double current_angle = control_loops::claw_queue.status->angle;
- LOG_STRUCT(DEBUG, "Got claw status", *control_loops::claw_queue.status);
-
- // I believe all we can care about here is the angle. Other values will
- // either be set or not, but there is nothing we can do about it. If it
- // never gets there we do not care, auto is over for us.
- if (::std::abs(current_angle - angle) < kAngleEpsilon) {
- break;
- }
- if (ShouldExitAuto()) return;
- }
-}
-
-void HandleAuto() {
- ::aos::time::Time start_time = ::aos::time::Time::Now();
- LOG(INFO, "Starting auto mode at %f\n", start_time.ToSeconds());
- ::std::unique_ptr<::frc971::actors::DrivetrainAction> drive;
- ::std::unique_ptr<::frc971::actors::PickupAction> pickup;
- ::std::unique_ptr<::frc971::actors::StackAction> stack;
- ::std::unique_ptr<::frc971::actors::HeldToLiftAction> lift;
-
- actors::PickupParams pickup_params;
- // Lift to here initially.
- pickup_params.pickup_angle = 0.9;
- // Start sucking here
- pickup_params.suck_angle = 0.8;
- // Go back down to here to finish sucking.
- pickup_params.suck_angle_finish = 0.4;
- // Pack the box back in here.
- pickup_params.pickup_finish_angle = kClawTotePackAngle;
- pickup_params.intake_time = 0.70;
- pickup_params.intake_voltage = 7.0;
-
- if (ShouldExitAuto()) return;
- InitializeEncoders();
- ResetDrivetrain();
-
- WaitForClawZero();
- WaitForFridgeZero();
-
- // Initialize the fridge.
- MoveFridge(0.0, 0.3, true, kFridgeXProfile, kFridgeYProfile);
-
- LOG(INFO, "Lowering claw into position.\n");
- SetClawState(0.0, 2.0, false, kInstantaneousClaw);
-
- LOG(INFO, "Sucking in tote.\n");
- SetClawState(0.0, 6.0, true, kInstantaneousClaw);
-
- time::SleepFor(time::Time::InSeconds(0.7));
- LOG(INFO, "Done sucking in tote\n");
-
- // Now pick it up
- pickup = actors::MakePickupAction(pickup_params);
- pickup->Start();
-
- time::SleepFor(time::Time::InSeconds(0.9));
- // Start turning.
- LOG(INFO, "Turning in place\n");
- drive = SetDriveGoal(0.0, kFastDrive, -0.23, kStackingFirstTurn);
-
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Now driving next to the can\n");
- drive = SetDriveGoal(0.60, kFastDrive);
-
- WaitUntilDoneOrCanceled(::std::move(pickup));
- if (ShouldExitAuto()) return;
-
- // Now grab it in the fridge.
- {
- actors::StackParams params;
-
- params.claw_out_angle = kClawTotePackAngle;
- params.bottom = 0.020;
- params.only_place = false;
- params.arm_clearance = kArmRaiseLowerClearance;
- params.over_box_before_place_height = 0.39;
-
- stack = actors::MakeStackAction(params);
- stack->Start();
- }
- WaitUntilDoneOrCanceled(::std::move(stack));
- if (ShouldExitAuto()) return;
-
- // Lower the claw to knock the tote.
- LOG(INFO, "Lowering the claw to knock the tote\n");
- SetClawStateNoWait(0.0, 0.0, true, kFastClaw);
-
- time::SleepFor(time::Time::InSeconds(0.1));
- if (ShouldExitAuto()) return;
-
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Knocking the can over\n");
- drive = SetDriveGoal(0.40, kFastKnockDrive, 1.05, kComboTurn);
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
- {
- actors::HeldToLiftParams params;
- params.arm_clearance = kArmRaiseLowerClearance;
- params.clamp_pause_time = 0.1;
- params.before_lift_settle_time = 0.1;
- params.bottom_height = 0.020;
- params.claw_out_angle = kClawStackClearance;
- params.lift_params.lift_height = kStackUpHeight;
- params.lift_params.lift_arm = kStackUpArm;
- params.lift_params.second_lift = false;
-
- lift = actors::MakeHeldToLiftAction(params);
- lift->Start();
- }
-
- LOG(INFO, "Turning back to aim\n");
- drive = SetDriveGoal(0.0, kFastDrive, -0.70);
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- SetClawStateNoWait(0.0, 4.0, false, kFastClaw);
- LOG(INFO, "Now driving the second tote\n");
- drive = SetDriveGoal(1.05, kFastDrive);
-
- // Wait until we are almost at the tote, and then start intaking.
- WaitUntilNear(0.35);
-
- SetClawState(0.0, 6.0, true, kFastClaw);
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- if (ShouldExitAuto()) return;
- time::SleepFor(time::Time::InSeconds(0.30));
- if (ShouldExitAuto()) return;
-
- SetClawStateNoWait(0.0, 4.0, true, kFastClaw);
- if (ShouldExitAuto()) return;
- time::SleepFor(time::Time::InSeconds(0.10));
-
- WaitUntilDoneOrCanceled(::std::move(lift));
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Done sucking in tote\n");
- SetClawState(0.0, 0.0, true, kFastClaw);
- if (ShouldExitAuto()) return;
-
- // Now pick it up
- pickup = actors::MakePickupAction(pickup_params);
- pickup->Start();
-
- time::SleepFor(time::Time::InSeconds(1.0));
- if (ShouldExitAuto()) return;
-
- // Start turning.
- LOG(INFO, "Turning in place\n");
- drive = SetDriveGoal(0.0, kStackingSecondDrive, -0.40, kStackingSecondTurn);
-
- WaitUntilDoneOrCanceled(::std::move(pickup));
- if (ShouldExitAuto()) return;
-
- // Now grab it in the fridge.
- {
- actors::StackParams params;
-
- params.claw_out_angle = kClawTotePackAngle;
- params.bottom = 0.020;
- params.only_place = false;
- params.arm_clearance = kArmRaiseLowerClearance;
- params.over_box_before_place_height = 0.39;
-
- stack = actors::MakeStackAction(params);
- stack->Start();
- }
-
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
- LOG(INFO, "Driving next to the can.\n");
- drive = SetDriveGoal(0.65, kStackingSecondDrive);
-
- WaitUntilDoneOrCanceled(::std::move(stack));
- if (ShouldExitAuto()) return;
-
- // Lower the claw to knock the tote.
- LOG(INFO, "Lowering the claw to knock the tote\n");
- SetClawStateNoWait(0.0, 0.0, true, kFastClaw);
-
- // Lift the fridge.
- MoveFridge(0.0, 0.3, true, kFridgeXProfile, kFridgeYProfile);
-
- time::SleepFor(time::Time::InSeconds(0.1));
- if (ShouldExitAuto()) return;
-
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Knocking the can over\n");
- drive = SetDriveGoal(0.40, kFastKnockDrive, 1.05, kComboTurn);
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Turning back to aim\n");
- drive = SetDriveGoal(0.0, kFastDrive, -0.60);
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
-
- SetClawStateNoWait(0.0, 4.0, false, kFastClaw);
- LOG(INFO, "Now driving to the last tote\n");
- drive = SetDriveGoal(1.05, kFastDrive);
- WaitUntilNear(0.05);
-
- SetClawState(0.0, 7.0, true, kFastClaw);
- if (ShouldExitAuto()) return;
-
- time::SleepFor(time::Time::InSeconds(0.2));
- if (ShouldExitAuto()) return;
-
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
- SetClawState(0.0, 6.0, true, kFastClaw);
-
- LOG(INFO, "Racing over\n");
- //StepDrive(2.5, -1.4);
- drive = SetDriveGoal(2.5, kRaceDrive, -1.4, kRaceTurn);
-
- time::SleepFor(time::Time::InSeconds(0.5));
-
- LOG(INFO, "Moving totes out\n");
- MoveFridge(0.6, 0.32, true, kFridgeXProfile, kFridgeYProfile);
-
- WaitForFridge();
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Lowering totes\n");
- MoveFridge(0.6, 0.15, false, kFridgeXProfile, kFridgeYProfile);
-
- WaitForFridge();
- if (ShouldExitAuto()) return;
-
- time::SleepFor(time::Time::InSeconds(0.1));
-
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Retracting\n");
- MoveFridge(0.0, 0.10, false, kFridgeFastXProfile, kFridgeYProfile);
-
- SetClawState(0.0, 0.0, false, kFastClaw);
-
- if (ShouldExitAuto()) return;
-
- WaitUntilDoneOrCanceled(::std::move(drive));
- if (ShouldExitAuto()) return;
-
- LOG(INFO, "Backing away to let the stack ago\n");
- drive = SetDriveGoal(-0.1, kRaceBackupDrive);
- WaitUntilDoneOrCanceled(::std::move(drive));
-
- WaitForFridge();
- if (ShouldExitAuto()) return;
-}
-
-} // namespace autonomous
-} // namespace frc971
diff --git a/frc971/autonomous/auto.h b/frc971/autonomous/auto.h
deleted file mode 100644
index 21122bc..0000000
--- a/frc971/autonomous/auto.h
+++ /dev/null
@@ -1,12 +0,0 @@
-#ifndef FRC971_AUTONOMOUS_AUTO_H_
-#define FRC971_AUTONOMOUS_AUTO_H_
-
-namespace frc971 {
-namespace autonomous {
-
-void HandleAuto();
-
-} // namespace autonomous
-} // namespace frc971
-
-#endif // FRC971_AUTONOMOUS_AUTO_H_
diff --git a/frc971/autonomous/auto_main.cc b/frc971/autonomous/auto_main.cc
deleted file mode 100644
index 9a70682..0000000
--- a/frc971/autonomous/auto_main.cc
+++ /dev/null
@@ -1,42 +0,0 @@
-#include <stdio.h>
-
-#include "aos/common/time.h"
-#include "aos/linux_code/init.h"
-#include "aos/common/logging/logging.h"
-#include "frc971/autonomous/auto.q.h"
-#include "frc971/autonomous/auto.h"
-
-using ::aos::time::Time;
-
-int main(int /*argc*/, char * /*argv*/[]) {
- ::aos::Init();
-
- LOG(INFO, "Auto main started\n");
- ::frc971::autonomous::autonomous.FetchLatest();
- while (!::frc971::autonomous::autonomous.get()) {
- ::frc971::autonomous::autonomous.FetchNextBlocking();
- LOG(INFO, "Got another auto packet\n");
- }
-
- while (true) {
- while (!::frc971::autonomous::autonomous->run_auto) {
- ::frc971::autonomous::autonomous.FetchNextBlocking();
- LOG(INFO, "Got another auto packet\n");
- }
- LOG(INFO, "Starting auto mode\n");
- ::aos::time::Time start_time = ::aos::time::Time::Now();
- ::frc971::autonomous::HandleAuto();
-
- ::aos::time::Time elapsed_time = ::aos::time::Time::Now() - start_time;
- LOG(INFO, "Auto mode exited in %f, waiting for it to finish.\n",
- elapsed_time.ToSeconds());
- while (::frc971::autonomous::autonomous->run_auto) {
- ::frc971::autonomous::autonomous.FetchNextBlocking();
- LOG(INFO, "Got another auto packet\n");
- }
- LOG(INFO, "Waiting for auto to start back up.\n");
- }
- ::aos::Cleanup();
- return 0;
-}
-
diff --git a/frc971/autonomous/autonomous.gyp b/frc971/autonomous/autonomous.gyp
index 8d75b27..e36a532 100644
--- a/frc971/autonomous/autonomous.gyp
+++ b/frc971/autonomous/autonomous.gyp
@@ -9,44 +9,5 @@
},
'includes': ['../../aos/build/queues.gypi'],
},
- {
- 'target_name': 'auto_lib',
- 'type': 'static_library',
- 'sources': [
- 'auto.cc',
- ],
- 'dependencies': [
- 'auto_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/util/util.gyp:trapezoid_profile',
- '<(AOS)/build/aos.gyp:logging',
- '<(DEPTH)/frc971/actors/actors.gyp:drivetrain_action_lib',
- '<(AOS)/common/logging/logging.gyp:queue_logging',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(DEPTH)/frc971/actors/actors.gyp:stack_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:held_to_lift_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:pickup_action_lib',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/controls/controls.gyp:control_loop',
- ],
- },
- {
- 'target_name': 'auto',
- 'type': 'executable',
- 'sources': [
- 'auto_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- 'auto_queue',
- 'auto_lib',
- ],
- },
],
}
diff --git a/frc971/constants.cc b/frc971/constants.cc
deleted file mode 100644
index 785c0d7..0000000
--- a/frc971/constants.cc
+++ /dev/null
@@ -1,381 +0,0 @@
-#include "frc971/constants.h"
-
-#include <math.h>
-#include <stdint.h>
-#include <inttypes.h>
-
-#include <map>
-
-#if __has_feature(address_sanitizer)
-#include "sanitizer/lsan_interface.h"
-#endif
-
-#include "aos/common/logging/logging.h"
-#include "aos/common/once.h"
-#include "aos/common/network/team_number.h"
-#include "aos/common/mutex.h"
-
-#include "frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-#include "frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-
-#ifndef M_PI
-#define M_PI 3.14159265358979323846
-#endif
-
-namespace frc971 {
-namespace constants {
-namespace {
-
-const uint16_t kCompTeamNumber = 971;
-const uint16_t kPracticeTeamNumber = 9971;
-
-// ///// Drivetrain Constants
-
-// These three constants were set by Daniel on 2/13/15.
-const double kDrivetrainEncoderRatio = 20.0 / 50.0;
-const double kLowGearRatio = kDrivetrainEncoderRatio * 20.0 / 50.0;
-const double kHighGearRatio = kLowGearRatio;
-
-const ShifterHallEffect kCompRightDriveShifter{555, 657, 660, 560, 0.2, 0.7};
-const ShifterHallEffect kCompLeftDriveShifter{555, 660, 644, 552, 0.2, 0.7};
-
-const ShifterHallEffect kPracticeRightDriveShifter{2.95, 3.95, 3.95,
- 2.95, 0.2, 0.7};
-const ShifterHallEffect kPracticeLeftDriveShifter{2.95, 4.2, 3.95,
- 3.0, 0.2, 0.7};
-const double kToteHeight = 0.3;
-
-// Set by Daniel on 2/13/15.
-// Distance from the center of the left wheel to the center of the right wheel.
-const double kRobotWidth = 37.806 /*inches*/ * 0.0254;
-
-// ///// Superstructure Constants
-
-// Elevator gearbox pulley output constants.
-const int kElevatorGearboxOutputPulleyTeeth = 32; // 32 teeth
-const double kElevatorGearboxOutputPitch = 0.005; // 5 mm/tooth
-const double kElevatorGearboxOutputRadianDistance =
- kElevatorGearboxOutputPulleyTeeth * kElevatorGearboxOutputPitch /
- (2.0 * M_PI);
-
-const double kArmZeroingHeight = 0.2;
-
-const double kMaxAllowedLeftRightArmDifference = 0.12; // radians
-const double kMaxAllowedLeftRightElevatorDifference = 0.04; // meters
-
-const Values::ClawGeometry kClawGeometry{
- // Horizontal distance from the center of the grabber to the end.
- 0.5 * 18.0 * 0.0254,
- // Vertical distance from the arm rotation center to the bottom of
- // the
- // grabber. Distance measured with arm vertical (theta = 0).
- 5.1 * 0.0254,
- // Vertical separation of the claw and arm rotation centers with the
- // elevator at 0.0 and the arm angle set to zero.
- 10.5 * 0.0254,
- // Horizontal separation of the claw and arm rotation centers with
- // the
- // elevator at 0.0 and the arm angle set to zero.
- 6.5 * 0.0254,
- // Distance between the center of the claw to the top of the claw.
- // 2.75 inches would work most of the time. Using 3.5 inches because
- // of the
- // pnumatics fitting on the piston.
- 3.5 * 0.0254,
- // The grabber is safe at any height if it is behind this location.
- // The location of the grabber is used here and not the location of
- // the end
- // of the grabber. The grabber location is (0, 0) when the elevator
- // is at 0
- // and the arm angle is 0.
- (18.0 - 0.3) * 0.0254,
- // The grabber is safe at any x if it is above this location.
- // The location of the grabber is used here and not the location of
- // the end
- // of the grabber. The grabber location is (0, 0) when the elevator
- // is at 0
- // and the arm angle is 0.
- // The "-5.4" is the location of the bottom of the grabber when
- // the elevator is at the bottom (-0.3 inches) and arm angle is 0.
- -8.0 * 0.0254,
-};
-
-// Gearing ratios of the pots and encoders for the elevator and arm.
-// Ratio is output shaft rotations per encoder/pot rotation
-// Checked by Daniel on 2/13/15.
-const double kArmEncoderRatio = 18.0 / 48.0 * 16.0 / 72.0;
-const double kArmPotRatio = 48.0 / 48.0 * 16.0 / 72.0;
-const double kElevatorEncoderRatio = 14.0 / 84.0;
-const double kElevatorPotRatio = 1.0;
-const double kClawEncoderRatio = 18.0 / 72.0;
-const double kClawPotRatio = 18.0 / 72.0;
-
-// Number of radians between each index pulse on the arm.
-const double kArmEncoderIndexDifference = 2.0 * M_PI * kArmEncoderRatio;
-// Number of meters between each index pulse on the elevator.
-const double kElevatorEncoderIndexDifference =
- kElevatorEncoderRatio * 2.0 * M_PI * // radians
- kElevatorGearboxOutputRadianDistance;
-// Number of radians between index pulses on the claw.
-const double kClawEncoderIndexDifference = 2.0 * M_PI * kClawEncoderRatio;
-
-const int kZeroingSampleSize = 200;
-
-// The length of the arm.
-const double kArmLength = 0.7366;
-
-// TODO(danielp): All these values might need to change.
-const double kClawPistonSwitchTime = 0.4;
-const double kClawZeroingRange = 0.3;
-
-const Values *DoGetValuesForTeam(uint16_t team) {
- switch (team) {
- case 1: // for tests
- return new Values{
- kDrivetrainEncoderRatio,
- kArmEncoderRatio,
- kArmPotRatio,
- kElevatorEncoderRatio,
- kElevatorPotRatio,
- kElevatorGearboxOutputRadianDistance,
- kClawEncoderRatio,
- kClawPotRatio,
- kToteHeight,
- kLowGearRatio,
- kHighGearRatio,
- kCompLeftDriveShifter,
- kCompRightDriveShifter,
- false,
- 0.5,
- control_loops::MakeVelocityDrivetrainLoop,
- control_loops::MakeDrivetrainLoop,
- 0.02, // drivetrain done delta
- 5.0, // drivetrain max speed
-
- // Motion ranges: hard_lower_limit, hard_upper_limit,
- // soft_lower_limit, soft_upper_limit
- {// Claw values, in radians.
- // 0 is level with the ground.
- // Positive moves in the direction of positive encoder values.
- {-0.05, M_PI / 2.0 + 0.1, 0.0, M_PI / 2.0},
-
- // Zeroing constants for wrist.
- {kZeroingSampleSize, kClawEncoderIndexDifference, 0.9, 0.3},
-
- 6.308141,
- kClawPistonSwitchTime,
- kClawZeroingRange},
-
- {// Elevator values, in meters.
- // 0 is the portion of the elevator carriage that Spencer removed
- // lining up with the bolt.
- // Positive is up.
- {-0.005, 0.689000, 0.010000, 0.680000},
-
- // Arm values, in radians.
- // 0 is sticking straight out horizontally over the intake/front.
- // Positive is rotating up and into the robot (towards the back).
- {-M_PI / 2 - 0.05, M_PI / 2 + 0.05, -M_PI / 2, M_PI / 2},
-
- // Elevator zeroing constants: left, right.
- {kZeroingSampleSize, kElevatorEncoderIndexDifference, 0.0, 0.3},
- {kZeroingSampleSize, kElevatorEncoderIndexDifference, 0.0, 0.3},
- // Arm zeroing constants: left, right.
- {kZeroingSampleSize, kArmEncoderIndexDifference, 0.0, 0.3},
- {kZeroingSampleSize, kArmEncoderIndexDifference, 0.0, 0.3},
- 0.7,
- -0.08,
- -3.5 - 0.01 - -0.02,
- 3.5 - 0.17 - -0.15,
-
- kArmZeroingHeight,
- kArmLength,
- },
- // End "sensor" values.
-
- kMaxAllowedLeftRightArmDifference,
- kMaxAllowedLeftRightElevatorDifference,
- kClawGeometry,
- };
- break;
- case kPracticeTeamNumber:
- return new Values{
- kDrivetrainEncoderRatio,
- kArmEncoderRatio,
- kArmPotRatio,
- kElevatorEncoderRatio,
- kElevatorPotRatio,
- kElevatorGearboxOutputRadianDistance,
- kClawEncoderRatio,
- kClawPotRatio,
- kToteHeight,
- kLowGearRatio,
- kHighGearRatio,
- kCompLeftDriveShifter,
- kCompRightDriveShifter,
- false,
- kRobotWidth,
- control_loops::MakeVelocityDrivetrainLoop,
- control_loops::MakeDrivetrainLoop,
- 0.02, // drivetrain done delta
- 5.0, // drivetrain max speed
-
- // Motion ranges: hard_lower_limit, hard_upper_limit,
- // soft_lower_limit, soft_upper_limit
- // TODO(sensors): Get actual bounds before turning on robot.
- {// Claw values, in radians.
- // 0 is level with the ground.
- // Positive moves in the direction of positive encoder values.
- {-0.05, M_PI / 2.0 + 0.1, 0.0, M_PI / 2.0},
-
- // Zeroing constants for wrist.
- {kZeroingSampleSize, kClawEncoderIndexDifference, 0.9104180000000001,
- 0.3},
-
- 6.308141,
- kClawPistonSwitchTime,
- kClawZeroingRange},
-
- {// Elevator values, in meters.
- // 0 is the portion of the elevator carriage that Spencer removed
- // lining up with the bolt.
- // Positive is up.
- {-0.00500, 0.689000, 0.010000, 0.680000},
-
- // Arm values, in radians.
- // 0 is sticking straight out horizontally over the intake/front.
- // Positive is rotating up and into the robot (towards the back).
- {-M_PI / 2 - 0.05, M_PI / 2 + 0.05, -M_PI / 2, M_PI / 2},
-
- // Elevator zeroing constants: left, right.
- {kZeroingSampleSize, kElevatorEncoderIndexDifference, 0.110677, 0.3}, // Was 0.088984 (3 mm too high)
- {kZeroingSampleSize, kElevatorEncoderIndexDifference, 0.109974, 0.3}, // Was 0.104557 (4 mm too low)
- // Arm zeroing constants: left, right.
- {kZeroingSampleSize, kArmEncoderIndexDifference, -0.324437, 0.3},
- {kZeroingSampleSize, kArmEncoderIndexDifference, -0.064683, 0.3},
- 0.722230 - -0.000594 - -0.026183 - 0.003442, // Left Elevator Poteniometer adjustment
- -0.081354 - -0.000374 - -0.024793 - -0.006916, // Right Elevator Poteniometer adjustment
- -3.509611 - 0.007415 - -0.019081,
- 3.506927 - 0.170017 - -0.147970,
-
- kArmZeroingHeight,
- kArmLength,
- },
- // End "sensor" values.
-
- kMaxAllowedLeftRightArmDifference,
- kMaxAllowedLeftRightElevatorDifference,
- kClawGeometry,
- };
- break;
- case kCompTeamNumber:
- return new Values{
- kDrivetrainEncoderRatio,
- kArmEncoderRatio,
- kArmPotRatio,
- kElevatorEncoderRatio,
- kElevatorPotRatio,
- kElevatorGearboxOutputRadianDistance,
- kClawEncoderRatio,
- kClawPotRatio,
- kToteHeight,
- kLowGearRatio,
- kHighGearRatio,
- kPracticeLeftDriveShifter,
- kPracticeRightDriveShifter,
- false,
- kRobotWidth,
- control_loops::MakeVelocityDrivetrainLoop,
- control_loops::MakeDrivetrainLoop,
- 0.02, // drivetrain done delta
- 5.0, // drivetrain max speed
-
- // Motion ranges: hard_lower_limit, hard_upper_limit,
- // soft_lower_limit, soft_upper_limit
- // TODO(sensors): Get actual bounds before turning on robot.
- {// Claw values, in radians.
- // 0 is level with the ground.
- // Positive moves in the direction of positive encoder values.
- {-0.05, M_PI / 2.0 + 0.1, 0.0, M_PI / 2.0},
-
- // Zeroing constants for wrist.
- // TODO(sensors): Get actual offsets for these.
- {kZeroingSampleSize, kClawEncoderIndexDifference, 0.952602, 0.3},
- 6.1663463999999992 + 0.015241,
-
- kClawPistonSwitchTime,
- kClawZeroingRange},
-
- {// Elevator values, in meters.
- // 0 is at the top of the elevator frame.
- // Positive is down towards the drivebase.
- {-0.00500, 0.689000, 0.010000, 0.680000},
-
- // Arm values, in radians.
- // 0 is sticking straight out horizontally over the intake/front.
- // Positive is rotating up and into the robot (towards the back).
- {-M_PI / 2 - 0.05, M_PI / 2 + 0.05, -M_PI / 2, M_PI / 2},
-
- // Elevator zeroing constants: left, right.
- // These are the encoder offsets.
- // TODO(sensors): Get actual offsets for these.
- {kZeroingSampleSize, kElevatorEncoderIndexDifference,
- 0.240286 - 0.007969 - 0.025, 0.3},
- {kZeroingSampleSize, kElevatorEncoderIndexDifference,
- 0.234583 - 0.000143, 0.3},
- // Arm zeroing constants: left, right.
- {kZeroingSampleSize, kArmEncoderIndexDifference, 0.060592, 0.3},
- {kZeroingSampleSize, kArmEncoderIndexDifference, 0.210155, 0.3},
- // These are the potentiometer offsets.
- 0.72069366666666679 - 0.026008 - 0.024948 + 0.025,
- -0.078959636363636357 - 0.024646 - 0.020260,
- -3.509611 - 0.007415 - -0.019081 - 0.029393 - -0.013585,
- 3.506927 - 0.170017 - -0.147970 - 0.005045 - -0.026504,
-
- kArmZeroingHeight,
- kArmLength,
- },
- // TODO(sensors): End "sensor" values.
-
- kMaxAllowedLeftRightArmDifference,
- kMaxAllowedLeftRightElevatorDifference,
- kClawGeometry,
- };
- break;
- default:
- LOG(FATAL, "unknown team #%" PRIu16 "\n", team);
- }
-}
-
-const Values *DoGetValues() {
- uint16_t team = ::aos::network::GetTeamNumber();
- LOG(INFO, "creating a Constants for team %" PRIu16 "\n", team);
- return DoGetValuesForTeam(team);
-}
-
-} // namespace
-
-const Values &GetValues() {
- static ::aos::Once<const Values> once(DoGetValues);
- return *once.Get();
-}
-
-const Values &GetValuesForTeam(uint16_t team_number) {
- static ::aos::Mutex mutex;
- ::aos::MutexLocker locker(&mutex);
-
- // IMPORTANT: This declaration has to stay after the mutex is locked to avoid
- // race conditions.
- static ::std::map<uint16_t, const Values *> values;
-
- if (values.count(team_number) == 0) {
- values[team_number] = DoGetValuesForTeam(team_number);
-#if __has_feature(address_sanitizer)
- __lsan_ignore_object(values[team_number]);
-#endif
- }
- return *values[team_number];
-}
-
-} // namespace constants
-} // namespace frc971
diff --git a/frc971/constants.h b/frc971/constants.h
index 0b6b725..890c63c 100644
--- a/frc971/constants.h
+++ b/frc971/constants.h
@@ -1,158 +1,21 @@
#ifndef FRC971_CONSTANTS_H_
#define FRC971_CONSTANTS_H_
-#include <stdint.h>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/shifter_hall_effect.h"
namespace frc971 {
namespace constants {
-// Has all of the numbers that change for both robots and makes it easy to
-// retrieve the values for the current one.
-
-// Everything is in SI units (volts, radians, meters, seconds, etc).
-// Some of these values are related to the conversion between raw values
-// (encoder counts, voltage, etc) to scaled units (radians, meters, etc).
-
-// This structure contains current values for all of the things that change.
-struct Values {
- // Drivetrain Values /////
-
- // The ratio from the encoder shaft to the drivetrain wheels.
- double drivetrain_encoder_ratio;
- // The ratio from the encoder shaft to the arm joint.
- double arm_encoder_ratio;
- // The ratio from the pot shaft to the arm joint.
- double arm_pot_ratio;
- // The ratio from the encoder shaft to the elevator output pulley.
- double elev_encoder_ratio;
- // The ratio from the pot shaft to the elevator output pulley.
- double elev_pot_ratio;
- // How far the elevator moves (meters) per radian on the output pulley.
- double elev_distance_per_radian;
- // The ratio from the encoder shaft to the claw joint.
- double claw_encoder_ratio;
- // The ratio from the pot shaft to the claw joint.
- double claw_pot_ratio;
-
- // How tall a tote is in meters.
- double tote_height;
-
- // The gear ratios from motor shafts to the drivetrain wheels for high and low
- // gear.
- double low_gear_ratio;
- double high_gear_ratio;
- ShifterHallEffect left_drive, right_drive;
- bool clutch_transmission;
-
- double turn_width;
-
- ::std::function<StateFeedbackLoop<2, 2, 2>()> make_v_drivetrain_loop;
- ::std::function<StateFeedbackLoop<4, 2, 2>()> make_drivetrain_loop;
-
- double drivetrain_done_distance;
- double drivetrain_max_speed;
-
- // Superstructure Values /////
-
- struct ZeroingConstants {
- // The number of samples in the moving average filter.
- int average_filter_size;
- // The difference in scaled units between two index pulses.
- double index_difference;
- // The absolute position in scaled units of one of the index pulses.
- double measured_index_position;
- // Value between 0 and 1 which determines a fraction of the index_diff
- // you want to use.
- double allowable_encoder_error;
- };
-
- // Defines a range of motion for a subsystem.
- // These are all absolute positions in scaled units.
- struct Range {
- double lower_hard_limit;
- double upper_hard_limit;
- double lower_limit;
- double upper_limit;
- };
-
- struct Claw {
- Range wrist;
- ZeroingConstants zeroing;
- // The value to add to potentiometer readings after they have been converted
- // to radians so that the resulting value is 0 when the claw is at absolute
- // 0 (horizontal straight out the front).
- double potentiometer_offset;
-
- // Time between sending commands to claw opening pistons and them reaching
- // the new state.
- double piston_switch_time;
- // How far on either side we look for the index pulse before we give up.
- double zeroing_range;
- };
- Claw claw;
-
- struct Fridge {
- Range elevator;
- Range arm;
-
- ZeroingConstants left_elev_zeroing;
- ZeroingConstants right_elev_zeroing;
- ZeroingConstants left_arm_zeroing;
- ZeroingConstants right_arm_zeroing;
-
- // Values to add to scaled potentiometer readings so 0 lines up with the
- // physical absolute 0.
- double left_elevator_potentiometer_offset;
- double right_elevator_potentiometer_offset;
- double left_arm_potentiometer_offset;
- double right_arm_potentiometer_offset;
-
- // How high the elevator has to be before we start zeroing the arm.
- double arm_zeroing_height;
-
- // The length of the arm, from the axis of the bottom pivot to the axis of
- // the top pivot.
- double arm_length;
- };
- Fridge fridge;
-
- double max_allowed_left_right_arm_difference;
- double max_allowed_left_right_elevator_difference;
-
- struct ClawGeometry {
- // Horizontal distance from the center of the grabber to the end.
- double grabber_half_length;
- // Vertical distance from the arm rotation center to the bottom of the
- // grabber. Distance measured with arm vertical (theta = 0).
- double grabber_delta_y;
- // Vertical separation of the claw and arm rotation centers with the
- // elevator at 0.0 and the arm angle set to zero.
- double grabber_arm_vert_separation;
- // Horizontal separation of the claw and arm rotation centers with the
- // elevator at 0.0 and the arm angle set to zero.
- double grabber_arm_horz_separation;
- // Distance between the center of the claw to the top of the claw.
- // The line drawn at this distance parallel to the claw centerline is used
- // to determine if claw interfears with the grabber.
- double claw_top_thickness;
- // The grabber is safe at any height if it is behind this location.
- double grabber_always_safe_h_min;
- // The grabber is safe at any x if it is above this location.
- double grabber_always_safe_x_max;
- };
- ClawGeometry clawGeometry;
+struct ZeroingConstants {
+ // The number of samples in the moving average filter.
+ int average_filter_size;
+ // The difference in scaled units between two index pulses.
+ double index_difference;
+ // The absolute position in scaled units of one of the index pulses.
+ double measured_index_position;
+ // Value between 0 and 1 which determines a fraction of the index_diff
+ // you want to use.
+ double allowable_encoder_error;
};
-// Creates (once) a Values instance for ::aos::network::GetTeamNumber() and
-// returns a reference to it.
-const Values &GetValues();
-
-// Creates Values instances for each team number it is called with and returns
-// them.
-const Values &GetValuesForTeam(uint16_t team_number);
-
} // namespace constants
} // namespace frc971
diff --git a/frc971/control_loops/claw/claw.cc b/frc971/control_loops/claw/claw.cc
deleted file mode 100644
index 068836c..0000000
--- a/frc971/control_loops/claw/claw.cc
+++ /dev/null
@@ -1,311 +0,0 @@
-#include "frc971/control_loops/claw/claw.h"
-
-#include <algorithm>
-
-#include "aos/common/controls/control_loops.q.h"
-#include "aos/common/logging/logging.h"
-
-#include "frc971/constants.h"
-#include "frc971/control_loops/claw/claw_motor_plant.h"
-#include "aos/common/util/trapezoid_profile.h"
-
-namespace frc971 {
-namespace control_loops {
-
-using ::aos::time::Time;
-
-constexpr double kZeroingVoltage = 4.0;
-
-void ClawCappedStateFeedbackLoop::CapU() {
- mutable_U(0, 0) = ::std::min(mutable_U(0, 0), max_voltage_);
- mutable_U(0, 0) = ::std::max(mutable_U(0, 0), -max_voltage_);
-}
-
-double ClawCappedStateFeedbackLoop::UnsaturateOutputGoalChange() {
- // Compute K matrix to compensate for position errors.
- double Kp = K(0, 0);
-
- // Compute how much we need to change R in order to achieve the change in U
- // that was observed.
- return -(1.0 / Kp) * (U_uncapped() - U())(0, 0);
-}
-
-Claw::Claw(control_loops::ClawQueue *claw)
- : aos::controls::ControlLoop<control_loops::ClawQueue>(claw),
- last_piston_edge_(Time::Now()),
- claw_loop_(new ClawCappedStateFeedbackLoop(MakeClawLoop())),
- claw_estimator_(constants::GetValues().claw.zeroing),
- profile_(::aos::controls::kLoopFrequency) {}
-
-void Claw::UpdateZeroingState() {
- if (claw_estimator_.offset_ratio_ready() < 1.0) {
- state_ = INITIALIZING;
- } else if (!claw_estimator_.zeroed()) {
- state_ = ZEROING;
- } else {
- state_ = RUNNING;
- }
-}
-
-void Claw::Correct() {
- Eigen::Matrix<double, 1, 1> Y;
- Y << claw_position();
- claw_loop_->Correct(Y);
-}
-
-void Claw::SetClawOffset(double offset) {
- LOG(INFO, "Changing claw offset from %f to %f.\n", claw_offset_, offset);
- const double doffset = offset - claw_offset_;
-
- // Adjust the height. The derivative should not need to be updated since the
- // speed is not changing.
- claw_loop_->mutable_X_hat(0, 0) += doffset;
-
- // Modify claw zeroing goal.
- claw_goal_ += doffset;
- // Update the cached offset value to the actual value.
- claw_offset_ = offset;
-}
-
-double Claw::estimated_claw_position() const {
- return current_position_.joint.encoder + claw_estimator_.offset();
-}
-
-double Claw::claw_position() const {
- return current_position_.joint.encoder + claw_offset_;
-}
-
-constexpr double kClawZeroingVelocity = 0.2;
-
-double Claw::claw_zeroing_velocity() {
- const auto &values = constants::GetValues();
-
- // Zeroing will work as following. At startup, record the offset of the claw.
- // Then, start moving the claw towards where the index pulse should be. We
- // search around it a little, and if we don't find anything, we estop.
- // Otherwise, we're done.
-
- const double target_pos = values.claw.zeroing.measured_index_position;
- // How far away we need to stay from the ends of the range while zeroing.
- constexpr double zeroing_limit = 0.1375;
- // Keep the zeroing range within the bounds of the mechanism.
- const double zeroing_range =
- ::std::min(target_pos - values.claw.wrist.lower_limit - zeroing_limit,
- values.claw.zeroing_range);
-
- if (claw_zeroing_velocity_ == 0) {
- if (estimated_claw_position() > target_pos) {
- claw_zeroing_velocity_ = -kClawZeroingVelocity;
- } else {
- claw_zeroing_velocity_ = kClawZeroingVelocity;
- }
- } else if (claw_zeroing_velocity_ > 0 &&
- estimated_claw_position() > target_pos + zeroing_range) {
- claw_zeroing_velocity_ = -kClawZeroingVelocity;
- } else if (claw_zeroing_velocity_ < 0 &&
- estimated_claw_position() < target_pos - zeroing_range) {
- claw_zeroing_velocity_ = kClawZeroingVelocity;
- }
-
- return claw_zeroing_velocity_;
-}
-
-void Claw::RunIteration(const control_loops::ClawQueue::Goal *unsafe_goal,
- const control_loops::ClawQueue::Position *position,
- control_loops::ClawQueue::Output *output,
- control_loops::ClawQueue::Status *status) {
- const auto &values = constants::GetValues();
-
- if (WasReset()) {
- LOG(ERROR, "WPILib reset! Restarting.\n");
- claw_estimator_.Reset();
- state_ = UNINITIALIZED;
- }
-
- current_position_ = *position;
-
- // Bool to track if we should turn the motor on or not.
- bool disable = output == nullptr;
- double claw_goal_velocity = 0.0;
-
- claw_estimator_.UpdateEstimate(position->joint);
-
- if (state_ != UNINITIALIZED) {
- Correct();
- }
-
- switch (state_) {
- case UNINITIALIZED:
- LOG(INFO, "Uninitialized.\n");
- // Startup. Assume that we are at the origin.
- claw_offset_ = -position->joint.encoder;
- claw_loop_->mutable_X_hat().setZero();
- Correct();
- state_ = INITIALIZING;
- disable = true;
- break;
-
- case INITIALIZING:
- LOG(INFO, "Waiting for accurate initial position.\n");
- disable = true;
- // Update state_ to accurately represent the state of the zeroing
- // estimator.
- UpdateZeroingState();
-
- if (state_ != INITIALIZING) {
- // Set the goals to where we are now.
- claw_goal_ = claw_position();
- }
- break;
-
- case ZEROING:
- LOG(DEBUG, "Zeroing.\n");
-
- // Update state_.
- UpdateZeroingState();
- if (claw_estimator_.zeroed()) {
- LOG(INFO, "Zeroed!\n");
- SetClawOffset(claw_estimator_.offset());
- } else if (!disable) {
- claw_goal_velocity = claw_zeroing_velocity();
- claw_goal_ +=
- claw_goal_velocity * ::aos::controls::kLoopFrequency.ToSeconds();
- }
-
- // Clear the current profile state if we are zeroing.
- {
- Eigen::Matrix<double, 2, 1> current;
- current.setZero();
- current << claw_goal_, claw_goal_velocity;
- profile_.MoveCurrentState(current);
- }
- break;
-
- case RUNNING:
- LOG(DEBUG, "Running!\n");
-
- // Update state_.
- UpdateZeroingState();
- if (unsafe_goal) {
- // Pick a set of sane defaults if none are specified.
- if (unsafe_goal->max_velocity != 0.0) {
- profile_.set_maximum_velocity(unsafe_goal->max_velocity);
- } else {
- profile_.set_maximum_velocity(2.5);
- }
- if (unsafe_goal->max_acceleration != 0.0) {
- profile_.set_maximum_acceleration(unsafe_goal->max_acceleration);
- } else {
- profile_.set_maximum_acceleration(4.0);
- }
-
- const double unfiltered_goal = ::std::max(
- ::std::min(unsafe_goal->angle, values.claw.wrist.upper_limit),
- values.claw.wrist.lower_limit);
- ::Eigen::Matrix<double, 2, 1> goal_state =
- profile_.Update(unfiltered_goal, unsafe_goal->angular_velocity);
- claw_goal_ = goal_state(0, 0);
- claw_goal_velocity = goal_state(1, 0);
- }
-
- if (state_ != RUNNING && state_ != ESTOP) {
- state_ = UNINITIALIZED;
- }
- break;
-
- case ESTOP:
- LOG(ERROR, "Estop!\n");
- disable = true;
- break;
- }
-
- // Make sure goal and position do not exceed the hardware limits if we are
- // RUNNING.
- if (state_ == RUNNING) {
- // Limit goal.
- claw_goal_ = ::std::min(claw_goal_, values.claw.wrist.upper_limit);
- claw_goal_ = ::std::max(claw_goal_, values.claw.wrist.lower_limit);
-
- // Check position.
- if (claw_position() >= values.claw.wrist.upper_hard_limit ||
- claw_position() <= values.claw.wrist.lower_hard_limit) {
- LOG(ERROR, "Claw at %f out of bounds [%f, %f].\n", claw_position(),
- values.claw.wrist.lower_limit, values.claw.wrist.upper_limit);
- }
- }
-
- // Set the goals.
- claw_loop_->mutable_R() << claw_goal_, claw_goal_velocity;
-
- const double max_voltage = (state_ == RUNNING) ? 12.0 : kZeroingVoltage;
- claw_loop_->set_max_voltage(max_voltage);
-
- if (state_ == ESTOP) {
- disable = true;
- }
- claw_loop_->Update(disable);
-
- if (state_ == INITIALIZING || state_ == ZEROING) {
- if (claw_loop_->U() != claw_loop_->U_uncapped()) {
- double deltaR = claw_loop_->UnsaturateOutputGoalChange();
-
- // Move the claw goal by the amount observed.
- LOG(WARNING, "Moving claw goal by %f to handle saturation.\n", deltaR);
- claw_goal_ += deltaR;
- }
- }
-
- if (output) {
- output->voltage = claw_loop_->U(0, 0);
- if (state_ != RUNNING) {
- output->intake_voltage = 0.0;
- output->rollers_closed = false;
- } else {
- if (unsafe_goal) {
- output->intake_voltage = unsafe_goal->intake;
- output->rollers_closed = unsafe_goal->rollers_closed;
- } else {
- output->intake_voltage = 0.0;
- output->rollers_closed = false;
- }
- }
- if (output->rollers_closed != last_rollers_closed_) {
- last_piston_edge_ = Time::Now();
- }
- }
-
- status->zeroed = state_ == RUNNING;
- status->estopped = state_ == ESTOP;
- status->state = state_;
- zeroing::PopulateEstimatorState(claw_estimator_, &status->zeroing_state);
-
- status->angle = claw_loop_->X_hat(0, 0);
- status->angular_velocity = claw_loop_->X_hat(1, 0);
-
- if (output) {
- status->intake = output->intake_voltage;
- } else {
- status->intake = 0;
- }
- status->goal_angle = claw_goal_;
- status->goal_velocity = claw_goal_velocity;
-
- if (output) {
- status->rollers_open =
- !output->rollers_closed &&
- (Time::Now() - last_piston_edge_ >= values.claw.piston_switch_time);
- status->rollers_closed =
- output->rollers_closed &&
- (Time::Now() - last_piston_edge_ >= values.claw.piston_switch_time);
- } else {
- status->rollers_open = false;
- status->rollers_closed = false;
- }
-
- if (output) {
- last_rollers_closed_ = output->rollers_closed;
- }
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/claw/claw.gyp b/frc971/control_loops/claw/claw.gyp
deleted file mode 100644
index 40fe95d..0000000
--- a/frc971/control_loops/claw/claw.gyp
+++ /dev/null
@@ -1,89 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'replay_claw',
- 'type': 'executable',
- 'variables': {
- 'no_rsync': 1,
- },
- 'sources': [
- 'replay_claw.cc',
- ],
- 'dependencies': [
- 'claw_queue',
- '<(AOS)/common/controls/controls.gyp:replay_control_loop',
- '<(AOS)/linux_code/linux_code.gyp:init',
- ],
- },
- {
- 'target_name': 'claw_queue',
- 'type': 'static_library',
- 'sources': ['claw.q'],
- 'variables': {
- 'header_path': 'frc971/control_loops/claw',
- },
- 'dependencies': [
- '<(AOS)/common/controls/controls.gyp:control_loop_queues',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/controls/controls.gyp:control_loop_queues',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
-
- ],
- 'includes': ['../../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'claw_lib',
- 'type': 'static_library',
- 'sources': [
- 'claw.cc',
- 'claw_motor_plant.cc',
- ],
- 'dependencies': [
- 'claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/common/util/util.gyp:trapezoid_profile',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
- ],
- 'export_dependent_settings': [
- 'claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/common/util/util.gyp:trapezoid_profile',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
- ],
- },
- {
- 'target_name': 'claw_lib_test',
- 'type': 'executable',
- 'sources': [
- 'claw_lib_test.cc',
- ],
- 'dependencies': [
- '<(EXTERNALS):gtest',
- 'claw_lib',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(AOS)/common/controls/controls.gyp:control_loop_test',
- '<(AOS)/common/common.gyp:time',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:position_sensor_sim',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
- ],
- },
- {
- 'target_name': 'claw',
- 'type': 'executable',
- 'sources': [
- 'claw_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- 'claw_lib',
- ],
- },
- ],
-}
diff --git a/frc971/control_loops/claw/claw.h b/frc971/control_loops/claw/claw.h
deleted file mode 100644
index 0413b8d..0000000
--- a/frc971/control_loops/claw/claw.h
+++ /dev/null
@@ -1,116 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_CLAW_H_
-#define FRC971_CONTROL_LOOPS_CLAW_H_
-
-#include <memory>
-
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/time.h"
-#include "aos/common/util/trapezoid_profile.h"
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/claw/claw.q.h"
-#include "frc971/control_loops/claw/claw_motor_plant.h"
-#include "frc971/zeroing/zeroing.h"
-
-namespace frc971 {
-namespace control_loops {
-namespace testing {
-class ClawTest_DisabledGoal_Test;
-class ClawTest_GoalPositiveWindup_Test;
-class ClawTest_GoalNegativeWindup_Test;
-} // namespace testing
-
-class ClawCappedStateFeedbackLoop : public StateFeedbackLoop<2, 1, 1> {
- public:
- ClawCappedStateFeedbackLoop(StateFeedbackLoop<2, 1, 1> &&loop)
- : StateFeedbackLoop<2, 1, 1>(::std::move(loop)), max_voltage_(12.0) {}
-
- void set_max_voltage(double max_voltage) {
- max_voltage_ = ::std::max(0.0, ::std::min(12.0, max_voltage));
- }
-
- void CapU() override;
-
- // Returns the amount to change the position goal in order to no longer
- // saturate the controller.
- double UnsaturateOutputGoalChange();
-
- private:
- double max_voltage_;
-};
-
-class Claw : public aos::controls::ControlLoop<control_loops::ClawQueue> {
- public:
- enum State {
- // Waiting to receive data before doing anything.
- UNINITIALIZED = 0,
- // Estimating the starting location.
- INITIALIZING = 1,
- // Moving to find an index pulse.
- ZEROING = 2,
- // Normal operation.
- RUNNING = 3,
- // Internal error caused the claw to abort.
- ESTOP = 4,
- };
-
- int state() { return state_; }
-
- explicit Claw(
- control_loops::ClawQueue *claw_queue = &control_loops::claw_queue);
-
- protected:
- virtual void RunIteration(const control_loops::ClawQueue::Goal *goal,
- const control_loops::ClawQueue::Position *position,
- control_loops::ClawQueue::Output *output,
- control_loops::ClawQueue::Status *status);
-
- private:
- friend class testing::ClawTest_DisabledGoal_Test;
- friend class testing::ClawTest_GoalPositiveWindup_Test;
- friend class testing::ClawTest_GoalNegativeWindup_Test;
-
- // Sets state_ to the correct state given the current state of the zeroing
- // estimator.
- void UpdateZeroingState();
- void SetClawOffset(double offset);
- // Corrects the Observer with the current position.
- void Correct();
-
- // Getter for the current claw position.
- double claw_position() const;
- // Our best guess at the current position of the claw.
- double estimated_claw_position() const;
- // Returns the current zeroing velocity for the claw. If the subsystem is too
- // far away from the center, it will switch directions.
- double claw_zeroing_velocity();
-
- State state_ = UNINITIALIZED;
-
- // The time when we last changed the claw piston state.
- ::aos::time::Time last_piston_edge_;
-
- // The state feedback control loop to talk to.
- ::std::unique_ptr<ClawCappedStateFeedbackLoop> claw_loop_;
-
- // Latest position from queue.
- control_loops::ClawQueue::Position current_position_;
- // Zeroing estimator for claw.
- zeroing::ZeroingEstimator claw_estimator_;
-
- // The goal for the claw.
- double claw_goal_ = 0.0;
- // Current velocity to move at while zeroing.
- double claw_zeroing_velocity_ = 0.0;
- // Offsets from the encoder position to the absolute position.
- double claw_offset_ = 0.0;
-
- // Whether claw was closed last cycle.
- bool last_rollers_closed_ = false;
-
- ::aos::util::TrapezoidProfile profile_;
-};
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_CLAW_H_
diff --git a/frc971/control_loops/claw/claw.q b/frc971/control_loops/claw/claw.q
deleted file mode 100644
index 8da1c20..0000000
--- a/frc971/control_loops/claw/claw.q
+++ /dev/null
@@ -1,81 +0,0 @@
-package frc971.control_loops;
-
-import "aos/common/controls/control_loops.q";
-import "frc971/control_loops/control_loops.q";
-
-queue_group ClawQueue {
- implements aos.control_loops.ControlLoop;
-
- // All angles are in radians with 0 sticking straight out the front. Rotating
- // up and into the robot is positive. Positive output voltage moves in the
- // direction of positive encoder values.
-
- message Goal {
- // Angle of wrist joint.
- double angle;
- // Angular velocity of wrist.
- float angular_velocity;
- // Maximum profile velocity, or 0 for the default.
- float max_velocity;
- // Maximum profile acceleration, or 0 for the default.
- float max_acceleration;
- // Voltage of intake rollers. Positive means sucking in, negative means
- // spitting out.
- double intake;
-
- // true to signal the rollers to close.
- bool rollers_closed;
- };
-
- message Position {
- PotAndIndexPosition joint;
- };
-
- message Output {
- // Voltage for intake motors. Positive is sucking in, negative is spitting
- // out.
- double intake_voltage;
- // Voltage for claw motor.
- double voltage;
-
- // true to signal the rollers to close.
- bool rollers_closed;
- };
-
- message Status {
- // Is claw zeroed?
- bool zeroed;
- // Did the claw estop?
- bool estopped;
- // The internal state of the claw state machine.
- uint32_t state;
- EstimatorState zeroing_state;
-
- // Estimated angle of wrist joint.
- double angle;
- // Estimated angular velocity of wrist.
- float angular_velocity;
-
- // Goal angle of wrist joint.
- double goal_angle;
- float goal_velocity;
- // Voltage of intake rollers. Positive means sucking in, negative means
- // spitting out.
- double intake;
-
- // True iff there has been enough time since we actuated the rollers outward
- // that they should be there.
- bool rollers_open;
- // True iff there has been enough time since we actuated the rollers closed
- // that they should be there.
- bool rollers_closed;
- };
-
- queue Goal goal;
- queue Position position;
- queue Output output;
- queue Status status;
-};
-
-queue_group ClawQueue claw_queue;
-
diff --git a/frc971/control_loops/claw/claw_lib_test.cc b/frc971/control_loops/claw/claw_lib_test.cc
deleted file mode 100644
index e53c0ed..0000000
--- a/frc971/control_loops/claw/claw_lib_test.cc
+++ /dev/null
@@ -1,347 +0,0 @@
-#include <math.h>
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/queue.h"
-#include "aos/common/time.h"
-#include "aos/common/controls/control_loop_test.h"
-#include "frc971/control_loops/claw/claw.q.h"
-#include "frc971/control_loops/claw/claw.h"
-#include "frc971/control_loops/position_sensor_sim.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/team_number_test_environment.h"
-
-using ::aos::time::Time;
-
-namespace frc971 {
-namespace control_loops {
-namespace testing {
-
-// Class which simulates the claw and sends out queue messages with the
-// position.
-class ClawSimulation {
- public:
- // Constructs a claw simulation.
- ClawSimulation()
- : claw_plant_(new StateFeedbackPlant<2, 1, 1>(MakeClawPlant())),
- pot_and_encoder_(constants::GetValues().claw.zeroing.index_difference),
- claw_queue_(".frc971.control_loops.claw_queue", 0x9d7452fb,
- ".frc971.control_loops.claw_queue.goal",
- ".frc971.control_loops.claw_queue.position",
- ".frc971.control_loops.claw_queue.output",
- ".frc971.control_loops.claw_queue.status") {
- InitializePosition(constants::GetValues().claw.wrist.lower_limit);
- }
-
- void InitializePosition(double start_pos) {
- InitializePosition(start_pos,
- constants::GetValues().claw.zeroing.measured_index_position);
- }
-
- void InitializePosition(double start_pos, double index_pos) {
- InitializePosition(start_pos,
- // This gives us a standard deviation of ~9 degrees on the pot noise.
- constants::GetValues().claw.zeroing.index_difference / 10.0,
- index_pos);
- }
-
- // Do specific initialization for the sensors.
- void InitializePosition(double start_pos,
- double pot_noise_stddev,
- double index_pos) {
- // Update internal state.
- claw_plant_->mutable_X(0, 0) = start_pos;
- // Zero velocity.
- claw_plant_->mutable_X(1, 0) = 0.0;
-
- pot_and_encoder_.Initialize(start_pos, pot_noise_stddev, index_pos);
- }
-
- // Sends a queue message with the position.
- void SendPositionMessage() {
- ::aos::ScopedMessagePtr<control_loops::ClawQueue::Position> position =
- claw_queue_.position.MakeMessage();
- pot_and_encoder_.GetSensorValues(&position->joint);
- position.Send();
- }
-
- // Simulates for a single timestep.
- void Simulate() {
- EXPECT_TRUE(claw_queue_.output.FetchLatest());
-
- // Feed voltages into physics simulation.
- claw_plant_->mutable_U() << claw_queue_.output->voltage;
- claw_plant_->Update();
-
- const double wrist_angle = claw_plant_->Y(0, 0);
-
- // TODO(danielp): Sanity checks.
-
- pot_and_encoder_.MoveTo(wrist_angle);
- }
-
- private:
- ::std::unique_ptr<StateFeedbackPlant<2, 1, 1>> claw_plant_;
- PositionSensorSimulator pot_and_encoder_;
-
- ClawQueue claw_queue_;
-};
-
-class ClawTest : public ::aos::testing::ControlLoopTest {
- protected:
- ClawTest()
- : claw_queue_(".frc971.control_loops.claw_queue", 0x9d7452fb,
- ".frc971.control_loops.claw_queue.goal",
- ".frc971.control_loops.claw_queue.position",
- ".frc971.control_loops.claw_queue.output",
- ".frc971.control_loops.claw_queue.status"),
- claw_(&claw_queue_),
- claw_plant_() {
- set_team_id(kTeamNumber);
- }
-
- void VerifyNearGoal() {
- claw_queue_.goal.FetchLatest();
- claw_queue_.status.FetchLatest();
- EXPECT_NEAR(claw_queue_.goal->angle,
- claw_queue_.status->angle,
- 10.0);
-
- EXPECT_TRUE(claw_queue_.status->zeroed);
- EXPECT_FALSE(claw_queue_.status->estopped);
- }
-
- // Runs one iteration of the whole simulation.
- void RunIteration(bool enabled = true) {
- SendMessages(enabled);
-
- claw_plant_.SendPositionMessage();
- claw_.Iterate();
- claw_plant_.Simulate();
-
- TickTime();
- }
-
- // Runs iterations until the specified amount of simulated time has elapsed.
- void RunForTime(const Time &run_for, bool enabled = true) {
- const auto start_time = Time::Now();
- while (Time::Now() < start_time + run_for) {
- RunIteration(enabled);
- }
- }
-
- // Create a new instance of the test queue so that it invalidates the queue
- // that it points to. Otherwise, we will have a pointed to
- // shared memory that is no longer valid.
- ClawQueue claw_queue_;
-
- // Create a control loop and simulation.
- Claw claw_;
- ClawSimulation claw_plant_;
-};
-
-// Tests that the loop does nothing when the goal is our lower limit.
-TEST_F(ClawTest, DoesNothing) {
- const auto &values = constants::GetValues();
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(values.claw.wrist.lower_limit)
- .Send());
-
- RunForTime(Time::InSeconds(6));
-
- // We should not have moved.
- VerifyNearGoal();
-}
-
-// NOTE: Claw zeroing is a little annoying because we only hit one index pulse
-// in our entire range of motion.
-
-// Tests that the loop zeroing works with normal values.
-TEST_F(ClawTest, Zeroes) {
- // It should zero itself if we run it for awhile.
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- RunForTime(Time::InSeconds(6));
-
- ASSERT_TRUE(claw_queue_.status.FetchLatest());
- EXPECT_TRUE(claw_queue_.status->zeroed);
- EXPECT_EQ(Claw::RUNNING, claw_queue_.status->state);
-}
-
-// Tests that claw zeroing fails if the index pulse occurs too close to the end
-// of the range.
-TEST_F(ClawTest, BadIndexPosition) {
- const auto values = constants::GetValues();
- claw_plant_.InitializePosition(values.claw.wrist.lower_limit,
- values.claw.wrist.upper_limit);
-
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- // The zeroing is going to take its sweet time on this one, so we had better
- // run it for longer.
- RunForTime(Time::InMS(12000));
-
- ASSERT_TRUE(claw_queue_.status.FetchLatest());
- EXPECT_FALSE(claw_queue_.status->zeroed);
- EXPECT_FALSE(claw_queue_.status->estopped);
-}
-
-// Tests that we can reach a reasonable goal.
-TEST_F(ClawTest, ReachesGoal) {
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- RunForTime(Time::InSeconds(6));
-
- VerifyNearGoal();
-}
-
-// Tests that it doesn't try to move past the physical range of the mechanism.
-TEST_F(ClawTest, RespectsRange) {
- const auto &values = constants::GetValues();
- // Upper limit
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(values.claw.wrist.upper_hard_limit + 5.0)
- .Send());
-
- RunForTime(Time::InSeconds(7));
-
- claw_queue_.status.FetchLatest();
- EXPECT_NEAR(values.claw.wrist.upper_limit,
- claw_queue_.status->angle,
- 2.0 * M_PI / 180.0);
-
- // Lower limit.
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(values.claw.wrist.lower_hard_limit - 5.0)
- .Send());
-
- RunForTime(Time::InMS(6000));
-
- claw_queue_.status.FetchLatest();
- EXPECT_NEAR(values.claw.wrist.lower_limit,
- claw_queue_.status->angle,
- 2.0 * M_PI / 180.0);
-}
-
-// Tests that starting at the lower hardstop doesn't cause an abort.
-TEST_F(ClawTest, LowerHardstopStartup) {
- claw_plant_.InitializePosition(
- constants::GetValues().claw.wrist.lower_hard_limit);
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
- RunForTime(Time::InSeconds(6));
-
- VerifyNearGoal();
-}
-
-// Tests that starting at the upper hardstop doesn't cause an abort.
-TEST_F(ClawTest, UpperHardstopStartup) {
- claw_plant_.InitializePosition(
- constants::GetValues().claw.wrist.upper_hard_limit);
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
- // Zeroing will take a long time here.
- RunForTime(Time::InSeconds(15));
-
- VerifyNearGoal();
-}
-
-
-// Tests that not having a goal doesn't break anything.
-TEST_F(ClawTest, NoGoal) {
- RunForTime(Time::InMS(50));
-}
-
-// Tests that a WPILib reset results in rezeroing.
-TEST_F(ClawTest, WpilibReset) {
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- RunForTime(Time::InSeconds(6));
- VerifyNearGoal();
-
- SimulateSensorReset();
- RunForTime(Time::InMS(100));
- ASSERT_TRUE(claw_queue_.status.FetchLatest());
- EXPECT_NE(Claw::RUNNING, claw_queue_.status->state);
-
- // Once again, it's going to take us awhile to rezero since we moved away from
- // our index pulse.
- RunForTime(Time::InSeconds(6));
- VerifyNearGoal();
-}
-
-// Tests that internal goals don't change while disabled.
-TEST_F(ClawTest, DisabledGoal) {
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- RunForTime(Time::InMS(100), false);
- EXPECT_EQ(0.0, claw_.claw_goal_);
-
- // Now make sure they move correctly.
- RunForTime(Time::InMS(1000), true);
- EXPECT_NE(0.0, claw_.claw_goal_);
-}
-
-// Tests that the claw zeroing goals don't wind up too far.
-TEST_F(ClawTest, GoalPositiveWindup) {
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- while (claw_.state() != Claw::ZEROING) {
- RunIteration();
- }
-
- // Kick it.
- RunForTime(Time::InMS(50));
- const double orig_claw_goal = claw_.claw_goal_;
- claw_.claw_goal_ += 100.0;
-
- RunIteration();
- EXPECT_NEAR(orig_claw_goal, claw_.claw_goal_, 0.10);
-
- RunIteration();
-
- EXPECT_EQ(claw_.claw_loop_->U(), claw_.claw_loop_->U_uncapped());
-}
-
-// Tests that the claw zeroing goals don't wind up too far.
-TEST_F(ClawTest, GoalNegativeWindup) {
- ASSERT_TRUE(claw_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .Send());
-
- while (claw_.state() != Claw::ZEROING) {
- RunIteration();
- }
-
- // Kick it.
- RunForTime(Time::InMS(50));
- double orig_claw_goal = claw_.claw_goal_;
- claw_.claw_goal_ -= 100.0;
-
- RunIteration();
- EXPECT_NEAR(orig_claw_goal, claw_.claw_goal_, 0.10);
-
- RunIteration();
-
- EXPECT_EQ(claw_.claw_loop_->U(), claw_.claw_loop_->U_uncapped());
-}
-
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/claw/claw_main.cc b/frc971/control_loops/claw/claw_main.cc
deleted file mode 100644
index bf25a03..0000000
--- a/frc971/control_loops/claw/claw_main.cc
+++ /dev/null
@@ -1,11 +0,0 @@
-#include "frc971/control_loops/claw/claw.h"
-
-#include "aos/linux_code/init.h"
-
-int main() {
- ::aos::Init();
- frc971::control_loops::Claw claw;
- claw.Run();
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/control_loops/claw/claw_motor_plant.cc b/frc971/control_loops/claw/claw_motor_plant.cc
deleted file mode 100644
index b95bf12..0000000
--- a/frc971/control_loops/claw/claw_motor_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "frc971/control_loops/claw/claw_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 1, 1> MakeClawPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 1.0, 0.00482455476758, 0.0, 0.930652495326;
- Eigen::Matrix<double, 2, 1> B;
- B << 6.97110924671e-05, 0.0275544125308;
- Eigen::Matrix<double, 1, 2> C;
- C << 1, 0;
- Eigen::Matrix<double, 1, 1> D;
- D << 0;
- Eigen::Matrix<double, 1, 1> U_max;
- U_max << 12.0;
- Eigen::Matrix<double, 1, 1> U_min;
- U_min << -12.0;
- return StateFeedbackPlantCoefficients<2, 1, 1>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<2, 1, 1> MakeClawController() {
- Eigen::Matrix<double, 2, 1> L;
- L << 0.998251427366, 26.9874526231;
- Eigen::Matrix<double, 1, 2> K;
- K << 74.4310031124, 4.72251126222;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.0, -0.00518405612386, 0.0, 1.07451492907;
- return StateFeedbackController<2, 1, 1>(L, K, A_inv, MakeClawPlantCoefficients());
-}
-
-StateFeedbackPlant<2, 1, 1> MakeClawPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>> plants(1);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 1, 1>>(new StateFeedbackPlantCoefficients<2, 1, 1>(MakeClawPlantCoefficients()));
- return StateFeedbackPlant<2, 1, 1>(&plants);
-}
-
-StateFeedbackLoop<2, 1, 1> MakeClawLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 1, 1>>> controllers(1);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 1, 1>>(new StateFeedbackController<2, 1, 1>(MakeClawController()));
- return StateFeedbackLoop<2, 1, 1>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/claw/claw_motor_plant.h b/frc971/control_loops/claw/claw_motor_plant.h
deleted file mode 100644
index 1502be3..0000000
--- a/frc971/control_loops/claw/claw_motor_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
-#define FRC971_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 1, 1> MakeClawPlantCoefficients();
-
-StateFeedbackController<2, 1, 1> MakeClawController();
-
-StateFeedbackPlant<2, 1, 1> MakeClawPlant();
-
-StateFeedbackLoop<2, 1, 1> MakeClawLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_CLAW_CLAW_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/claw/replay_claw.cc b/frc971/control_loops/claw/replay_claw.cc
deleted file mode 100644
index 00d3c6d..0000000
--- a/frc971/control_loops/claw/replay_claw.cc
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "aos/common/controls/replay_control_loop.h"
-#include "aos/linux_code/init.h"
-
-#include "frc971/control_loops/claw/claw.q.h"
-
-// Reads one or more log files and sends out all the queue messages (in the
-// correct order and at the correct time) to feed a "live" claw process.
-
-int main(int argc, char **argv) {
- if (argc <= 1) {
- fprintf(stderr, "Need at least one file to replay!\n");
- return EXIT_FAILURE;
- }
-
- ::aos::InitNRT();
-
- ::aos::controls::ControlLoopReplayer<::frc971::control_loops::ClawQueue>
- replayer(&::frc971::control_loops::claw_queue, "claw");
- for (int i = 1; i < argc; ++i) {
- replayer.ProcessFile(argv[i]);
- }
-
- ::aos::Cleanup();
-}
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
deleted file mode 100644
index 03e0db8..0000000
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ /dev/null
@@ -1,777 +0,0 @@
-#include "frc971/control_loops/drivetrain/drivetrain.h"
-
-#include <stdio.h>
-#include <sched.h>
-#include <cmath>
-#include <memory>
-#include "Eigen/Dense"
-
-#include "aos/common/logging/logging.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/commonmath.h"
-#include "aos/common/logging/queue_logging.h"
-#include "aos/common/logging/matrix_logging.h"
-
-#include "frc971/constants.h"
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/coerce_goal.h"
-#include "frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/queues/gyro.q.h"
-#include "frc971/shifter_hall_effect.h"
-
-// A consistent way to mark code that goes away without shifters. It's still
-// here because we will have shifters again in the future.
-#define HAVE_SHIFTERS 0
-
-using frc971::sensors::gyro_reading;
-
-namespace frc971 {
-namespace control_loops {
-
-class DrivetrainMotorsSS {
- public:
- class LimitedDrivetrainLoop : public StateFeedbackLoop<4, 2, 2> {
- public:
- LimitedDrivetrainLoop(StateFeedbackLoop<4, 2, 2> &&loop)
- : StateFeedbackLoop<4, 2, 2>(::std::move(loop)),
- U_Poly_((Eigen::Matrix<double, 4, 2>() << 1, 0,
- -1, 0,
- 0, 1,
- 0, -1).finished(),
- (Eigen::Matrix<double, 4, 1>() << 12.0, 12.0,
- 12.0, 12.0).finished()) {
- ::aos::controls::HPolytope<0>::Init();
- T << 1, -1, 1, 1;
- T_inverse = T.inverse();
- }
-
- bool output_was_capped() const {
- return output_was_capped_;
- }
-
- private:
- virtual void CapU() {
- const Eigen::Matrix<double, 4, 1> error = R() - X_hat();
-
- if (::std::abs(U(0, 0)) > 12.0 || ::std::abs(U(1, 0)) > 12.0) {
- mutable_U() =
- U() * 12.0 / ::std::max(::std::abs(U(0, 0)), ::std::abs(U(1, 0)));
- LOG_MATRIX(DEBUG, "U is now", U());
- // TODO(Austin): Figure out why the polytope stuff wasn't working and
- // remove this hack.
- output_was_capped_ = true;
- return;
-
- LOG_MATRIX(DEBUG, "U at start", U());
- LOG_MATRIX(DEBUG, "R at start", R());
- LOG_MATRIX(DEBUG, "Xhat at start", X_hat());
-
- Eigen::Matrix<double, 2, 2> position_K;
- position_K << K(0, 0), K(0, 2),
- K(1, 0), K(1, 2);
- Eigen::Matrix<double, 2, 2> velocity_K;
- velocity_K << K(0, 1), K(0, 3),
- K(1, 1), K(1, 3);
-
- Eigen::Matrix<double, 2, 1> position_error;
- position_error << error(0, 0), error(2, 0);
- const auto drive_error = T_inverse * position_error;
- Eigen::Matrix<double, 2, 1> velocity_error;
- velocity_error << error(1, 0), error(3, 0);
- LOG_MATRIX(DEBUG, "error", error);
-
- const auto &poly = U_Poly_;
- const Eigen::Matrix<double, 4, 2> pos_poly_H =
- poly.H() * position_K * T;
- const Eigen::Matrix<double, 4, 1> pos_poly_k =
- poly.k() - poly.H() * velocity_K * velocity_error;
- const ::aos::controls::HPolytope<2> pos_poly(pos_poly_H, pos_poly_k);
-
- Eigen::Matrix<double, 2, 1> adjusted_pos_error;
- {
- const auto &P = drive_error;
-
- Eigen::Matrix<double, 1, 2> L45;
- L45 << ::aos::sign(P(1, 0)), -::aos::sign(P(0, 0));
- const double w45 = 0;
-
- Eigen::Matrix<double, 1, 2> LH;
- if (::std::abs(P(0, 0)) > ::std::abs(P(1, 0))) {
- LH << 0, 1;
- } else {
- LH << 1, 0;
- }
- const double wh = LH.dot(P);
-
- Eigen::Matrix<double, 2, 2> standard;
- standard << L45, LH;
- Eigen::Matrix<double, 2, 1> W;
- W << w45, wh;
- const Eigen::Matrix<double, 2, 1> intersection =
- standard.inverse() * W;
-
- bool is_inside_h;
- const auto adjusted_pos_error_h =
- DoCoerceGoal(pos_poly, LH, wh, drive_error, &is_inside_h);
- const auto adjusted_pos_error_45 =
- DoCoerceGoal(pos_poly, L45, w45, intersection, nullptr);
- if (pos_poly.IsInside(intersection)) {
- adjusted_pos_error = adjusted_pos_error_h;
- } else {
- if (is_inside_h) {
- if (adjusted_pos_error_h.norm() > adjusted_pos_error_45.norm()) {
- adjusted_pos_error = adjusted_pos_error_h;
- } else {
- adjusted_pos_error = adjusted_pos_error_45;
- }
- } else {
- adjusted_pos_error = adjusted_pos_error_45;
- }
- }
- }
-
- LOG_MATRIX(DEBUG, "adjusted_pos_error", adjusted_pos_error);
- mutable_U() =
- velocity_K * velocity_error + position_K * T * adjusted_pos_error;
- LOG_MATRIX(DEBUG, "U is now", U());
- } else {
- output_was_capped_ = false;
- }
- }
-
- const ::aos::controls::HPolytope<2> U_Poly_;
- Eigen::Matrix<double, 2, 2> T, T_inverse;
- bool output_was_capped_ = false;;
- };
-
- DrivetrainMotorsSS()
- : loop_(new LimitedDrivetrainLoop(
- constants::GetValues().make_drivetrain_loop())),
- filtered_offset_(0.0),
- gyro_(0.0),
- left_goal_(0.0),
- right_goal_(0.0),
- raw_left_(0.0),
- raw_right_(0.0) {
- // Low gear on both.
- loop_->set_controller_index(0);
- }
-
- void SetGoal(double left, double left_velocity, double right,
- double right_velocity) {
- left_goal_ = left;
- right_goal_ = right;
- loop_->mutable_R() << left, left_velocity, right, right_velocity;
- }
- void SetRawPosition(double left, double right) {
- raw_right_ = right;
- raw_left_ = left;
- Eigen::Matrix<double, 2, 1> Y;
- Y << left + filtered_offset_, right - filtered_offset_;
- loop_->Correct(Y);
- }
- void SetPosition(double left, double right, double gyro) {
- // Decay the offset quickly because this gyro is great.
- const double offset =
- (right - left - gyro * constants::GetValues().turn_width) / 2.0;
- filtered_offset_ = 0.25 * offset + 0.75 * filtered_offset_;
- gyro_ = gyro;
- SetRawPosition(left, right);
- }
-
- void SetExternalMotors(double left_voltage, double right_voltage) {
- loop_->mutable_U() << left_voltage, right_voltage;
- }
-
- void Update(bool stop_motors, bool enable_control_loop) {
- if (enable_control_loop) {
- loop_->Update(stop_motors);
- } else {
- if (stop_motors) {
- loop_->mutable_U().setZero();
- loop_->mutable_U_uncapped().setZero();
- }
- loop_->UpdateObserver();
- }
- ::Eigen::Matrix<double, 4, 1> E = loop_->R() - loop_->X_hat();
- LOG_MATRIX(DEBUG, "E", E);
- }
-
- double GetEstimatedRobotSpeed() const {
- // lets just call the average of left and right velocities close enough
- return (loop_->X_hat(1, 0) + loop_->X_hat(3, 0)) / 2;
- }
-
- double GetEstimatedLeftEncoder() const {
- return loop_->X_hat(0, 0);
- }
-
- double GetEstimatedRightEncoder() const {
- return loop_->X_hat(2, 0);
- }
-
- bool OutputWasCapped() const {
- return loop_->output_was_capped();
- }
-
- void SendMotors(DrivetrainQueue::Output *output) const {
- if (output) {
- output->left_voltage = loop_->U(0, 0);
- output->right_voltage = loop_->U(1, 0);
- output->left_high = false;
- output->right_high = false;
- }
- }
-
- const LimitedDrivetrainLoop &loop() const { return *loop_; }
-
- private:
- ::std::unique_ptr<LimitedDrivetrainLoop> loop_;
-
- double filtered_offset_;
- double gyro_;
- double left_goal_;
- double right_goal_;
- double raw_left_;
- double raw_right_;
-};
-
-class PolyDrivetrain {
- public:
-
- enum Gear {
- HIGH,
- LOW,
- SHIFTING_UP,
- SHIFTING_DOWN
- };
- // Stall Torque in N m
- static constexpr double kStallTorque = 2.42;
- // Stall Current in Amps
- static constexpr double kStallCurrent = 133.0;
- // Free Speed in RPM. Used number from last year.
- static constexpr double kFreeSpeed = 4650.0;
- // Free Current in Amps
- static constexpr double kFreeCurrent = 2.7;
- // Moment of inertia of the drivetrain in kg m^2
- // Just borrowed from last year.
- static constexpr double J = 10;
- // Mass of the robot, in kg.
- static constexpr double m = 68;
- // Radius of the robot, in meters (from last year).
- static constexpr double rb = 0.9603 / 2.0;
- static constexpr double kWheelRadius = 0.0515938;
- // Resistance of the motor, divided by the number of motors.
- static constexpr double kR = (12.0 / kStallCurrent / 2 + 0.03) / (0.93 * 0.93);
- // Motor velocity constant
- static constexpr double Kv =
- ((kFreeSpeed / 60.0 * 2.0 * M_PI) / (12.0 - kR * kFreeCurrent));
- // Torque constant
- static constexpr double Kt = kStallTorque / kStallCurrent;
-
- PolyDrivetrain()
- : U_Poly_((Eigen::Matrix<double, 4, 2>() << /*[[*/ 1, 0 /*]*/,
- /*[*/ -1, 0 /*]*/,
- /*[*/ 0, 1 /*]*/,
- /*[*/ 0, -1 /*]]*/).finished(),
- (Eigen::Matrix<double, 4, 1>() << /*[[*/ 12 /*]*/,
- /*[*/ 12 /*]*/,
- /*[*/ 12 /*]*/,
- /*[*/ 12 /*]]*/).finished()),
- loop_(new StateFeedbackLoop<2, 2, 2>(
- constants::GetValues().make_v_drivetrain_loop())),
- ttrust_(1.1),
- wheel_(0.0),
- throttle_(0.0),
- quickturn_(false),
- stale_count_(0),
- position_time_delta_(0.01),
- left_gear_(LOW),
- right_gear_(LOW),
- counter_(0) {
-
- last_position_.Zero();
- position_.Zero();
- }
- static bool IsInGear(Gear gear) { return gear == LOW || gear == HIGH; }
-
- static double MotorSpeed(const constants::ShifterHallEffect &hall_effect,
- double shifter_position, double velocity) {
- // TODO(austin): G_high, G_low and kWheelRadius
- const double avg_hall_effect =
- (hall_effect.clear_high + hall_effect.clear_low) / 2.0;
-
- if (shifter_position > avg_hall_effect) {
- return velocity / constants::GetValues().high_gear_ratio / kWheelRadius;
- } else {
- return velocity / constants::GetValues().low_gear_ratio / kWheelRadius;
- }
- }
-
- Gear ComputeGear(const constants::ShifterHallEffect &hall_effect,
- double velocity, Gear current) {
- const double low_omega = MotorSpeed(hall_effect, 0.0, ::std::abs(velocity));
- const double high_omega =
- MotorSpeed(hall_effect, 1.0, ::std::abs(velocity));
-
- double high_torque = ((12.0 - high_omega / Kv) * Kt / kR);
- double low_torque = ((12.0 - low_omega / Kv) * Kt / kR);
- double high_power = high_torque * high_omega;
- double low_power = low_torque * low_omega;
-
- // TODO(aschuh): Do this right!
- if ((current == HIGH || high_power > low_power + 160) &&
- ::std::abs(velocity) > 0.14) {
- return HIGH;
- } else {
- return LOW;
- }
- }
-
- void SetGoal(double wheel, double throttle, bool quickturn, bool highgear) {
- const double kWheelNonLinearity = 0.5;
- // Apply a sin function that's scaled to make it feel better.
- const double angular_range = M_PI_2 * kWheelNonLinearity;
-
- wheel_ = sin(angular_range * wheel) / sin(angular_range);
- wheel_ = sin(angular_range * wheel_) / sin(angular_range);
- wheel_ *= 2.3;
- quickturn_ = quickturn;
-
- static const double kThrottleDeadband = 0.05;
- if (::std::abs(throttle) < kThrottleDeadband) {
- throttle_ = 0;
- } else {
- throttle_ = copysign((::std::abs(throttle) - kThrottleDeadband) /
- (1.0 - kThrottleDeadband), throttle);
- }
-
- // TODO(austin): Fix the upshift logic to include states.
- Gear requested_gear;
- if (false) {
- const auto &values = constants::GetValues();
- const double current_left_velocity =
- (position_.left_encoder - last_position_.left_encoder) /
- position_time_delta_;
- const double current_right_velocity =
- (position_.right_encoder - last_position_.right_encoder) /
- position_time_delta_;
-
- Gear left_requested =
- ComputeGear(values.left_drive, current_left_velocity, left_gear_);
- Gear right_requested =
- ComputeGear(values.right_drive, current_right_velocity, right_gear_);
- requested_gear =
- (left_requested == HIGH || right_requested == HIGH) ? HIGH : LOW;
- } else {
- requested_gear = highgear ? HIGH : LOW;
- }
-
- const Gear shift_up =
- constants::GetValues().clutch_transmission ? HIGH : SHIFTING_UP;
- const Gear shift_down =
- constants::GetValues().clutch_transmission ? LOW : SHIFTING_DOWN;
-
- if (left_gear_ != requested_gear) {
- if (IsInGear(left_gear_)) {
- if (requested_gear == HIGH) {
- left_gear_ = shift_up;
- } else {
- left_gear_ = shift_down;
- }
- } else {
- if (requested_gear == HIGH && left_gear_ == SHIFTING_DOWN) {
- left_gear_ = SHIFTING_UP;
- } else if (requested_gear == LOW && left_gear_ == SHIFTING_UP) {
- left_gear_ = SHIFTING_DOWN;
- }
- }
- }
- if (right_gear_ != requested_gear) {
- if (IsInGear(right_gear_)) {
- if (requested_gear == HIGH) {
- right_gear_ = shift_up;
- } else {
- right_gear_ = shift_down;
- }
- } else {
- if (requested_gear == HIGH && right_gear_ == SHIFTING_DOWN) {
- right_gear_ = SHIFTING_UP;
- } else if (requested_gear == LOW && right_gear_ == SHIFTING_UP) {
- right_gear_ = SHIFTING_DOWN;
- }
- }
- }
- }
- void SetPosition(const DrivetrainQueue::Position *position) {
- const auto &values = constants::GetValues();
- if (position == NULL) {
- ++stale_count_;
- } else {
- last_position_ = position_;
- position_ = *position;
- position_time_delta_ = (stale_count_ + 1) * 0.01;
- stale_count_ = 0;
- }
-
-#if HAVE_SHIFTERS
- if (position) {
- GearLogging gear_logging;
- // Switch to the correct controller.
- const double left_middle_shifter_position =
- (values.left_drive.clear_high + values.left_drive.clear_low) / 2.0;
- const double right_middle_shifter_position =
- (values.right_drive.clear_high + values.right_drive.clear_low) / 2.0;
-
- if (position->left_shifter_position < left_middle_shifter_position ||
- left_gear_ == LOW) {
- if (position->right_shifter_position < right_middle_shifter_position ||
- right_gear_ == LOW) {
- gear_logging.left_loop_high = false;
- gear_logging.right_loop_high = false;
- loop_->set_controller_index(gear_logging.controller_index = 0);
- } else {
- gear_logging.left_loop_high = false;
- gear_logging.right_loop_high = true;
- loop_->set_controller_index(gear_logging.controller_index = 1);
- }
- } else {
- if (position->right_shifter_position < right_middle_shifter_position ||
- right_gear_ == LOW) {
- gear_logging.left_loop_high = true;
- gear_logging.right_loop_high = false;
- loop_->set_controller_index(gear_logging.controller_index = 2);
- } else {
- gear_logging.left_loop_high = true;
- gear_logging.right_loop_high = true;
- loop_->set_controller_index(gear_logging.controller_index = 3);
- }
- }
-
- // TODO(austin): Constants.
- if (position->left_shifter_position > values.left_drive.clear_high && left_gear_ == SHIFTING_UP) {
- left_gear_ = HIGH;
- }
- if (position->left_shifter_position < values.left_drive.clear_low && left_gear_ == SHIFTING_DOWN) {
- left_gear_ = LOW;
- }
- if (position->right_shifter_position > values.right_drive.clear_high && right_gear_ == SHIFTING_UP) {
- right_gear_ = HIGH;
- }
- if (position->right_shifter_position < values.right_drive.clear_low && right_gear_ == SHIFTING_DOWN) {
- right_gear_ = LOW;
- }
-
- gear_logging.left_state = left_gear_;
- gear_logging.right_state = right_gear_;
- LOG_STRUCT(DEBUG, "state", gear_logging);
- }
-#else
- (void) values;
-#endif
- }
-
- double FilterVelocity(double throttle) {
- const Eigen::Matrix<double, 2, 2> FF =
- loop_->B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
- constexpr int kHighGearController = 3;
- const Eigen::Matrix<double, 2, 2> FF_high =
- loop_->controller(kHighGearController).plant.B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() -
- loop_->controller(kHighGearController).plant.A());
-
- ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
- int min_FF_sum_index;
- const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
- const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
- const double high_min_FF_sum = FF_high.col(0).sum();
-
- const double adjusted_ff_voltage = ::aos::Clip(
- throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
- return (adjusted_ff_voltage +
- ttrust_ * min_K_sum * (loop_->X_hat(0, 0) + loop_->X_hat(1, 0)) /
- 2.0) /
- (ttrust_ * min_K_sum + min_FF_sum);
- }
-
- double MaxVelocity() {
- const Eigen::Matrix<double, 2, 2> FF =
- loop_->B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
- constexpr int kHighGearController = 3;
- const Eigen::Matrix<double, 2, 2> FF_high =
- loop_->controller(kHighGearController).plant.B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() -
- loop_->controller(kHighGearController).plant.A());
-
- ::Eigen::Matrix<double, 1, 2> FF_sum = FF.colwise().sum();
- int min_FF_sum_index;
- const double min_FF_sum = FF_sum.minCoeff(&min_FF_sum_index);
- //const double min_K_sum = loop_->K().col(min_FF_sum_index).sum();
- const double high_min_FF_sum = FF_high.col(0).sum();
-
- const double adjusted_ff_voltage = ::aos::Clip(
- 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0);
- return adjusted_ff_voltage / min_FF_sum;
- }
-
- void Update() {
- const auto &values = constants::GetValues();
- // TODO(austin): Observer for the current velocity instead of difference
- // calculations.
- ++counter_;
-#if HAVE_SHIFTERS
- const double current_left_velocity =
- (position_.left_encoder - last_position_.left_encoder) /
- position_time_delta_;
- const double current_right_velocity =
- (position_.right_encoder - last_position_.right_encoder) /
- position_time_delta_;
- const double left_motor_speed =
- MotorSpeed(values.left_drive, position_.left_shifter_position,
- current_left_velocity);
- const double right_motor_speed =
- MotorSpeed(values.right_drive, position_.right_shifter_position,
- current_right_velocity);
-
- {
- CIMLogging logging;
-
- // Reset the CIM model to the current conditions to be ready for when we
- // shift.
- if (IsInGear(left_gear_)) {
- logging.left_in_gear = true;
- } else {
- logging.left_in_gear = false;
- }
- logging.left_motor_speed = left_motor_speed;
- logging.left_velocity = current_left_velocity;
- if (IsInGear(right_gear_)) {
- logging.right_in_gear = true;
- } else {
- logging.right_in_gear = false;
- }
- logging.right_motor_speed = right_motor_speed;
- logging.right_velocity = current_right_velocity;
-
- LOG_STRUCT(DEBUG, "currently", logging);
- }
-#else
- (void) values;
-#endif
-
-#if HAVE_SHIFTERS
- if (IsInGear(left_gear_) && IsInGear(right_gear_)) {
-#else
- {
-#endif
- // FF * X = U (steady state)
- const Eigen::Matrix<double, 2, 2> FF =
- loop_->B().inverse() *
- (Eigen::Matrix<double, 2, 2>::Identity() - loop_->A());
-
- // Invert the plant to figure out how the velocity filter would have to
- // work
- // out in order to filter out the forwards negative inertia.
- // This math assumes that the left and right power and velocity are
- // equals,
- // and that the plant is the same on the left and right.
- const double fvel = FilterVelocity(throttle_);
-
- const double sign_svel = wheel_ * ((fvel > 0.0) ? 1.0 : -1.0);
- double steering_velocity;
- if (quickturn_) {
- steering_velocity = wheel_ * MaxVelocity();
- } else {
- steering_velocity = ::std::abs(fvel) * wheel_;
- }
- const double left_velocity = fvel - steering_velocity;
- const double right_velocity = fvel + steering_velocity;
- LOG(DEBUG, "l=%f r=%f\n", left_velocity, right_velocity);
-
- // Integrate velocity to get the position.
- // This position is used to get integral control.
- loop_->mutable_R() << left_velocity, right_velocity;
-
- if (!quickturn_) {
- // K * R = w
- Eigen::Matrix<double, 1, 2> equality_k;
- equality_k << 1 + sign_svel, -(1 - sign_svel);
- const double equality_w = 0.0;
-
- // Construct a constraint on R by manipulating the constraint on U
- ::aos::controls::HPolytope<2> R_poly = ::aos::controls::HPolytope<2>(
- U_Poly_.H() * (loop_->K() + FF),
- U_Poly_.k() + U_Poly_.H() * loop_->K() * loop_->X_hat());
-
- // Limit R back inside the box.
- loop_->mutable_R() =
- CoerceGoal(R_poly, equality_k, equality_w, loop_->R());
- }
-
- const Eigen::Matrix<double, 2, 1> FF_volts = FF * loop_->R();
- const Eigen::Matrix<double, 2, 1> U_ideal =
- loop_->K() * (loop_->R() - loop_->X_hat()) + FF_volts;
-
- for (int i = 0; i < 2; i++) {
- loop_->mutable_U()[i] = ::aos::Clip(U_ideal[i], -12, 12);
- }
-
- // TODO(austin): Model this better.
- // TODO(austin): Feed back?
- loop_->mutable_X_hat() =
- loop_->A() * loop_->X_hat() + loop_->B() * loop_->U();
-#if HAVE_SHIFTERS
- } else {
- // Any motor is not in gear. Speed match.
- ::Eigen::Matrix<double, 1, 1> R_left;
- ::Eigen::Matrix<double, 1, 1> R_right;
- R_left(0, 0) = left_motor_speed;
- R_right(0, 0) = right_motor_speed;
-
- const double wiggle =
- (static_cast<double>((counter_ % 20) / 10) - 0.5) * 5.0;
-
- loop_->mutable_U(0, 0) = ::aos::Clip(
- (R_left / Kv)(0, 0) + (IsInGear(left_gear_) ? 0 : wiggle),
- -12.0, 12.0);
- loop_->mutable_U(1, 0) = ::aos::Clip(
- (R_right / Kv)(0, 0) + (IsInGear(right_gear_) ? 0 : wiggle),
- -12.0, 12.0);
- loop_->mutable_U() *= 12.0 / ::aos::robot_state->voltage_battery;
-#endif
- }
- }
-
- void SendMotors(DrivetrainQueue::Output *output) {
- if (output != NULL) {
- output->left_voltage = loop_->U(0, 0);
- output->right_voltage = loop_->U(1, 0);
- output->left_high = left_gear_ == HIGH || left_gear_ == SHIFTING_UP;
- output->right_high = right_gear_ == HIGH || right_gear_ == SHIFTING_UP;
- }
- }
-
- private:
- const ::aos::controls::HPolytope<2> U_Poly_;
-
- ::std::unique_ptr<StateFeedbackLoop<2, 2, 2>> loop_;
-
- const double ttrust_;
- double wheel_;
- double throttle_;
- bool quickturn_;
- int stale_count_;
- double position_time_delta_;
- Gear left_gear_;
- Gear right_gear_;
- DrivetrainQueue::Position last_position_;
- DrivetrainQueue::Position position_;
- int counter_;
-};
-constexpr double PolyDrivetrain::kStallTorque;
-constexpr double PolyDrivetrain::kStallCurrent;
-constexpr double PolyDrivetrain::kFreeSpeed;
-constexpr double PolyDrivetrain::kFreeCurrent;
-constexpr double PolyDrivetrain::J;
-constexpr double PolyDrivetrain::m;
-constexpr double PolyDrivetrain::rb;
-constexpr double PolyDrivetrain::kWheelRadius;
-constexpr double PolyDrivetrain::kR;
-constexpr double PolyDrivetrain::Kv;
-constexpr double PolyDrivetrain::Kt;
-
-
-void DrivetrainLoop::RunIteration(const DrivetrainQueue::Goal *goal,
- const DrivetrainQueue::Position *position,
- DrivetrainQueue::Output *output,
- DrivetrainQueue::Status * status) {
- // TODO(aschuh): These should be members of the class.
- static DrivetrainMotorsSS dt_closedloop;
- static PolyDrivetrain dt_openloop;
-
- bool bad_pos = false;
- if (position == nullptr) {
- LOG_INTERVAL(no_position_);
- bad_pos = true;
- }
- no_position_.Print();
-
- bool control_loop_driving = false;
- if (goal) {
- double wheel = goal->steering;
- double throttle = goal->throttle;
- bool quickturn = goal->quickturn;
-#if HAVE_SHIFTERS
- bool highgear = goal->highgear;
-#endif
-
- control_loop_driving = goal->control_loop_driving;
- double left_goal = goal->left_goal;
- double right_goal = goal->right_goal;
-
- dt_closedloop.SetGoal(left_goal, goal->left_velocity_goal, right_goal,
- goal->right_velocity_goal);
-#if HAVE_SHIFTERS
- dt_openloop.SetGoal(wheel, throttle, quickturn, highgear);
-#else
- dt_openloop.SetGoal(wheel, throttle, quickturn, false);
-#endif
- }
-
- if (!bad_pos) {
- const double left_encoder = position->left_encoder;
- const double right_encoder = position->right_encoder;
- if (gyro_reading.FetchLatest()) {
- LOG_STRUCT(DEBUG, "using", *gyro_reading.get());
- dt_closedloop.SetPosition(left_encoder, right_encoder,
- gyro_reading->angle);
- } else {
- dt_closedloop.SetRawPosition(left_encoder, right_encoder);
- }
- }
- dt_openloop.SetPosition(position);
- dt_openloop.Update();
-
- if (control_loop_driving) {
- dt_closedloop.Update(output == NULL, true);
- dt_closedloop.SendMotors(output);
- } else {
- dt_openloop.SendMotors(output);
- if (output) {
- dt_closedloop.SetExternalMotors(output->left_voltage,
- output->right_voltage);
- }
- dt_closedloop.Update(output == NULL, false);
- }
-
- // set the output status of the control loop state
- if (status) {
- bool done = false;
- if (goal) {
- done = ((::std::abs(goal->left_goal -
- dt_closedloop.GetEstimatedLeftEncoder()) <
- constants::GetValues().drivetrain_done_distance) &&
- (::std::abs(goal->right_goal -
- dt_closedloop.GetEstimatedRightEncoder()) <
- constants::GetValues().drivetrain_done_distance));
- }
- status->is_done = done;
- status->robot_speed = dt_closedloop.GetEstimatedRobotSpeed();
- status->filtered_left_position = dt_closedloop.GetEstimatedLeftEncoder();
- status->filtered_right_position = dt_closedloop.GetEstimatedRightEncoder();
-
- status->filtered_left_velocity = dt_closedloop.loop().X_hat(1, 0);
- status->filtered_right_velocity = dt_closedloop.loop().X_hat(3, 0);
- status->output_was_capped = dt_closedloop.OutputWasCapped();
- status->uncapped_left_voltage = dt_closedloop.loop().U_uncapped(0, 0);
- status->uncapped_right_voltage = dt_closedloop.loop().U_uncapped(1, 0);
- }
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain.gyp b/frc971/control_loops/drivetrain/drivetrain.gyp
deleted file mode 100644
index fb32377..0000000
--- a/frc971/control_loops/drivetrain/drivetrain.gyp
+++ /dev/null
@@ -1,103 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'replay_drivetrain',
- 'type': 'executable',
- 'variables': {
- 'no_rsync': 1,
- },
- 'sources': [
- 'replay_drivetrain.cc',
- ],
- 'dependencies': [
- 'drivetrain_queue',
- '<(AOS)/common/controls/controls.gyp:replay_control_loop',
- '<(AOS)/linux_code/linux_code.gyp:init',
- ],
- },
- {
- 'target_name': 'drivetrain_queue',
- 'type': 'static_library',
- 'sources': ['drivetrain.q'],
- 'variables': {
- 'header_path': 'frc971/control_loops/drivetrain',
- },
- 'dependencies': [
- '<(AOS)/common/controls/controls.gyp:control_loop_queues',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/controls/controls.gyp:control_loop_queues',
- ],
- 'includes': ['../../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'polydrivetrain_plants',
- 'type': 'static_library',
- 'sources': [
- 'polydrivetrain_dog_motor_plant.cc',
- 'drivetrain_dog_motor_plant.cc',
- ],
- 'dependencies': [
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- ],
- 'export_dependent_settings': [
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- ],
- },
- {
- 'target_name': 'drivetrain_lib',
- 'type': 'static_library',
- 'sources': [
- 'drivetrain.cc',
- 'polydrivetrain_cim_plant.cc',
- ],
- 'dependencies': [
- 'drivetrain_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(AOS)/common/controls/controls.gyp:polytope',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
- '<(DEPTH)/frc971/queues/queues.gyp:gyro',
- '<(AOS)/common/util/util.gyp:log_interval',
- '<(AOS)/common/logging/logging.gyp:queue_logging',
- '<(AOS)/common/logging/logging.gyp:matrix_logging',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/controls/controls.gyp:polytope',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:coerce_goal',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- 'drivetrain_queue',
- ],
- },
- {
- 'target_name': 'drivetrain_lib_test',
- 'type': 'executable',
- 'sources': [
- 'drivetrain_lib_test.cc',
- ],
- 'dependencies': [
- '<(EXTERNALS):gtest',
- 'drivetrain_queue',
- 'drivetrain_lib',
- '<(AOS)/common/controls/controls.gyp:control_loop_test',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/queues/queues.gyp:gyro',
- '<(AOS)/common/common.gyp:queues',
- ],
- },
- {
- 'target_name': 'drivetrain',
- 'type': 'executable',
- 'sources': [
- 'drivetrain_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- 'drivetrain_lib',
- 'drivetrain_queue',
- ],
- },
- ],
-}
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
deleted file mode 100644
index decde09..0000000
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ /dev/null
@@ -1,43 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
-#define FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
-
-#include "Eigen/Dense"
-
-#include "aos/common/controls/polytope.h"
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/controls/polytope.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-#include "aos/common/util/log_interval.h"
-
-namespace frc971 {
-namespace control_loops {
-
-class DrivetrainLoop
- : public aos::controls::ControlLoop<control_loops::DrivetrainQueue> {
- public:
- // Constructs a control loop which can take a Drivetrain or defaults to the
- // drivetrain at frc971::control_loops::drivetrain
- explicit DrivetrainLoop(control_loops::DrivetrainQueue *my_drivetrain =
- &control_loops::drivetrain_queue)
- : aos::controls::ControlLoop<control_loops::DrivetrainQueue>(
- my_drivetrain) {
- ::aos::controls::HPolytope<0>::Init();
- }
-
- protected:
- // Executes one cycle of the control loop.
- virtual void RunIteration(
- const control_loops::DrivetrainQueue::Goal *goal,
- const control_loops::DrivetrainQueue::Position *position,
- control_loops::DrivetrainQueue::Output *output,
- control_loops::DrivetrainQueue::Status *status);
-
- typedef ::aos::util::SimpleLogInterval SimpleLogInterval;
- SimpleLogInterval no_position_ = SimpleLogInterval(
- ::aos::time::Time::InSeconds(0.25), WARNING, "no position");
-};
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain.q b/frc971/control_loops/drivetrain/drivetrain.q
deleted file mode 100644
index 942c5b3..0000000
--- a/frc971/control_loops/drivetrain/drivetrain.q
+++ /dev/null
@@ -1,71 +0,0 @@
-package frc971.control_loops;
-
-import "aos/common/controls/control_loops.q";
-
-struct GearLogging {
- int8_t controller_index;
- bool left_loop_high;
- bool right_loop_high;
- int8_t left_state;
- int8_t right_state;
-};
-
-struct CIMLogging {
- bool left_in_gear;
- bool right_in_gear;
- double left_motor_speed;
- double right_motor_speed;
- double left_velocity;
- double right_velocity;
-};
-
-queue_group DrivetrainQueue {
- implements aos.control_loops.ControlLoop;
-
- message Goal {
- double steering;
- double throttle;
- //bool highgear;
- bool quickturn;
- bool control_loop_driving;
- double left_goal;
- double left_velocity_goal;
- double right_goal;
- double right_velocity_goal;
- };
-
- message Position {
- double left_encoder;
- double right_encoder;
- //double left_shifter_position;
- //double right_shifter_position;
- };
-
- message Output {
- double left_voltage;
- double right_voltage;
- bool left_high;
- bool right_high;
- };
-
- message Status {
- double robot_speed;
- double filtered_left_position;
- double filtered_right_position;
- double filtered_left_velocity;
- double filtered_right_velocity;
-
- double uncapped_left_voltage;
- double uncapped_right_voltage;
- bool output_was_capped;
-
- bool is_done;
- };
-
- queue Goal goal;
- queue Position position;
- queue Output output;
- queue Status status;
-};
-
-queue_group DrivetrainQueue drivetrain_queue;
diff --git a/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.cc b/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
deleted file mode 100644
index b04c5af..0000000
--- a/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.cc
+++ /dev/null
@@ -1,133 +0,0 @@
-#include "frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowLowPlantCoefficients() {
- Eigen::Matrix<double, 4, 4> A;
- A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
- Eigen::Matrix<double, 4, 2> B;
- B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
- Eigen::Matrix<double, 2, 4> C;
- C << 1, 0, 0, 0, 0, 0, 1, 0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients() {
- Eigen::Matrix<double, 4, 4> A;
- A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
- Eigen::Matrix<double, 4, 2> B;
- B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
- Eigen::Matrix<double, 2, 4> C;
- C << 1, 0, 0, 0, 0, 0, 1, 0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients() {
- Eigen::Matrix<double, 4, 4> A;
- A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
- Eigen::Matrix<double, 4, 2> B;
- B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
- Eigen::Matrix<double, 2, 4> C;
- C << 1, 0, 0, 0, 0, 0, 1, 0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients() {
- Eigen::Matrix<double, 4, 4> A;
- A << 1.0, 0.00494348612824, 0.0, 1.24048455404e-05, 0.0, 0.977484092703, 0.0, 0.00492433284048, 0.0, 1.24048455404e-05, 1.0, 0.00494348612824, 0.0, 0.00492433284048, 0.0, 0.977484092703;
- Eigen::Matrix<double, 4, 2> B;
- B << 2.09180756177e-05, -4.59153636043e-06, 0.00833405032795, -0.00182269526971, -4.59153636043e-06, 2.09180756177e-05, -0.00182269526971, 0.00833405032795;
- Eigen::Matrix<double, 2, 4> C;
- C << 1, 0, 0, 0, 0, 0, 1, 0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController() {
- Eigen::Matrix<double, 4, 2> L;
- L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
- Eigen::Matrix<double, 2, 4> K;
- K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
- Eigen::Matrix<double, 4, 4> A_inv;
- A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
- return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowLowPlantCoefficients());
-}
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController() {
- Eigen::Matrix<double, 4, 2> L;
- L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
- Eigen::Matrix<double, 2, 4> K;
- K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
- Eigen::Matrix<double, 4, 4> A_inv;
- A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
- return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainLowHighPlantCoefficients());
-}
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController() {
- Eigen::Matrix<double, 4, 2> L;
- L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
- Eigen::Matrix<double, 2, 4> K;
- K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
- Eigen::Matrix<double, 4, 4> A_inv;
- A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
- return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighLowPlantCoefficients());
-}
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController() {
- Eigen::Matrix<double, 4, 2> L;
- L << 1.2774840927, 0.00492433284048, 79.1440456622, 1.05150722636, 0.00492433284048, 1.2774840927, 1.05150722636, 79.1440456622;
- Eigen::Matrix<double, 2, 4> K;
- K << 160.19677247, 15.5358468938, 1.60401194139, 1.33861213093, 1.60401194142, 1.33861213094, 160.19677247, 15.5358468938;
- Eigen::Matrix<double, 4, 4> A_inv;
- A_inv << 1.0, -0.00505742153256, 0.0, 1.27875036472e-05, 0.0, 1.02306051542, 0.0, -0.00515393603998, 0.0, 1.27875036472e-05, 1.0, -0.00505742153256, 0.0, -0.00515393603998, 0.0, 1.02306051542;
- return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeDrivetrainHighHighPlantCoefficients());
-}
-
-StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(4);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowLowPlantCoefficients()));
- plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainLowHighPlantCoefficients()));
- plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighLowPlantCoefficients()));
- plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeDrivetrainHighHighPlantCoefficients()));
- return StateFeedbackPlant<4, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(4);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowLowController()));
- controllers[1] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainLowHighController()));
- controllers[2] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighLowController()));
- controllers[3] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeDrivetrainHighHighController()));
- return StateFeedbackLoop<4, 2, 2>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h b/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h
deleted file mode 100644
index 366f95d..0000000
--- a/frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
-#define FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowLowPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainLowLowController();
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainLowHighPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainLowHighController();
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighLowPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainHighLowController();
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeDrivetrainHighHighPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeDrivetrainHighHighController();
-
-StateFeedbackPlant<4, 2, 2> MakeDrivetrainPlant();
-
-StateFeedbackLoop<4, 2, 2> MakeDrivetrainLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
deleted file mode 100644
index 7e14cf0..0000000
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ /dev/null
@@ -1,297 +0,0 @@
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/network/team_number.h"
-#include "aos/common/queue_testutils.h"
-#include "aos/common/controls/polytope.h"
-#include "aos/common/controls/control_loop_test.h"
-
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/control_loops/drivetrain/drivetrain.h"
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/coerce_goal.h"
-#include "frc971/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-#include "frc971/queues/gyro.q.h"
-
-
-namespace frc971 {
-namespace control_loops {
-namespace testing {
-
-class Environment : public ::testing::Environment {
- public:
- virtual ~Environment() {}
- // how to set up the environment.
- virtual void SetUp() {
- aos::controls::HPolytope<0>::Init();
- }
-};
-::testing::Environment* const holder_env =
- ::testing::AddGlobalTestEnvironment(new Environment);
-
-class TeamNumberEnvironment : public ::testing::Environment {
- public:
- // Override this to define how to set up the environment.
- virtual void SetUp() { aos::network::OverrideTeamNumber(971); }
-};
-
-::testing::Environment* const team_number_env =
- ::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment);
-
-// Class which simulates the drivetrain and sends out queue messages containing
-// the position.
-class DrivetrainSimulation {
- public:
- // Constructs a motor simulation.
- // TODO(aschuh) Do we want to test the clutch one too?
- DrivetrainSimulation()
- : drivetrain_plant_(
- new StateFeedbackPlant<4, 2, 2>(MakeDrivetrainPlant())),
- my_drivetrain_queue_(".frc971.control_loops.drivetrain",
- 0x8a8dde77, ".frc971.control_loops.drivetrain.goal",
- ".frc971.control_loops.drivetrain.position",
- ".frc971.control_loops.drivetrain.output",
- ".frc971.control_loops.drivetrain.status") {
- Reinitialize();
- }
-
- // Resets the plant.
- void Reinitialize() {
- drivetrain_plant_->mutable_X(0, 0) = 0.0;
- drivetrain_plant_->mutable_X(1, 0) = 0.0;
- drivetrain_plant_->mutable_Y() =
- drivetrain_plant_->C() * drivetrain_plant_->X();
- last_left_position_ = drivetrain_plant_->Y(0, 0);
- last_right_position_ = drivetrain_plant_->Y(1, 0);
- }
-
- // Returns the position of the drivetrain.
- double GetLeftPosition() const { return drivetrain_plant_->Y(0, 0); }
- double GetRightPosition() const { return drivetrain_plant_->Y(1, 0); }
-
- // Sends out the position queue messages.
- void SendPositionMessage() {
- const double left_encoder = GetLeftPosition();
- const double right_encoder = GetRightPosition();
-
- ::aos::ScopedMessagePtr<control_loops::DrivetrainQueue::Position> position =
- my_drivetrain_queue_.position.MakeMessage();
- position->left_encoder = left_encoder;
- position->right_encoder = right_encoder;
- position.Send();
- }
-
- // Simulates the drivetrain moving for one timestep.
- void Simulate() {
- last_left_position_ = drivetrain_plant_->Y(0, 0);
- last_right_position_ = drivetrain_plant_->Y(1, 0);
- EXPECT_TRUE(my_drivetrain_queue_.output.FetchLatest());
- drivetrain_plant_->mutable_U() << my_drivetrain_queue_.output->left_voltage,
- my_drivetrain_queue_.output->right_voltage;
- drivetrain_plant_->Update();
- }
-
- ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> drivetrain_plant_;
- private:
- DrivetrainQueue my_drivetrain_queue_;
- double last_left_position_;
- double last_right_position_;
-};
-
-class DrivetrainTest : public ::aos::testing::ControlLoopTest {
- protected:
- // Create a new instance of the test queue so that it invalidates the queue
- // that it points to. Otherwise, we will have a pointer to shared memory that
- // is no longer valid.
- DrivetrainQueue my_drivetrain_queue_;
-
- // Create a loop and simulation plant.
- DrivetrainLoop drivetrain_motor_;
- DrivetrainSimulation drivetrain_motor_plant_;
-
- DrivetrainTest() : my_drivetrain_queue_(".frc971.control_loops.drivetrain",
- 0x8a8dde77,
- ".frc971.control_loops.drivetrain.goal",
- ".frc971.control_loops.drivetrain.position",
- ".frc971.control_loops.drivetrain.output",
- ".frc971.control_loops.drivetrain.status"),
- drivetrain_motor_(&my_drivetrain_queue_),
- drivetrain_motor_plant_() {
- ::frc971::sensors::gyro_reading.Clear();
- }
-
- void VerifyNearGoal() {
- my_drivetrain_queue_.goal.FetchLatest();
- my_drivetrain_queue_.position.FetchLatest();
- EXPECT_NEAR(my_drivetrain_queue_.goal->left_goal,
- drivetrain_motor_plant_.GetLeftPosition(),
- 1e-2);
- EXPECT_NEAR(my_drivetrain_queue_.goal->right_goal,
- drivetrain_motor_plant_.GetRightPosition(),
- 1e-2);
- }
-
- virtual ~DrivetrainTest() {
- ::frc971::sensors::gyro_reading.Clear();
- }
-};
-
-// Tests that the drivetrain converges on a goal.
-TEST_F(DrivetrainTest, ConvergesCorrectly) {
- my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
- .left_goal(-1.0)
- .right_goal(1.0).Send();
- for (int i = 0; i < 200; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- SimulateTimestep(true);
- }
- VerifyNearGoal();
-}
-
-// Tests that it survives disabling.
-TEST_F(DrivetrainTest, SurvivesDisabling) {
- my_drivetrain_queue_.goal.MakeWithBuilder().control_loop_driving(true)
- .left_goal(-1.0)
- .right_goal(1.0).Send();
- for (int i = 0; i < 500; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- if (i > 20 && i < 200) {
- SimulateTimestep(false);
- } else {
- SimulateTimestep(true);
- }
- }
- VerifyNearGoal();
-}
-
-// Tests that never having a goal doesn't break.
-TEST_F(DrivetrainTest, NoGoalStart) {
- for (int i = 0; i < 20; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- }
-}
-
-// Tests that never having a goal, but having driver's station messages, doesn't
-// break.
-TEST_F(DrivetrainTest, NoGoalWithRobotState) {
- for (int i = 0; i < 20; ++i) {
- drivetrain_motor_plant_.SendPositionMessage();
- drivetrain_motor_.Iterate();
- drivetrain_motor_plant_.Simulate();
- SimulateTimestep(true);
- }
-}
-
-::aos::controls::HPolytope<2> MakeBox(double x1_min, double x1_max,
- double x2_min, double x2_max) {
- Eigen::Matrix<double, 4, 2> box_H;
- box_H << /*[[*/ 1.0, 0.0 /*]*/,
- /*[*/-1.0, 0.0 /*]*/,
- /*[*/ 0.0, 1.0 /*]*/,
- /*[*/ 0.0,-1.0 /*]]*/;
- Eigen::Matrix<double, 4, 1> box_k;
- box_k << /*[[*/ x1_max /*]*/,
- /*[*/-x1_min /*]*/,
- /*[*/ x2_max /*]*/,
- /*[*/-x2_min /*]]*/;
- ::aos::controls::HPolytope<2> t_poly(box_H, box_k);
- return t_poly;
-}
-
-class CoerceGoalTest : public ::testing::Test {
- public:
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW
-};
-
-// WHOOOHH!
-TEST_F(CoerceGoalTest, Inside) {
- ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << /*[[*/ 1, -1 /*]]*/;
-
- Eigen::Matrix<double, 2, 1> R;
- R << /*[[*/ 1.5, 1.5 /*]]*/;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(R(0, 0), output(0, 0));
- EXPECT_EQ(R(1, 0), output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Outside_Inside_Intersect) {
- ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << 1, -1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(2.0, output(0, 0));
- EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Outside_Inside_no_Intersect) {
- ::aos::controls::HPolytope<2> box = MakeBox(3, 4, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << 1, -1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(3.0, output(0, 0));
- EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, Middle_Of_Edge) {
- ::aos::controls::HPolytope<2> box = MakeBox(0, 4, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << -1, 1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(2.0, output(0, 0));
- EXPECT_EQ(2.0, output(1, 0));
-}
-
-TEST_F(CoerceGoalTest, PerpendicularLine) {
- ::aos::controls::HPolytope<2> box = MakeBox(1, 2, 1, 2);
-
- Eigen::Matrix<double, 1, 2> K;
- K << 1, 1;
-
- Eigen::Matrix<double, 2, 1> R;
- R << 5, 5;
-
- Eigen::Matrix<double, 2, 1> output =
- ::frc971::control_loops::CoerceGoal(box, K, 0, R);
-
- EXPECT_EQ(1.0, output(0, 0));
- EXPECT_EQ(1.0, output(1, 0));
-}
-
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/drivetrain_main.cc b/frc971/control_loops/drivetrain/drivetrain_main.cc
deleted file mode 100644
index f3f0ddd..0000000
--- a/frc971/control_loops/drivetrain/drivetrain_main.cc
+++ /dev/null
@@ -1,11 +0,0 @@
-#include "frc971/control_loops/drivetrain/drivetrain.h"
-
-#include "aos/linux_code/init.h"
-
-int main() {
- ::aos::Init();
- frc971::control_loops::DrivetrainLoop drivetrain;
- drivetrain.Run();
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.cc b/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.cc
deleted file mode 100644
index ec2b669..0000000
--- a/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients() {
- Eigen::Matrix<double, 1, 1> A;
- A << 0.783924473544;
- Eigen::Matrix<double, 1, 1> B;
- B << 8.94979586973;
- Eigen::Matrix<double, 1, 1> C;
- C << 1;
- Eigen::Matrix<double, 1, 1> D;
- D << 0;
- Eigen::Matrix<double, 1, 1> U_max;
- U_max << 12.0;
- Eigen::Matrix<double, 1, 1> U_min;
- U_min << -12.0;
- return StateFeedbackPlantCoefficients<1, 1, 1>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<1, 1, 1> MakeCIMController() {
- Eigen::Matrix<double, 1, 1> L;
- L << 0.773924473544;
- Eigen::Matrix<double, 1, 1> K;
- K << 0.086473980503;
- Eigen::Matrix<double, 1, 1> A_inv;
- A_inv << 1.2756330919;
- return StateFeedbackController<1, 1, 1>(L, K, A_inv, MakeCIMPlantCoefficients());
-}
-
-StateFeedbackPlant<1, 1, 1> MakeCIMPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>> plants(1);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<1, 1, 1>>(new StateFeedbackPlantCoefficients<1, 1, 1>(MakeCIMPlantCoefficients()));
- return StateFeedbackPlant<1, 1, 1>(&plants);
-}
-
-StateFeedbackLoop<1, 1, 1> MakeCIMLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<1, 1, 1>>> controllers(1);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<1, 1, 1>>(new StateFeedbackController<1, 1, 1>(MakeCIMController()));
- return StateFeedbackLoop<1, 1, 1>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h b/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h
deleted file mode 100644
index 12b2c59..0000000
--- a/frc971/control_loops/drivetrain/polydrivetrain_cim_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
-#define FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<1, 1, 1> MakeCIMPlantCoefficients();
-
-StateFeedbackController<1, 1, 1> MakeCIMController();
-
-StateFeedbackPlant<1, 1, 1> MakeCIMPlant();
-
-StateFeedbackLoop<1, 1, 1> MakeCIMLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_CIM_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc b/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
deleted file mode 100644
index 1641306..0000000
--- a/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.cc
+++ /dev/null
@@ -1,133 +0,0 @@
-#include "frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients() {
- Eigen::Matrix<double, 2, 2> A;
- A << 0.955499400541, 0.00962691403749, 0.00962691403749, 0.955499400541;
- Eigen::Matrix<double, 2, 2> B;
- B << 0.0164714763931, -0.00356331126397, -0.00356331126397, 0.0164714763931;
- Eigen::Matrix<double, 2, 2> C;
- C << 1.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0.0, 0.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<2, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
- Eigen::Matrix<double, 2, 2> K;
- K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowLowPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
- Eigen::Matrix<double, 2, 2> K;
- K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainLowHighPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
- Eigen::Matrix<double, 2, 2> K;
- K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighLowPlantCoefficients());
-}
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController() {
- Eigen::Matrix<double, 2, 2> L;
- L << 0.935499400541, 0.00962691403749, 0.00962691403749, 0.935499400541;
- Eigen::Matrix<double, 2, 2> K;
- K << 22.7750288573, 5.51143253556, 5.51143253556, 22.7750288573;
- Eigen::Matrix<double, 2, 2> A_inv;
- A_inv << 1.04667938127, -0.010545576923, -0.010545576923, 1.04667938127;
- return StateFeedbackController<2, 2, 2>(L, K, A_inv, MakeVelocityDrivetrainHighHighPlantCoefficients());
-}
-
-StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>> plants(4);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowLowPlantCoefficients()));
- plants[1] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainLowHighPlantCoefficients()));
- plants[2] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighLowPlantCoefficients()));
- plants[3] = ::std::unique_ptr<StateFeedbackPlantCoefficients<2, 2, 2>>(new StateFeedbackPlantCoefficients<2, 2, 2>(MakeVelocityDrivetrainHighHighPlantCoefficients()));
- return StateFeedbackPlant<2, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<2, 2, 2>>> controllers(4);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowLowController()));
- controllers[1] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainLowHighController()));
- controllers[2] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighLowController()));
- controllers[3] = ::std::unique_ptr<StateFeedbackController<2, 2, 2>>(new StateFeedbackController<2, 2, 2>(MakeVelocityDrivetrainHighHighController()));
- return StateFeedbackLoop<2, 2, 2>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h b/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
deleted file mode 100644
index 27aa4dd..0000000
--- a/frc971/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h
+++ /dev/null
@@ -1,32 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
-#define FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowLowPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowLowController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainLowHighPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainLowHighController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighLowPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighLowController();
-
-StateFeedbackPlantCoefficients<2, 2, 2> MakeVelocityDrivetrainHighHighPlantCoefficients();
-
-StateFeedbackController<2, 2, 2> MakeVelocityDrivetrainHighHighController();
-
-StateFeedbackPlant<2, 2, 2> MakeVelocityDrivetrainPlant();
-
-StateFeedbackLoop<2, 2, 2> MakeVelocityDrivetrainLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_DOG_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/drivetrain/replay_drivetrain.cc b/frc971/control_loops/drivetrain/replay_drivetrain.cc
deleted file mode 100644
index 432efdc..0000000
--- a/frc971/control_loops/drivetrain/replay_drivetrain.cc
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "aos/common/controls/replay_control_loop.h"
-#include "aos/linux_code/init.h"
-
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-
-// Reads one or more log files and sends out all the queue messages (in the
-// correct order and at the correct time) to feed a "live" drivetrain process.
-
-int main(int argc, char **argv) {
- if (argc <= 1) {
- fprintf(stderr, "Need at least one file to replay!\n");
- return EXIT_FAILURE;
- }
-
- ::aos::InitNRT();
-
- ::aos::controls::ControlLoopReplayer<::frc971::control_loops::DrivetrainQueue>
- replayer(&::frc971::control_loops::drivetrain_queue, "drivetrain");
- for (int i = 1; i < argc; ++i) {
- replayer.ProcessFile(argv[i]);
- }
-
- ::aos::Cleanup();
-}
diff --git a/frc971/control_loops/fridge/arm_motor_plant.cc b/frc971/control_loops/fridge/arm_motor_plant.cc
deleted file mode 100644
index 556b812..0000000
--- a/frc971/control_loops/fridge/arm_motor_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "frc971/control_loops/fridge/arm_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeArmPlantCoefficients() {
- Eigen::Matrix<double, 4, 4> A;
- A << 1.0, 0.00479642025454, 0.0, 0.0, 0.0, 0.919688585028, 0.0, 0.0, 0.0, 0.0, 0.999539771613, 0.00479566382645, 0.0, 0.0, -0.18154390621, 0.919241022297;
- Eigen::Matrix<double, 4, 2> B;
- B << 2.46496779984e-05, 2.46496779984e-05, 0.00972420175808, 0.00972420175808, 2.46477449538e-05, -2.46477449538e-05, 0.00972266818532, -0.00972266818532;
- Eigen::Matrix<double, 2, 4> C;
- C << 1, 0, 1, 0, 1, 0, -1, 0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<4, 2, 2> MakeArmController() {
- Eigen::Matrix<double, 4, 2> L;
- L << 0.759844292514, 0.759844292514, 54.2541762188, 54.2541762188, 0.759390396955, -0.759390396955, 54.1048167043, -54.1048167043;
- Eigen::Matrix<double, 2, 4> K;
- K << 320.979606093, 21.0129517955, 884.233784759, 36.3637782119, 320.979606095, 21.0129517956, -884.233784749, -36.3637782119;
- Eigen::Matrix<double, 4, 4> A_inv;
- A_inv << 1.0, -0.00521526561559, 0.0, 0.0, 0.0, 1.08732457517, 0.0, 0.0, 0.0, 0.0, 0.999513354044, -0.00521444313273, 0.0, 0.0, 0.197397150694, 1.08682415753;
- return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeArmPlantCoefficients());
-}
-
-StateFeedbackPlant<4, 2, 2> MakeArmPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(1);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeArmPlantCoefficients()));
- return StateFeedbackPlant<4, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<4, 2, 2> MakeArmLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(1);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeArmController()));
- return StateFeedbackLoop<4, 2, 2>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/fridge/arm_motor_plant.h b/frc971/control_loops/fridge/arm_motor_plant.h
deleted file mode 100644
index 4874ad5..0000000
--- a/frc971/control_loops/fridge/arm_motor_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_FRIDGE_ARM_MOTOR_PLANT_H_
-#define FRC971_CONTROL_LOOPS_FRIDGE_ARM_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeArmPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeArmController();
-
-StateFeedbackPlant<4, 2, 2> MakeArmPlant();
-
-StateFeedbackLoop<4, 2, 2> MakeArmLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_FRIDGE_ARM_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/fridge/elevator_motor_plant.cc b/frc971/control_loops/fridge/elevator_motor_plant.cc
deleted file mode 100644
index e75e668..0000000
--- a/frc971/control_loops/fridge/elevator_motor_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "frc971/control_loops/fridge/elevator_motor_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeElevatorPlantCoefficients() {
- Eigen::Matrix<double, 4, 4> A;
- A << 1.0, 0.00435668193669, 0.0, 0.0, 0.0, 0.754212786054, 0.0, 0.0, 0.0, 0.0, 0.997194498569, 0.00435222083164, 0.0, 0.0, -1.07131589702, 0.751658962986;
- Eigen::Matrix<double, 4, 2> B;
- B << 3.82580284276e-05, 3.82580284276e-05, 0.0146169286307, 0.0146169286307, 3.82387898839e-05, -3.82387898839e-05, 0.0146019613563, -0.0146019613563;
- Eigen::Matrix<double, 2, 4> C;
- C << 1, 0, 1, 0, 1, 0, -1, 0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<4, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<4, 2, 2> MakeElevatorController() {
- Eigen::Matrix<double, 4, 2> L;
- L << 0.677106393027, 0.677106393027, 35.5375738607, 35.5375738607, 0.674426730777, -0.674426730777, 34.7138874344, -34.7138874344;
- Eigen::Matrix<double, 2, 4> K;
- K << 321.310606763, 11.7674534233, 601.047935717, 12.6977148843, 321.310606764, 11.7674534233, -601.047935716, -12.6977148843;
- Eigen::Matrix<double, 4, 4> A_inv;
- A_inv << 1.0, -0.00577646258091, 0.0, 0.0, 0.0, 1.32588576923, 0.0, 0.0, 0.0, 0.0, 0.996613922337, -0.00577054766522, 0.0, 0.0, 1.42044250221, 1.32216599481;
- return StateFeedbackController<4, 2, 2>(L, K, A_inv, MakeElevatorPlantCoefficients());
-}
-
-StateFeedbackPlant<4, 2, 2> MakeElevatorPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>> plants(1);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<4, 2, 2>>(new StateFeedbackPlantCoefficients<4, 2, 2>(MakeElevatorPlantCoefficients()));
- return StateFeedbackPlant<4, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<4, 2, 2> MakeElevatorLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<4, 2, 2>>> controllers(1);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<4, 2, 2>>(new StateFeedbackController<4, 2, 2>(MakeElevatorController()));
- return StateFeedbackLoop<4, 2, 2>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/fridge/elevator_motor_plant.h b/frc971/control_loops/fridge/elevator_motor_plant.h
deleted file mode 100644
index 7efd116..0000000
--- a/frc971/control_loops/fridge/elevator_motor_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_FRIDGE_ELEVATOR_MOTOR_PLANT_H_
-#define FRC971_CONTROL_LOOPS_FRIDGE_ELEVATOR_MOTOR_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<4, 2, 2> MakeElevatorPlantCoefficients();
-
-StateFeedbackController<4, 2, 2> MakeElevatorController();
-
-StateFeedbackPlant<4, 2, 2> MakeElevatorPlant();
-
-StateFeedbackLoop<4, 2, 2> MakeElevatorLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_FRIDGE_ELEVATOR_MOTOR_PLANT_H_
diff --git a/frc971/control_loops/fridge/fridge.cc b/frc971/control_loops/fridge/fridge.cc
deleted file mode 100644
index b5e0ab6..0000000
--- a/frc971/control_loops/fridge/fridge.cc
+++ /dev/null
@@ -1,720 +0,0 @@
-#include "frc971/control_loops/fridge/fridge.h"
-
-#include <cmath>
-
-#include "aos/common/controls/control_loops.q.h"
-#include "aos/common/logging/logging.h"
-
-#include "frc971/control_loops/fridge/elevator_motor_plant.h"
-#include "frc971/control_loops/fridge/integral_arm_plant.h"
-#include "frc971/control_loops/voltage_cap/voltage_cap.h"
-#include "frc971/zeroing/zeroing.h"
-
-#include "frc971/constants.h"
-
-namespace frc971 {
-namespace control_loops {
-
-namespace {
-constexpr double kZeroingVoltage = 4.0;
-constexpr double kElevatorZeroingVelocity = 0.10;
-// What speed we move to our safe height at.
-constexpr double kElevatorSafeHeightVelocity = 0.3;
-constexpr double kArmZeroingVelocity = 0.20;
-} // namespace
-
-template <int S>
-void CappedStateFeedbackLoop<S>::CapU() {
- VoltageCap(max_voltage_, this->U(0, 0), this->U(1, 0), &this->mutable_U(0, 0),
- &this->mutable_U(1, 0));
-}
-
-template <int S>
-Eigen::Matrix<double, 2, 1>
-CappedStateFeedbackLoop<S>::UnsaturateOutputGoalChange() {
- // Compute the K matrix used to compensate for position errors.
- Eigen::Matrix<double, 2, 2> Kp;
- Kp.setZero();
- Kp.col(0) = this->K().col(0);
- Kp.col(1) = this->K().col(2);
-
- Eigen::Matrix<double, 2, 2> Kp_inv = Kp.inverse();
-
- // Compute how much we need to change R in order to achieve the change in U
- // that was observed.
- Eigen::Matrix<double, 2, 1> deltaR =
- -Kp_inv * (this->U_uncapped() - this->U());
- return deltaR;
-}
-
-Fridge::Fridge(control_loops::FridgeQueue *fridge)
- : aos::controls::ControlLoop<control_loops::FridgeQueue>(fridge),
- arm_loop_(new CappedStateFeedbackLoop<5>(
- StateFeedbackLoop<5, 2, 2>(MakeIntegralArmLoop()))),
- elevator_loop_(new CappedStateFeedbackLoop<4>(
- StateFeedbackLoop<4, 2, 2>(MakeElevatorLoop()))),
- left_arm_estimator_(constants::GetValues().fridge.left_arm_zeroing),
- right_arm_estimator_(constants::GetValues().fridge.right_arm_zeroing),
- left_elevator_estimator_(constants::GetValues().fridge.left_elev_zeroing),
- right_elevator_estimator_(
- constants::GetValues().fridge.right_elev_zeroing),
- last_profiling_type_(ProfilingType::ANGLE_HEIGHT_PROFILING),
- kinematics_(constants::GetValues().fridge.arm_length,
- constants::GetValues().fridge.elevator.upper_limit,
- constants::GetValues().fridge.elevator.lower_limit,
- constants::GetValues().fridge.arm.upper_limit,
- constants::GetValues().fridge.arm.lower_limit),
- arm_profile_(::aos::controls::kLoopFrequency),
- elevator_profile_(::aos::controls::kLoopFrequency),
- x_profile_(::aos::controls::kLoopFrequency),
- y_profile_(::aos::controls::kLoopFrequency) {}
-
-void Fridge::UpdateZeroingState() {
- if (left_elevator_estimator_.offset_ratio_ready() < 1.0 ||
- right_elevator_estimator_.offset_ratio_ready() < 1.0 ||
- left_arm_estimator_.offset_ratio_ready() < 1.0 ||
- right_arm_estimator_.offset_ratio_ready() < 1.0) {
- state_ = INITIALIZING;
- } else if (!left_elevator_estimator_.zeroed() ||
- !right_elevator_estimator_.zeroed()) {
- state_ = ZEROING_ELEVATOR;
- } else if (!left_arm_estimator_.zeroed() || !right_arm_estimator_.zeroed()) {
- state_ = ZEROING_ARM;
- } else {
- state_ = RUNNING;
- }
-}
-
-void Fridge::Correct() {
- {
- Eigen::Matrix<double, 2, 1> Y;
- Y << left_elevator(), right_elevator();
- elevator_loop_->Correct(Y);
- }
-
- {
- Eigen::Matrix<double, 2, 1> Y;
- Y << left_arm(), right_arm();
- arm_loop_->Correct(Y);
- }
-}
-
-void Fridge::SetElevatorOffset(double left_offset, double right_offset) {
- LOG(INFO, "Changing Elevator offset from %f, %f to %f, %f\n",
- left_elevator_offset_, right_elevator_offset_, left_offset, right_offset);
- double left_doffset = left_offset - left_elevator_offset_;
- double right_doffset = right_offset - right_elevator_offset_;
-
- // Adjust the average height and height difference between the two sides.
- // The derivatives of both should not need to be updated since the speeds
- // haven't changed.
- // The height difference is calculated as left - right, not right - left.
- elevator_loop_->mutable_X_hat(0, 0) += (left_doffset + right_doffset) / 2;
- elevator_loop_->mutable_X_hat(2, 0) += (left_doffset - right_doffset) / 2;
-
- // Modify the zeroing goal.
- elevator_goal_ += (left_doffset + right_doffset) / 2;
-
- // Update the cached offset values to the actual values.
- left_elevator_offset_ = left_offset;
- right_elevator_offset_ = right_offset;
-}
-
-void Fridge::SetArmOffset(double left_offset, double right_offset) {
- LOG(INFO, "Changing Arm offset from %f, %f to %f, %f\n", left_arm_offset_,
- right_arm_offset_, left_offset, right_offset);
- double left_doffset = left_offset - left_arm_offset_;
- double right_doffset = right_offset - right_arm_offset_;
-
- // Adjust the average angle and angle difference between the two sides.
- // The derivatives of both should not need to be updated since the speeds
- // haven't changed.
- arm_loop_->mutable_X_hat(0, 0) += (left_doffset + right_doffset) / 2;
- arm_loop_->mutable_X_hat(2, 0) += (left_doffset - right_doffset) / 2;
-
- // Modify the zeroing goal.
- arm_goal_ += (left_doffset + right_doffset) / 2;
-
- // Update the cached offset values to the actual values.
- left_arm_offset_ = left_offset;
- right_arm_offset_ = right_offset;
-}
-
-double Fridge::estimated_left_elevator() {
- return current_position_.elevator.left.encoder +
- left_elevator_estimator_.offset();
-}
-double Fridge::estimated_right_elevator() {
- return current_position_.elevator.right.encoder +
- right_elevator_estimator_.offset();
-}
-
-double Fridge::estimated_elevator() {
- return (estimated_left_elevator() + estimated_right_elevator()) / 2.0;
-}
-
-double Fridge::estimated_left_arm() {
- return current_position_.arm.left.encoder + left_arm_estimator_.offset();
-}
-double Fridge::estimated_right_arm() {
- return current_position_.arm.right.encoder + right_arm_estimator_.offset();
-}
-double Fridge::estimated_arm() {
- return (estimated_left_arm() + estimated_right_arm()) / 2.0;
-}
-
-double Fridge::left_elevator() {
- return current_position_.elevator.left.encoder + left_elevator_offset_;
-}
-double Fridge::right_elevator() {
- return current_position_.elevator.right.encoder + right_elevator_offset_;
-}
-
-double Fridge::elevator() { return (left_elevator() + right_elevator()) / 2.0; }
-
-double Fridge::left_arm() {
- return current_position_.arm.left.encoder + left_arm_offset_;
-}
-double Fridge::right_arm() {
- return current_position_.arm.right.encoder + right_arm_offset_;
-}
-double Fridge::arm() { return (left_arm() + right_arm()) / 2.0; }
-
-double Fridge::elevator_zeroing_velocity() {
- double average_elevator =
- (constants::GetValues().fridge.elevator.lower_limit +
- constants::GetValues().fridge.elevator.upper_limit) /
- 2.0;
-
- const double pulse_width = ::std::max(
- constants::GetValues().fridge.left_elev_zeroing.index_difference,
- constants::GetValues().fridge.right_elev_zeroing.index_difference);
-
- if (elevator_zeroing_velocity_ == 0) {
- if (estimated_elevator() > average_elevator) {
- elevator_zeroing_velocity_ = -kElevatorZeroingVelocity;
- } else {
- elevator_zeroing_velocity_ = kElevatorZeroingVelocity;
- }
- } else if (elevator_zeroing_velocity_ > 0 &&
- estimated_elevator() > average_elevator + 1.1 * pulse_width) {
- elevator_zeroing_velocity_ = -kElevatorZeroingVelocity;
- } else if (elevator_zeroing_velocity_ < 0 &&
- estimated_elevator() < average_elevator - 1.1 * pulse_width) {
- elevator_zeroing_velocity_ = kElevatorZeroingVelocity;
- }
- return elevator_zeroing_velocity_;
-}
-
-double Fridge::UseUnlessZero(double target_value, double default_value) {
- if (target_value != 0.0) {
- return target_value;
- } else {
- return default_value;
- }
-}
-
-double Fridge::arm_zeroing_velocity() {
- const double average_arm = (constants::GetValues().fridge.arm.lower_limit +
- constants::GetValues().fridge.arm.upper_limit) /
- 2.0;
- const double pulse_width = ::std::max(
- constants::GetValues().fridge.right_arm_zeroing.index_difference,
- constants::GetValues().fridge.left_arm_zeroing.index_difference);
-
- if (arm_zeroing_velocity_ == 0) {
- if (estimated_arm() > average_arm) {
- arm_zeroing_velocity_ = -kArmZeroingVelocity;
- } else {
- arm_zeroing_velocity_ = kArmZeroingVelocity;
- }
- } else if (arm_zeroing_velocity_ > 0.0 &&
- estimated_arm() > average_arm + 1.1 * pulse_width) {
- arm_zeroing_velocity_ = -kArmZeroingVelocity;
- } else if (arm_zeroing_velocity_ < 0.0 && estimated_arm() < average_arm) {
- arm_zeroing_velocity_ = kArmZeroingVelocity;
- }
- return arm_zeroing_velocity_;
-}
-
-void Fridge::RunIteration(const control_loops::FridgeQueue::Goal *unsafe_goal,
- const control_loops::FridgeQueue::Position *position,
- control_loops::FridgeQueue::Output *output,
- control_loops::FridgeQueue::Status *status) {
- if (WasReset()) {
- LOG(ERROR, "WPILib reset, restarting\n");
- left_elevator_estimator_.Reset();
- right_elevator_estimator_.Reset();
- left_arm_estimator_.Reset();
- right_arm_estimator_.Reset();
- state_ = UNINITIALIZED;
- }
-
- // Get a reference to the constants struct since we use it so often in this
- // code.
- const auto &values = constants::GetValues();
-
- // Bool to track if we should turn the motors on or not.
- bool disable = output == nullptr;
-
- // Save the current position so it can be used easily in the class.
- current_position_ = *position;
-
- left_elevator_estimator_.UpdateEstimate(position->elevator.left);
- right_elevator_estimator_.UpdateEstimate(position->elevator.right);
- left_arm_estimator_.UpdateEstimate(position->arm.left);
- right_arm_estimator_.UpdateEstimate(position->arm.right);
-
- if (state_ != UNINITIALIZED) {
- Correct();
- }
-
- // Zeroing will work as follows:
- // At startup, record the offset of the two halves of the two subsystems.
- // Then, start moving the elevator towards the center until both halves are
- // zeroed.
- // Then, start moving the claw towards the center until both halves are
- // zeroed.
- // Then, done!
-
- // We'll then need code to do sanity checking on values.
-
- // Now, we need to figure out which way to go.
-
- switch (state_) {
- case UNINITIALIZED:
- LOG(DEBUG, "Uninitialized\n");
- // Startup. Assume that we are at the origin everywhere.
- // This records the encoder offset between the two sides of the elevator.
- left_elevator_offset_ = -position->elevator.left.encoder;
- right_elevator_offset_ = -position->elevator.right.encoder;
- left_arm_offset_ = -position->arm.left.encoder;
- right_arm_offset_ = -position->arm.right.encoder;
- elevator_loop_->mutable_X_hat().setZero();
- arm_loop_->mutable_X_hat().setZero();
- LOG(INFO, "Initializing arm offsets to %f, %f\n", left_arm_offset_,
- right_arm_offset_);
- LOG(INFO, "Initializing elevator offsets to %f, %f\n",
- left_elevator_offset_, right_elevator_offset_);
- Correct();
- state_ = INITIALIZING;
- disable = true;
- break;
-
- case INITIALIZING:
- LOG(DEBUG, "Waiting for accurate initial position.\n");
- disable = true;
- // Update state_ to accurately represent the state of the zeroing
- // estimators.
- UpdateZeroingState();
- if (state_ != INITIALIZING) {
- // Set the goals to where we are now.
- elevator_goal_ = elevator();
- arm_goal_ = arm();
- }
- break;
-
- case ZEROING_ELEVATOR:
- LOG(DEBUG, "Zeroing elevator\n");
-
- // Update state_ to accurately represent the state of the zeroing
- // estimators.
- UpdateZeroingState();
- if (left_elevator_estimator_.zeroed() &&
- right_elevator_estimator_.zeroed()) {
- SetElevatorOffset(left_elevator_estimator_.offset(),
- right_elevator_estimator_.offset());
- LOG(DEBUG, "Zeroed the elevator!\n");
-
- if (elevator() < values.fridge.arm_zeroing_height &&
- state_ != INITIALIZING) {
- // Move the elevator to a safe height before we start zeroing the arm,
- // so that we don't crash anything.
- LOG(DEBUG, "Moving elevator to safe height.\n");
- if (elevator_goal_ < values.fridge.arm_zeroing_height) {
- elevator_goal_ += kElevatorSafeHeightVelocity *
- ::aos::controls::kLoopFrequency.ToSeconds();
- elevator_goal_velocity_ = kElevatorSafeHeightVelocity;
- state_ = ZEROING_ELEVATOR;
- } else {
- // We want it stopped at whatever height it's currently set to.
- elevator_goal_velocity_ = 0;
- }
- }
- } else if (!disable) {
- elevator_goal_velocity_ = elevator_zeroing_velocity();
- elevator_goal_ += elevator_goal_velocity_ *
- ::aos::controls::kLoopFrequency.ToSeconds();
- }
-
- // Bypass motion profiles while we are zeroing.
- // This is also an important step right after the elevator is zeroed and
- // we reach into the elevator's state matrix and change it based on the
- // newly-obtained offset.
- {
- Eigen::Matrix<double, 2, 1> current;
- current.setZero();
- current << elevator_goal_, elevator_goal_velocity_;
- elevator_profile_.MoveCurrentState(current);
- }
- break;
-
- case ZEROING_ARM:
- LOG(DEBUG, "Zeroing the arm\n");
-
- if (elevator() < values.fridge.arm_zeroing_height - 0.10 ||
- elevator_goal_ < values.fridge.arm_zeroing_height) {
- LOG(INFO,
- "Going back to ZEROING_ELEVATOR until it gets high enough to "
- "safely zero the arm\n");
- state_ = ZEROING_ELEVATOR;
- break;
- }
-
- // Update state_ to accurately represent the state of the zeroing
- // estimators.
- UpdateZeroingState();
- if (left_arm_estimator_.zeroed() && right_arm_estimator_.zeroed()) {
- SetArmOffset(left_arm_estimator_.offset(),
- right_arm_estimator_.offset());
- LOG(DEBUG, "Zeroed the arm!\n");
- } else if (!disable) {
- arm_goal_velocity_ = arm_zeroing_velocity();
- arm_goal_ +=
- arm_goal_velocity_ * ::aos::controls::kLoopFrequency.ToSeconds();
- }
-
- // Bypass motion profiles while we are zeroing.
- // This is also an important step right after the arm is zeroed and
- // we reach into the arm's state matrix and change it based on the
- // newly-obtained offset.
- {
- Eigen::Matrix<double, 2, 1> current;
- current.setZero();
- current << arm_goal_, arm_goal_velocity_;
- arm_profile_.MoveCurrentState(current);
- }
- break;
-
- case RUNNING:
- LOG(DEBUG, "Running!\n");
- if (unsafe_goal) {
- // Handle the case where we switch between the types of profiling.
- ProfilingType new_profiling_type =
- static_cast<ProfilingType>(unsafe_goal->profiling_type);
-
- if (last_profiling_type_ != new_profiling_type) {
- // Reset the height/angle profiles.
- Eigen::Matrix<double, 2, 1> current;
- current.setZero();
- current << arm_goal_, arm_goal_velocity_;
- arm_profile_.MoveCurrentState(current);
- current << elevator_goal_, elevator_goal_velocity_;
- elevator_profile_.MoveCurrentState(current);
-
- // Reset the x/y profiles.
- aos::util::ElevatorArmKinematics::KinematicResult x_y_result;
- kinematics_.ForwardKinematic(elevator_goal_, arm_goal_,
- elevator_goal_velocity_,
- arm_goal_velocity_, &x_y_result);
- current << x_y_result.fridge_x, x_y_result.fridge_x_velocity;
- x_profile_.MoveCurrentState(current);
- current << x_y_result.fridge_h, x_y_result.fridge_h_velocity;
- y_profile_.MoveCurrentState(current);
-
- last_profiling_type_ = new_profiling_type;
- }
-
- if (new_profiling_type == ProfilingType::ANGLE_HEIGHT_PROFILING) {
- // Pick a set of sane arm defaults if none are specified.
- arm_profile_.set_maximum_velocity(
- UseUnlessZero(unsafe_goal->max_angular_velocity, 1.0));
- arm_profile_.set_maximum_acceleration(
- UseUnlessZero(unsafe_goal->max_angular_acceleration, 3.0));
- elevator_profile_.set_maximum_velocity(
- UseUnlessZero(unsafe_goal->max_velocity, 0.50));
- elevator_profile_.set_maximum_acceleration(
- UseUnlessZero(unsafe_goal->max_acceleration, 2.0));
-
- // Use the profiles to limit the arm's movements.
- const double unfiltered_arm_goal = ::std::max(
- ::std::min(unsafe_goal->angle, values.fridge.arm.upper_limit),
- values.fridge.arm.lower_limit);
- ::Eigen::Matrix<double, 2, 1> arm_goal_state = arm_profile_.Update(
- unfiltered_arm_goal, unsafe_goal->angular_velocity);
- arm_goal_ = arm_goal_state(0, 0);
- arm_goal_velocity_ = arm_goal_state(1, 0);
-
- // Use the profiles to limit the elevator's movements.
- const double unfiltered_elevator_goal =
- ::std::max(::std::min(unsafe_goal->height,
- values.fridge.elevator.upper_limit),
- values.fridge.elevator.lower_limit);
- ::Eigen::Matrix<double, 2, 1> elevator_goal_state =
- elevator_profile_.Update(unfiltered_elevator_goal,
- unsafe_goal->velocity);
- elevator_goal_ = elevator_goal_state(0, 0);
- elevator_goal_velocity_ = elevator_goal_state(1, 0);
- } else if (new_profiling_type == ProfilingType::X_Y_PROFILING) {
- // Use x/y profiling
- aos::util::ElevatorArmKinematics::KinematicResult kinematic_result;
-
- x_profile_.set_maximum_velocity(
- UseUnlessZero(unsafe_goal->max_x_velocity, 0.5));
- x_profile_.set_maximum_acceleration(
- UseUnlessZero(unsafe_goal->max_x_acceleration, 2.0));
- y_profile_.set_maximum_velocity(
- UseUnlessZero(unsafe_goal->max_y_velocity, 0.50));
- y_profile_.set_maximum_acceleration(
- UseUnlessZero(unsafe_goal->max_y_acceleration, 2.0));
-
- // Limit the goals before we update the profiles.
- kinematics_.InverseKinematic(
- unsafe_goal->x, unsafe_goal->y, unsafe_goal->x_velocity,
- unsafe_goal->y_velocity, &kinematic_result);
-
- // Use the profiles to limit the x movements.
- ::Eigen::Matrix<double, 2, 1> x_goal_state = x_profile_.Update(
- kinematic_result.fridge_x, kinematic_result.fridge_x_velocity);
-
- // Use the profiles to limit the y movements.
- ::Eigen::Matrix<double, 2, 1> y_goal_state = y_profile_.Update(
- kinematic_result.fridge_h, kinematic_result.fridge_h_velocity);
-
- // Convert x/y goal states into arm/elevator goals.
- // The inverse kinematics functions automatically perform range
- // checking and adjust the results so that they're always valid.
- kinematics_.InverseKinematic(x_goal_state(0, 0), y_goal_state(0, 0),
- x_goal_state(1, 0), y_goal_state(1, 0),
- &kinematic_result);
-
- // Store the appropriate inverse kinematic results in the
- // arm/elevator goals.
- arm_goal_ = kinematic_result.arm_angle;
- arm_goal_velocity_ = kinematic_result.arm_velocity;
-
- elevator_goal_ = kinematic_result.elevator_height;
- elevator_goal_velocity_ = kinematic_result.arm_velocity;
- } else {
- LOG(ERROR, "Unknown profiling_type: %d\n",
- unsafe_goal->profiling_type);
- }
- }
-
- // Update state_ to accurately represent the state of the zeroing
- // estimators.
- UpdateZeroingState();
-
- if (state_ != RUNNING && state_ != ESTOP) {
- state_ = UNINITIALIZED;
- }
- break;
-
- case ESTOP:
- LOG(ERROR, "Estop\n");
- disable = true;
- break;
- }
-
- // Commence death if either left/right tracking error gets too big. This
- // should run immediately after the SetArmOffset and SetElevatorOffset
- // functions to double-check that the hardware is in a sane state.
- if (::std::abs(left_arm() - right_arm()) >=
- values.max_allowed_left_right_arm_difference) {
- LOG(ERROR, "The arms are too far apart. |%f - %f| > %f\n", left_arm(),
- right_arm(), values.max_allowed_left_right_arm_difference);
-
- // Indicate an ESTOP condition and stop the motors.
- if (output) {
- state_ = ESTOP;
- }
- disable = true;
- }
-
- if (::std::abs(left_elevator() - right_elevator()) >=
- values.max_allowed_left_right_elevator_difference) {
- LOG(ERROR, "The elevators are too far apart. |%f - %f| > %f\n",
- left_elevator(), right_elevator(),
- values.max_allowed_left_right_elevator_difference);
-
- // Indicate an ESTOP condition and stop the motors.
- if (output) {
- state_ = ESTOP;
- }
- disable = true;
- }
-
- // Limit the goals so we can't exceed the hardware limits if we are RUNNING.
- if (state_ == RUNNING) {
- // Limit the arm goal to min/max allowable angles.
- if (arm_goal_ >= values.fridge.arm.upper_limit) {
- LOG(WARNING, "Arm goal above limit, %f > %f\n", arm_goal_,
- values.fridge.arm.upper_limit);
- arm_goal_ = values.fridge.arm.upper_limit;
- }
- if (arm_goal_ <= values.fridge.arm.lower_limit) {
- LOG(WARNING, "Arm goal below limit, %f < %f\n", arm_goal_,
- values.fridge.arm.lower_limit);
- arm_goal_ = values.fridge.arm.lower_limit;
- }
-
- // Limit the elevator goal to min/max allowable heights.
- if (elevator_goal_ >= values.fridge.elevator.upper_limit) {
- LOG(WARNING, "Elevator goal above limit, %f > %f\n", elevator_goal_,
- values.fridge.elevator.upper_limit);
- elevator_goal_ = values.fridge.elevator.upper_limit;
- }
- if (elevator_goal_ <= values.fridge.elevator.lower_limit) {
- LOG(WARNING, "Elevator goal below limit, %f < %f\n", elevator_goal_,
- values.fridge.elevator.lower_limit);
- elevator_goal_ = values.fridge.elevator.lower_limit;
- }
- }
-
- // Check the lower level hardware limit as well.
- if (state_ == RUNNING) {
- if (left_arm() >= values.fridge.arm.upper_hard_limit ||
- left_arm() <= values.fridge.arm.lower_hard_limit) {
- LOG(ERROR, "Left arm at %f out of bounds [%f, %f], ESTOPing\n",
- left_arm(), values.fridge.arm.lower_hard_limit,
- values.fridge.arm.upper_hard_limit);
- if (output) {
- state_ = ESTOP;
- }
- }
-
- if (right_arm() >= values.fridge.arm.upper_hard_limit ||
- right_arm() <= values.fridge.arm.lower_hard_limit) {
- LOG(ERROR, "Right arm at %f out of bounds [%f, %f], ESTOPing\n",
- right_arm(), values.fridge.arm.lower_hard_limit,
- values.fridge.arm.upper_hard_limit);
- if (output) {
- state_ = ESTOP;
- }
- }
-
- if (left_elevator() >= values.fridge.elevator.upper_hard_limit) {
- LOG(ERROR, "Left elevator at %f out of bounds [%f, %f], ESTOPing\n",
- left_elevator(), values.fridge.elevator.lower_hard_limit,
- values.fridge.elevator.upper_hard_limit);
- if (output) {
- state_ = ESTOP;
- }
- }
-
- if (right_elevator() >= values.fridge.elevator.upper_hard_limit) {
- LOG(ERROR, "Right elevator at %f out of bounds [%f, %f], ESTOPing\n",
- right_elevator(), values.fridge.elevator.lower_hard_limit,
- values.fridge.elevator.upper_hard_limit);
- if (output) {
- state_ = ESTOP;
- }
- }
- }
-
- // Set the goals.
- arm_loop_->mutable_R() << arm_goal_, arm_goal_velocity_, 0.0, 0.0, 0.0;
- elevator_loop_->mutable_R() << elevator_goal_, elevator_goal_velocity_, 0.0,
- 0.0;
-
- const double max_voltage = state_ == RUNNING ? 12.0 : kZeroingVoltage;
- arm_loop_->set_max_voltage(max_voltage);
- elevator_loop_->set_max_voltage(max_voltage);
-
- if (state_ == ESTOP) {
- disable = true;
- }
- arm_loop_->Update(disable);
- elevator_loop_->Update(disable);
-
- if (state_ == INITIALIZING || state_ == ZEROING_ELEVATOR ||
- state_ == ZEROING_ARM) {
- if (arm_loop_->U() != arm_loop_->U_uncapped()) {
- Eigen::Matrix<double, 2, 1> deltaR =
- arm_loop_->UnsaturateOutputGoalChange();
-
- // Move the average arm goal by the amount observed.
- LOG(WARNING, "Moving arm goal by %f to handle saturation\n",
- deltaR(0, 0));
- arm_goal_ += deltaR(0, 0);
- }
-
- if (elevator_loop_->U() != elevator_loop_->U_uncapped()) {
- Eigen::Matrix<double, 2, 1> deltaR =
- elevator_loop_->UnsaturateOutputGoalChange();
-
- // Move the average elevator goal by the amount observed.
- LOG(WARNING, "Moving elevator goal by %f to handle saturation\n",
- deltaR(0, 0));
- elevator_goal_ += deltaR(0, 0);
- }
- }
-
- if (output) {
- output->left_arm = arm_loop_->U(0, 0);
- output->right_arm = arm_loop_->U(1, 0);
- output->left_elevator = elevator_loop_->U(0, 0);
- output->right_elevator = elevator_loop_->U(1, 0);
- if (unsafe_goal) {
- output->grabbers = unsafe_goal->grabbers;
- } else {
- output->grabbers.top_front = false;
- output->grabbers.top_back = false;
- output->grabbers.bottom_front = false;
- output->grabbers.bottom_back = false;
- }
- }
-
- // TODO(austin): Populate these fully.
- status->zeroed = state_ == RUNNING;
-
- status->angle = arm_loop_->X_hat(0, 0);
- status->angular_velocity = arm_loop_->X_hat(1, 0);
- status->height = elevator_loop_->X_hat(0, 0);
- status->velocity = elevator_loop_->X_hat(1, 0);
-
- status->goal_angle = arm_goal_;
- status->goal_angular_velocity = arm_goal_velocity_;
- status->goal_height = elevator_goal_;
- status->goal_velocity = elevator_goal_velocity_;
-
- // Populate the same status, but in X/Y co-ordinates.
- aos::util::ElevatorArmKinematics::KinematicResult x_y_status;
- kinematics_.ForwardKinematic(status->height, status->angle,
- status->velocity, status->angular_velocity,
- &x_y_status);
- status->x = x_y_status.fridge_x;
- status->y = x_y_status.fridge_h;
- status->x_velocity = x_y_status.fridge_x_velocity;
- status->y_velocity = x_y_status.fridge_h_velocity;
-
- kinematics_.ForwardKinematic(status->goal_height, status->goal_angle,
- status->goal_velocity, status->goal_angular_velocity,
- &x_y_status);
- status->goal_x = x_y_status.fridge_x;
- status->goal_y = x_y_status.fridge_h;
- status->goal_x_velocity = x_y_status.fridge_x_velocity;
- status->goal_y_velocity = x_y_status.fridge_h_velocity;
-
- if (unsafe_goal) {
- status->grabbers = unsafe_goal->grabbers;
- } else {
- status->grabbers.top_front = false;
- status->grabbers.top_back = false;
- status->grabbers.bottom_front = false;
- status->grabbers.bottom_back = false;
- }
- zeroing::PopulateEstimatorState(left_arm_estimator_, &status->left_arm_state);
- zeroing::PopulateEstimatorState(right_arm_estimator_,
- &status->right_arm_state);
- zeroing::PopulateEstimatorState(left_elevator_estimator_,
- &status->left_elevator_state);
- zeroing::PopulateEstimatorState(right_elevator_estimator_,
- &status->right_elevator_state);
- status->estopped = (state_ == ESTOP);
- status->state = state_;
- last_state_ = state_;
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/fridge/fridge.gyp b/frc971/control_loops/fridge/fridge.gyp
deleted file mode 100644
index aaf3153..0000000
--- a/frc971/control_loops/fridge/fridge.gyp
+++ /dev/null
@@ -1,89 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'replay_fridge',
- 'type': 'executable',
- 'variables': {
- 'no_rsync': 1,
- },
- 'sources': [
- 'replay_fridge.cc',
- ],
- 'dependencies': [
- 'fridge_queue',
- '<(AOS)/common/controls/controls.gyp:replay_control_loop',
- '<(AOS)/linux_code/linux_code.gyp:init',
- ],
- },
- {
- 'target_name': 'fridge_queue',
- 'type': 'static_library',
- 'sources': ['fridge.q'],
- 'variables': {
- 'header_path': 'frc971/control_loops/fridge',
- },
- 'dependencies': [
- '<(AOS)/common/controls/controls.gyp:control_loop_queues',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
- '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
- ],
- 'export_dependent_settings': [
- '<(AOS)/common/controls/controls.gyp:control_loop_queues',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
- '<(DEPTH)/frc971/zeroing/zeroing.gyp:zeroing',
- ],
- 'includes': ['../../../aos/build/queues.gypi'],
- },
- {
- 'target_name': 'fridge_lib',
- 'type': 'static_library',
- 'sources': [
- 'fridge.cc',
- 'integral_arm_plant.cc',
- 'elevator_motor_plant.cc',
- ],
- 'dependencies': [
- 'fridge_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(AOS)/common/util/util.gyp:trapezoid_profile',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/control_loops/voltage_cap/voltage_cap.gyp:voltage_cap',
- ],
- 'export_dependent_settings': [
- 'fridge_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(AOS)/common/util/util.gyp:trapezoid_profile',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- ],
- },
- {
- 'target_name': 'fridge_lib_test',
- 'type': 'executable',
- 'sources': [
- 'fridge_lib_test.cc',
- 'arm_motor_plant.cc',
- ],
- 'dependencies': [
- '<(EXTERNALS):gtest',
- 'fridge_lib',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(AOS)/common/controls/controls.gyp:control_loop_test',
- '<(AOS)/common/common.gyp:time',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:position_sensor_sim',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:team_number_test_environment',
- ],
- },
- {
- 'target_name': 'fridge',
- 'type': 'executable',
- 'sources': [
- 'fridge_main.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- 'fridge_lib',
- ],
- },
- ],
-}
diff --git a/frc971/control_loops/fridge/fridge.h b/frc971/control_loops/fridge/fridge.h
deleted file mode 100644
index d1fbc68..0000000
--- a/frc971/control_loops/fridge/fridge.h
+++ /dev/null
@@ -1,172 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_FRIDGE_H_
-#define FRC971_CONTROL_LOOPS_FRIDGE_H_
-
-#include <memory>
-
-#include "aos/common/controls/control_loop.h"
-#include "aos/common/util/trapezoid_profile.h"
-#include "frc971/control_loops/state_feedback_loop.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "frc971/zeroing/zeroing.h"
-#include "aos/common/util/kinematics.h"
-
-namespace frc971 {
-namespace control_loops {
-namespace testing {
-class FridgeTest_DisabledGoalTest_Test;
-class FridgeTest_ArmGoalPositiveWindupTest_Test;
-class FridgeTest_ElevatorGoalPositiveWindupTest_Test;
-class FridgeTest_ArmGoalNegativeWindupTest_Test;
-class FridgeTest_ElevatorGoalNegativeWindupTest_Test;
-class FridgeTest_SafeArmZeroing_Test;
-} // namespace testing
-
-template<int S>
-class CappedStateFeedbackLoop : public StateFeedbackLoop<S, 2, 2> {
- public:
- CappedStateFeedbackLoop(StateFeedbackLoop<S, 2, 2> &&loop)
- : StateFeedbackLoop<S, 2, 2>(::std::move(loop)), max_voltage_(12.0) {}
-
- void set_max_voltage(double max_voltage) {
- max_voltage_ = ::std::max(0.0, ::std::min(12.0, max_voltage));
- }
-
- void CapU() override;
-
- // Returns the amount to change the position goals (average and difference) in
- // order to no longer saturate the controller.
- Eigen::Matrix<double, 2, 1> UnsaturateOutputGoalChange();
-
- private:
- double max_voltage_;
-};
-
-class Fridge
- : public aos::controls::ControlLoop<control_loops::FridgeQueue> {
- public:
- explicit Fridge(
- control_loops::FridgeQueue *fridge_queue = &control_loops::fridge_queue);
-
- enum State {
- // Waiting to receive data before doing anything.
- UNINITIALIZED = 0,
- // Estimating the starting location.
- INITIALIZING = 1,
- // Moving the elevator to find an index pulse.
- ZEROING_ELEVATOR = 2,
- // Moving the arm to find an index pulse.
- ZEROING_ARM = 3,
- // All good!
- RUNNING = 4,
- // Internal error caused the fridge to abort.
- ESTOP = 5,
- };
-
- enum class ProfilingType : int32_t {
- // Use angle/height to specify the fridge goal.
- ANGLE_HEIGHT_PROFILING = 0,
- // Use x/y co-ordinates to specify the fridge goal.
- X_Y_PROFILING = 1,
- };
-
- State state() const { return state_; }
-
- protected:
- void RunIteration(const control_loops::FridgeQueue::Goal *goal,
- const control_loops::FridgeQueue::Position *position,
- control_loops::FridgeQueue::Output *output,
- control_loops::FridgeQueue::Status *status) override;
-
- private:
- friend class testing::FridgeTest_DisabledGoalTest_Test;
- friend class testing::FridgeTest_ElevatorGoalPositiveWindupTest_Test;
- friend class testing::FridgeTest_ArmGoalPositiveWindupTest_Test;
- friend class testing::FridgeTest_ElevatorGoalNegativeWindupTest_Test;
- friend class testing::FridgeTest_ArmGoalNegativeWindupTest_Test;
- friend class testing::FridgeTest_SafeArmZeroing_Test;
-
- // Sets state_ to the correct state given the current state of the zeroing
- // estimators.
- void UpdateZeroingState();
-
- void SetElevatorOffset(double left_offset, double right_offset);
- void SetArmOffset(double left_offset, double right_offset);
-
- // Getters for the current elevator positions.
- double left_elevator();
- double right_elevator();
- double elevator();
-
- // Getters for the current arm positions.
- double left_arm();
- double right_arm();
- double arm();
-
- // Our best guess at the current position of the elevator.
- double estimated_left_elevator();
- double estimated_right_elevator();
- double estimated_elevator();
-
- // Our best guess at the current position of the arm.
- double estimated_left_arm();
- double estimated_right_arm();
- double estimated_arm();
-
- // Returns the current zeroing velocity for either subsystem.
- // If the subsystem is too far away from the center, these will switch
- // directions.
- double elevator_zeroing_velocity();
- double arm_zeroing_velocity();
-
- // Corrects the Observer with the current position.
- void Correct();
-
- double UseUnlessZero(double target_value, double default_value);
-
- // The state feedback control loop or loops to talk to.
- ::std::unique_ptr<CappedStateFeedbackLoop<5>> arm_loop_;
- ::std::unique_ptr<CappedStateFeedbackLoop<4>> elevator_loop_;
-
- zeroing::ZeroingEstimator left_arm_estimator_;
- zeroing::ZeroingEstimator right_arm_estimator_;
- zeroing::ZeroingEstimator left_elevator_estimator_;
- zeroing::ZeroingEstimator right_elevator_estimator_;
-
- // Offsets from the encoder position to the absolute position. Add these to
- // the encoder position to get the absolute position.
- double left_elevator_offset_ = 0.0;
- double right_elevator_offset_ = 0.0;
- double left_arm_offset_ = 0.0;
- double right_arm_offset_ = 0.0;
-
- // Current velocity to move at while zeroing.
- double elevator_zeroing_velocity_ = 0.0;
- double arm_zeroing_velocity_ = 0.0;
-
- // The goals for the elevator and arm.
- double elevator_goal_ = 0.0;
- double arm_goal_ = 0.0;
-
- double arm_goal_velocity_ = 0.0;
- double elevator_goal_velocity_ = 0.0;
-
- State state_ = UNINITIALIZED;
- State last_state_ = UNINITIALIZED;
-
- control_loops::FridgeQueue::Position current_position_;
-
- ProfilingType last_profiling_type_;
- aos::util::ElevatorArmKinematics kinematics_;
-
- aos::util::TrapezoidProfile arm_profile_;
- aos::util::TrapezoidProfile elevator_profile_;
-
- aos::util::TrapezoidProfile x_profile_;
- aos::util::TrapezoidProfile y_profile_;
-};
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_FRIDGE_H_
-
diff --git a/frc971/control_loops/fridge/fridge.q b/frc971/control_loops/fridge/fridge.q
deleted file mode 100644
index 257374d..0000000
--- a/frc971/control_loops/fridge/fridge.q
+++ /dev/null
@@ -1,152 +0,0 @@
-package frc971.control_loops;
-
-import "aos/common/controls/control_loops.q";
-import "frc971/control_loops/control_loops.q";
-
-// Represents states for all of the box-grabbing pistons.
-// true is grabbed and false is retracted for all of them.
-struct GrabberPistons {
- bool top_front;
- bool top_back;
- bool bottom_front;
- bool bottom_back;
-};
-
-queue_group FridgeQueue {
- implements aos.control_loops.ControlLoop;
-
- // All angles are in radians with 0 sticking straight up.
- // Rotating up and into the robot (towards the back
- // where boxes are placed) is positive. Positive output voltage moves all
- // mechanisms in the direction with positive sensor values.
-
- // Elevator heights are the vertical distance (in meters) from a defined zero.
- // In this case, zero is where the portion of the carriage that Spencer
- // removed lines up with the bolt.
-
- // X/Y positions are distances (in meters) the fridge is away from its origin
- // position. Origin is considered at a height of zero and an angle of zero.
- // Positive X positions are towards the front of the robot and negative X is
- // towards the back of the robot (which is where we score).
- // Y is positive going up and negative when it goes below the origin.
-
- message Goal {
- // Profile type.
- // Set to 0 for angle/height profiling.
- // Set to 1 for x/y profiling.
- int32_t profiling_type;
-
- // Angle of the arm.
- double angle;
- // Height of the elevator.
- double height;
-
- // Angular velocity of the arm.
- float angular_velocity;
- // Linear velocity of the elevator.
- float velocity;
-
- // Maximum arm profile angular velocity or 0 for the default.
- float max_angular_velocity;
- // Maximum elevator profile velocity or 0 for the default.
- float max_velocity;
-
- // Maximum arm profile acceleration or 0 for the default.
- float max_angular_acceleration;
- // Maximum elevator profile acceleration or 0 for the default.
- float max_acceleration;
-
- // X position of the fridge.
- double x;
- // Y position of the fridge.
- double y;
-
- // Velocity of the x position of the fridge.
- float x_velocity;
- // Velocity of the y position of the fridge.
- float y_velocity;
-
- // Maximum x profile velocity or 0 for the default.
- float max_x_velocity;
- // Maximum y profile velocity or 0 for the default.
- float max_y_velocity;
-
- // Maximum x profile acceleration or 0 for the default.
- float max_x_acceleration;
- // Maximum y profile acceleration or 0 for the default.
- float max_y_acceleration;
-
- // TODO(austin): Do I need acceleration here too?
-
- GrabberPistons grabbers;
- };
-
- message Position {
- PotAndIndexPair arm;
- PotAndIndexPair elevator;
- };
-
- message Status {
- // Are both the arm and elevator zeroed?
- bool zeroed;
-
- // Estimated angle of the arm.
- double angle;
- // Estimated angular velocity of the arm.
- float angular_velocity;
- // Estimated height of the elevator.
- double height;
- // Estimated velocity of the elvator.
- float velocity;
- // state of the grabber pistons
- GrabberPistons grabbers;
-
- // Goal angle and velocity of the arm.
- double goal_angle;
- float goal_angular_velocity;
- // Goal height and velocity of the elevator.
- double goal_height;
- float goal_velocity;
-
- // Estimated X/Y position of the fridge.
- // These are translated directly from the height/angle statuses.
- double x;
- double y;
- float x_velocity;
- float y_velocity;
-
- // X/Y goals of the fridge.
- // These are translated directly from the height/angle goals.
- double goal_x;
- double goal_y;
- float goal_x_velocity;
- float goal_y_velocity;
-
- // If true, we have aborted.
- bool estopped;
-
- // The internal state of the state machine.
- int32_t state;
-
- EstimatorState left_elevator_state;
- EstimatorState right_elevator_state;
- EstimatorState left_arm_state;
- EstimatorState right_arm_state;
- };
-
- message Output {
- double left_arm;
- double right_arm;
- double left_elevator;
- double right_elevator;
-
- GrabberPistons grabbers;
- };
-
- queue Goal goal;
- queue Position position;
- queue Output output;
- queue Status status;
-};
-
-queue_group FridgeQueue fridge_queue;
diff --git a/frc971/control_loops/fridge/fridge_lib_test.cc b/frc971/control_loops/fridge/fridge_lib_test.cc
deleted file mode 100644
index 83859ee..0000000
--- a/frc971/control_loops/fridge/fridge_lib_test.cc
+++ /dev/null
@@ -1,735 +0,0 @@
-#include "frc971/control_loops/fridge/fridge.h"
-
-#include <math.h>
-#include <unistd.h>
-
-#include <memory>
-
-#include "gtest/gtest.h"
-#include "aos/common/queue.h"
-#include "aos/common/time.h"
-#include "aos/common/commonmath.h"
-#include "aos/common/controls/control_loop_test.h"
-#include "aos/common/util/kinematics.h"
-#include "frc971/control_loops/position_sensor_sim.h"
-#include "frc971/control_loops/fridge/arm_motor_plant.h"
-#include "frc971/control_loops/fridge/elevator_motor_plant.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "frc971/constants.h"
-#include "frc971/control_loops/team_number_test_environment.h"
-
-using ::aos::time::Time;
-
-namespace frc971 {
-namespace control_loops {
-namespace testing {
-// Class which simulates the fridge and sends out queue messages with the
-// position.
-class FridgeSimulation {
- public:
- static constexpr double kNoiseScalar = 0.1;
- // Constructs a simulation.
- FridgeSimulation()
- : arm_plant_(new StateFeedbackPlant<4, 2, 2>(MakeArmPlant())),
- elevator_plant_(new StateFeedbackPlant<4, 2, 2>(MakeElevatorPlant())),
- left_arm_pot_encoder_(
- constants::GetValues().fridge.left_arm_zeroing.index_difference),
- right_arm_pot_encoder_(
- constants::GetValues().fridge.right_arm_zeroing.index_difference),
- left_elevator_pot_encoder_(
- constants::GetValues().fridge.left_elev_zeroing.index_difference),
- right_elevator_pot_encoder_(
- constants::GetValues().fridge.right_elev_zeroing.index_difference),
- fridge_queue_(".frc971.control_loops.fridge_queue", 0xe4e05855,
- ".frc971.control_loops.fridge_queue.goal",
- ".frc971.control_loops.fridge_queue.position",
- ".frc971.control_loops.fridge_queue.output",
- ".frc971.control_loops.fridge_queue.status") {
- // Initialize the elevator.
- InitializeElevatorPosition(
- constants::GetValues().fridge.elevator.lower_limit);
- // Initialize the arm.
- InitializeArmPosition(0.0);
- }
-
- void InitializeElevatorPosition(double start_pos) {
- InitializeElevatorPosition(start_pos, start_pos);
- }
-
- void InitializeElevatorPosition(double left_start_pos,
- double right_start_pos) {
- InitializeElevatorPosition(
- left_start_pos, right_start_pos,
- kNoiseScalar *
- constants::GetValues().fridge.right_elev_zeroing.index_difference);
- }
-
- void InitializeElevatorPosition(double left_start_pos, double right_start_pos,
- double pot_noise_stddev) {
- // Update the internal state of the elevator plant.
- elevator_plant_->mutable_X(0, 0) = (left_start_pos + right_start_pos) / 2.0;
- elevator_plant_->mutable_X(1, 0) = 0.0;
- elevator_plant_->mutable_X(2, 0) = (left_start_pos - right_start_pos) / 2.0;
- elevator_plant_->mutable_X(3, 0) = 0.0;
-
- right_elevator_pot_encoder_.Initialize(right_start_pos, pot_noise_stddev);
- left_elevator_pot_encoder_.Initialize(left_start_pos, pot_noise_stddev);
- elevator_initial_difference_ = left_start_pos - right_start_pos;
- }
-
- void InitializeArmPosition(double start_pos) {
- InitializeArmPosition(start_pos, start_pos);
- }
-
- void InitializeArmPosition(double left_start_pos, double right_start_pos) {
- InitializeArmPosition(
- left_start_pos, right_start_pos,
- kNoiseScalar *
- constants::GetValues().fridge.right_arm_zeroing.index_difference);
- }
- void InitializeArmPosition(double left_start_pos, double right_start_pos,
- double pot_noise_stddev) {
- // Update the internal state of the arm plant.
- arm_plant_->mutable_X(0, 0) = (left_start_pos + right_start_pos) / 2.0;
- arm_plant_->mutable_X(1, 0) = 0.0;
- arm_plant_->mutable_X(2, 0) = (left_start_pos - right_start_pos) / 2.0;
- arm_plant_->mutable_X(3, 0) = 0.0;
-
- left_arm_pot_encoder_.Initialize(left_start_pos, pot_noise_stddev);
- right_arm_pot_encoder_.Initialize(right_start_pos, pot_noise_stddev);
- arm_initial_difference_ = left_start_pos - right_start_pos;
- }
-
- // Changes the left-right calculations in the limit checks to measure absolute
- // differences instead of differences relative to the starting offset.
- void ErrorOnAbsoluteDifference() {
- arm_initial_difference_ = 0.0;
- elevator_initial_difference_ = 0.0;
- }
-
- // Sends a queue message with the position.
- void SendPositionMessage() {
- ::aos::ScopedMessagePtr<control_loops::FridgeQueue::Position> position =
- fridge_queue_.position.MakeMessage();
-
- left_arm_pot_encoder_.GetSensorValues(&position->arm.left);
- right_arm_pot_encoder_.GetSensorValues(&position->arm.right);
- left_elevator_pot_encoder_.GetSensorValues(&position->elevator.left);
- right_elevator_pot_encoder_.GetSensorValues(&position->elevator.right);
-
- position.Send();
- }
-
- // Sets the difference between the commanded and applied power for the arm.
- // This lets us test that the integrator for the arm works.
- void set_arm_power_error(double arm_power_error) {
- arm_power_error_ = arm_power_error;
- }
- // Simulates for a single timestep.
- void Simulate() {
- EXPECT_TRUE(fridge_queue_.output.FetchLatest());
-
- // Feed voltages into physics simulation.
- if (arm_power_error_ != 0.0) {
- arm_plant_->mutable_U() << ::aos::Clip(
- fridge_queue_.output->left_arm + arm_power_error_, -12, 12),
- ::aos::Clip(fridge_queue_.output->right_arm + arm_power_error_, -12,
- 12);
- } else {
- arm_plant_->mutable_U() << fridge_queue_.output->left_arm,
- fridge_queue_.output->right_arm;
- }
- elevator_plant_->mutable_U() << fridge_queue_.output->left_elevator,
- fridge_queue_.output->right_elevator;
-
- // Use the plant to generate the next physical state given the voltages to
- // the motors.
- arm_plant_->Update();
- elevator_plant_->Update();
-
- const double left_arm_angle = arm_plant_->Y(0, 0);
- const double right_arm_angle = arm_plant_->Y(1, 0);
- const double left_elevator_height = elevator_plant_->Y(0, 0);
- const double right_elevator_height = elevator_plant_->Y(1, 0);
-
- // TODO (phil) Do some sanity tests on the arm angles and the elevator
- // heights. For example, we need to make sure that both sides are within a
- // certain distance of each other and they haven't crashed into the top or
- // the bottom.
-
- // Use the physical state to simulate sensor readings.
- left_arm_pot_encoder_.MoveTo(left_arm_angle);
- right_arm_pot_encoder_.MoveTo(right_arm_angle);
- left_elevator_pot_encoder_.MoveTo(left_elevator_height);
- right_elevator_pot_encoder_.MoveTo(right_elevator_height);
-
- // Verify that the arm and elevator sides don't change much from their
- // initial difference. Use the initial difference instead of the absolute
- // difference to handle starting too far apart to test e-stopping.
- EXPECT_NEAR(left_arm_angle - right_arm_angle, arm_initial_difference_,
- 5.0 * M_PI / 180.0);
- EXPECT_NEAR(left_elevator_height - right_elevator_height,
- elevator_initial_difference_, 0.0254);
-
- // Validate that the arm is within range.
- EXPECT_GE(left_arm_angle,
- constants::GetValues().fridge.arm.lower_hard_limit);
- EXPECT_GE(right_arm_angle,
- constants::GetValues().fridge.arm.lower_hard_limit);
- EXPECT_LE(left_arm_angle,
- constants::GetValues().fridge.arm.upper_hard_limit);
- EXPECT_LE(right_arm_angle,
- constants::GetValues().fridge.arm.upper_hard_limit);
-
- // Validate that the elevator is within range.
- EXPECT_GE(left_elevator_height,
- constants::GetValues().fridge.elevator.lower_hard_limit);
- EXPECT_GE(right_elevator_height,
- constants::GetValues().fridge.elevator.lower_hard_limit);
- EXPECT_LE(left_elevator_height,
- constants::GetValues().fridge.elevator.upper_hard_limit);
- EXPECT_LE(right_elevator_height,
- constants::GetValues().fridge.elevator.upper_hard_limit);
- }
-
- private:
- ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> arm_plant_;
- ::std::unique_ptr<StateFeedbackPlant<4, 2, 2>> elevator_plant_;
-
- PositionSensorSimulator left_arm_pot_encoder_;
- PositionSensorSimulator right_arm_pot_encoder_;
- PositionSensorSimulator left_elevator_pot_encoder_;
- PositionSensorSimulator right_elevator_pot_encoder_;
-
- FridgeQueue fridge_queue_;
-
- double elevator_initial_difference_ = 0.0;
- double arm_initial_difference_ = 0.0;
- double arm_power_error_ = 0.0;
-};
-
-class FridgeTest : public ::aos::testing::ControlLoopTest {
- protected:
- FridgeTest()
- : fridge_queue_(".frc971.control_loops.fridge_queue", 0xe4e05855,
- ".frc971.control_loops.fridge_queue.goal",
- ".frc971.control_loops.fridge_queue.position",
- ".frc971.control_loops.fridge_queue.output",
- ".frc971.control_loops.fridge_queue.status"),
- fridge_(&fridge_queue_),
- fridge_plant_(),
- kinematics_(constants::GetValues().fridge.arm_length,
- constants::GetValues().fridge.elevator.upper_limit,
- constants::GetValues().fridge.elevator.lower_limit,
- constants::GetValues().fridge.arm.upper_limit,
- constants::GetValues().fridge.arm.lower_limit) {
- set_team_id(kTeamNumber);
- }
-
- void VerifyNearGoal() {
- fridge_queue_.goal.FetchLatest();
- fridge_queue_.status.FetchLatest();
- EXPECT_TRUE(fridge_queue_.goal.get() != nullptr);
- EXPECT_TRUE(fridge_queue_.status.get() != nullptr);
- if (fridge_queue_.goal->profiling_type == 0) {
- EXPECT_NEAR(fridge_queue_.goal->angle, fridge_queue_.status->angle,
- 0.001);
- EXPECT_NEAR(fridge_queue_.goal->height, fridge_queue_.status->height,
- 0.001);
- } else if (fridge_queue_.goal->profiling_type == 1) {
- aos::util::ElevatorArmKinematics::KinematicResult x_y_status;
- kinematics_.ForwardKinematic(fridge_queue_.status->height,
- fridge_queue_.status->angle, 0.0, 0.0, &x_y_status);
- EXPECT_NEAR(fridge_queue_.goal->x, x_y_status.fridge_x, 0.001);
- EXPECT_NEAR(fridge_queue_.goal->y, x_y_status.fridge_h, 0.001);
- } else {
- // Unhandled profiling type.
- EXPECT_TRUE(false);
- }
- }
-
- // Runs one iteration of the whole simulation and checks that separation
- // remains reasonable.
- void RunIteration(bool enabled = true) {
- SendMessages(enabled);
-
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
-
- TickTime();
- }
-
- // Runs iterations until the specified amount of simulated time has elapsed.
- void RunForTime(const Time &run_for, bool enabled = true) {
- const auto start_time = Time::Now();
- while (Time::Now() < start_time + run_for) {
- RunIteration(enabled);
- }
- }
-
- // Create a new instance of the test queue so that it invalidates the queue
- // that it points to. Otherwise, we will have a pointed to
- // shared memory that is no longer valid.
- FridgeQueue fridge_queue_;
-
- // Create a control loop and simulation.
- Fridge fridge_;
- FridgeSimulation fridge_plant_;
-
- aos::util::ElevatorArmKinematics kinematics_;
-};
-
-// Tests that the loop does nothing when the goal is zero.
-TEST_F(FridgeTest, DoesNothing) {
- // Set the goals to the starting values. This should theoretically guarantee
- // that the controller does nothing.
- const auto &values = constants::GetValues();
- ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
- .angle(0.0)
- .height(values.fridge.elevator.lower_limit)
- .max_velocity(20)
- .max_acceleration(20)
- .max_angular_velocity(20)
- .max_angular_acceleration(20)
- .Send());
-
- // Run a few iterations.
- RunForTime(Time::InSeconds(5));
-
- VerifyNearGoal();
-}
-
-// Tests that the loop can reach a goal.
-TEST_F(FridgeTest, ReachesXYGoal) {
- // Set a reasonable goal.
- const auto &values = constants::GetValues();
- const double soft_limit = values.fridge.elevator.lower_limit;
- const double height = soft_limit + 0.4;
- const double angle = M_PI / 6.0;
-
- aos::util::ElevatorArmKinematics::KinematicResult x_y_goals;
- kinematics_.ForwardKinematic(height, angle, 0.0, 0.0, &x_y_goals);
-
- ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
- .profiling_type(1)
- .x(x_y_goals.fridge_x)
- .y(x_y_goals.fridge_h)
- .max_x_velocity(20)
- .max_y_velocity(20)
- .max_x_acceleration(20)
- .max_y_acceleration(20)
- .Send());
-
- // Give it a lot of time to get there.
- RunForTime(Time::InSeconds(5));
-
- VerifyNearGoal();
-}
-
-// Tests that the loop can reach a goal.
-TEST_F(FridgeTest, ReachesGoal) {
- // Set a reasonable goal.
- const auto &values = constants::GetValues();
- const double soft_limit = values.fridge.elevator.lower_limit;
- ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
- .angle(M_PI / 4.0)
- .height(soft_limit + 0.5)
- .max_velocity(20)
- .max_acceleration(20)
- .max_angular_velocity(20)
- .max_angular_acceleration(20)
- .Send());
-
- // Give it a lot of time to get there.
- RunForTime(Time::InSeconds(5));
-
- VerifyNearGoal();
-}
-
-// Tests that the loop doesn't try and go beyond the physical range of the
-// mechanisms.
-TEST_F(FridgeTest, RespectsRange) {
- // Put the arm up to get it out of the way.
- // We're going to send the elevator to -5, which should be significantly too
- // low.
- ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
- .angle(M_PI)
- .height(-5.0)
- .max_velocity(20)
- .max_acceleration(20)
- .max_angular_velocity(20)
- .max_angular_acceleration(20)
- .Send());
-
- RunForTime(Time::InSeconds(10));
-
- // Check that we are near our soft limit.
- fridge_queue_.status.FetchLatest();
- const auto &values = constants::GetValues();
- EXPECT_NEAR(values.fridge.elevator.lower_limit, fridge_queue_.status->height,
- 0.001);
- EXPECT_NEAR(values.fridge.arm.upper_limit, fridge_queue_.status->angle,
- 0.001);
-
- // Put the arm down to get it out of the way.
- // We're going to give the elevator some ridiculously high goal.
- ASSERT_TRUE(fridge_queue_.goal.MakeWithBuilder()
- .angle(-M_PI)
- .height(50.0)
- .max_velocity(20)
- .max_acceleration(20)
- .max_angular_velocity(20)
- .max_angular_acceleration(20)
- .Send());
-
- RunForTime(Time::InSeconds(10));
-
- // Check that we are near our soft limit.
- fridge_queue_.status.FetchLatest();
- EXPECT_NEAR(values.fridge.elevator.upper_limit, fridge_queue_.status->height,
- 0.001);
- EXPECT_NEAR(values.fridge.arm.lower_limit, fridge_queue_.status->angle,
- 0.001);
-}
-
-// Tests that the loop zeroes when run for a while.
-TEST_F(FridgeTest, ZeroTest) {
- fridge_queue_.goal.MakeWithBuilder()
- .angle(0.0)
- .height(0.5)
- .max_velocity(20)
- .max_acceleration(20)
- .max_angular_velocity(20)
- .max_angular_acceleration(20)
- .Send();
- RunForTime(Time::InSeconds(5));
-
- VerifyNearGoal();
-}
-
-// Tests that starting at the lower hardstops doesn't cause an abort.
-TEST_F(FridgeTest, LowerHardstopStartup) {
- fridge_plant_.InitializeElevatorPosition(
- constants::GetValues().fridge.elevator.lower_hard_limit,
- constants::GetValues().fridge.elevator.lower_hard_limit);
- fridge_plant_.InitializeArmPosition(
- constants::GetValues().fridge.arm.lower_hard_limit,
- constants::GetValues().fridge.arm.lower_hard_limit);
- fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
- // We have to wait for it to put the elevator in a safe position as well.
- RunForTime(Time::InMS(8000));
-
- VerifyNearGoal();
-}
-
-// Tests that starting at the upper hardstops doesn't cause an abort.
-TEST_F(FridgeTest, UpperHardstopStartup) {
- fridge_plant_.InitializeElevatorPosition(
- constants::GetValues().fridge.elevator.upper_hard_limit,
- constants::GetValues().fridge.elevator.upper_hard_limit);
- fridge_plant_.InitializeArmPosition(
- constants::GetValues().fridge.arm.upper_hard_limit,
- constants::GetValues().fridge.arm.upper_hard_limit);
- fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
- RunForTime(Time::InMS(5000));
-
- VerifyNearGoal();
-}
-
-// Tests that starting with an initial arm difference triggers an ESTOP.
-TEST_F(FridgeTest, ArmFarApartEstop) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
-
- do {
- fridge_plant_.InitializeArmPosition(
- constants::GetValues().fridge.arm.lower_limit,
- constants::GetValues().fridge.arm.lower_limit + 0.2);
- SendMessages(true);
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
- TickTime();
- } while (fridge_.state() == Fridge::INITIALIZING);
-
- EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
-
- // TODO(austin): We should estop earlier once Phil's code to detect issues
- // before the index pulse is merged.
- while (fridge_.state() != Fridge::RUNNING &&
- fridge_.state() != Fridge::ESTOP) {
- SendMessages(true);
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
- TickTime();
- }
-
- EXPECT_EQ(Fridge::ESTOP, fridge_.state());
-}
-
-// Tests that starting with an initial elevator difference triggers an ESTOP.
-TEST_F(FridgeTest, ElevatorFarApartEstop) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
-
- do {
- fridge_plant_.InitializeElevatorPosition(
- constants::GetValues().fridge.elevator.lower_limit,
- constants::GetValues().fridge.elevator.lower_limit + 0.1);
- SendMessages(true);
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
- TickTime();
- } while (fridge_.state() == Fridge::INITIALIZING);
-
- EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
-
- // TODO(austin): We should estop earlier once Phil's code to detect issues
- // before the index pulse is merged.
- while (fridge_.state() != Fridge::RUNNING &&
- fridge_.state() != Fridge::ESTOP) {
- SendMessages(true);
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
- TickTime();
- }
-
- EXPECT_EQ(Fridge::ESTOP, fridge_.state());
-}
-
-// Tests that starting with an initial elevator difference converges back to 0
-// error when zeroed.
-TEST_F(FridgeTest, ElevatorFixError) {
- fridge_queue_.goal.MakeWithBuilder()
- .angle(0.0)
- .height(0.2)
- .max_velocity(20)
- .max_acceleration(20)
- .Send();
-
- do {
- fridge_plant_.InitializeElevatorPosition(
- constants::GetValues().fridge.elevator.lower_limit,
- constants::GetValues().fridge.elevator.lower_limit + 0.01);
- fridge_plant_.ErrorOnAbsoluteDifference();
- SendMessages(true);
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
- TickTime();
- } while (fridge_.state() == Fridge::INITIALIZING);
-
- EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
-
- RunForTime(Time::InSeconds(5));
- VerifyNearGoal();
-}
-
-// Tests that starting with an initial arm difference converges back to 0
-// error when zeroed.
-TEST_F(FridgeTest, ArmFixError) {
- fridge_queue_.goal.MakeWithBuilder()
- .angle(0.0)
- .height(0.2)
- .max_angular_velocity(20)
- .max_angular_acceleration(20)
- .Send();
-
- do {
- fridge_plant_.InitializeArmPosition(0.0, 0.02);
- fridge_plant_.ErrorOnAbsoluteDifference();
- SendMessages(true);
- fridge_plant_.SendPositionMessage();
- fridge_.Iterate();
- fridge_plant_.Simulate();
- TickTime();
- } while (fridge_.state() == Fridge::INITIALIZING);
-
- EXPECT_EQ(Fridge::ZEROING_ELEVATOR, fridge_.state());
-
- RunForTime(Time::InSeconds(5));
- VerifyNearGoal();
-}
-
-// Tests that resetting WPILib results in a rezero.
-TEST_F(FridgeTest, ResetTest) {
- fridge_plant_.InitializeElevatorPosition(
- constants::GetValues().fridge.elevator.upper_hard_limit,
- constants::GetValues().fridge.elevator.upper_hard_limit);
- fridge_plant_.InitializeArmPosition(
- constants::GetValues().fridge.arm.upper_hard_limit,
- constants::GetValues().fridge.arm.upper_hard_limit);
- fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
- RunForTime(Time::InMS(5000));
-
- EXPECT_EQ(Fridge::RUNNING, fridge_.state());
- VerifyNearGoal();
- SimulateSensorReset();
- RunForTime(Time::InMS(100));
- EXPECT_NE(Fridge::RUNNING, fridge_.state());
- RunForTime(Time::InMS(6000));
- EXPECT_EQ(Fridge::RUNNING, fridge_.state());
- VerifyNearGoal();
-}
-
-// Tests that the internal goals don't change while disabled.
-TEST_F(FridgeTest, DisabledGoalTest) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
-
- RunForTime(Time::InMS(100), false);
- EXPECT_EQ(0.0, fridge_.elevator_goal_);
- EXPECT_EQ(0.0, fridge_.arm_goal_);
-
- // Now make sure they move correctly
- RunForTime(Time::InMS(4000), true);
- EXPECT_NE(0.0, fridge_.elevator_goal_);
- EXPECT_NE(0.0, fridge_.arm_goal_);
-}
-
-// Tests that the elevator zeroing goals don't wind up too far.
-TEST_F(FridgeTest, ElevatorGoalPositiveWindupTest) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
-
- while (fridge_.state() != Fridge::ZEROING_ELEVATOR) {
- RunIteration();
- }
-
- // Kick it.
- RunForTime(Time::InMS(50));
- double orig_fridge_goal = fridge_.elevator_goal_;
- fridge_.elevator_goal_ += 100.0;
-
- RunIteration();
- EXPECT_NEAR(orig_fridge_goal, fridge_.elevator_goal_, 0.05);
-
- RunIteration();
-
- EXPECT_EQ(fridge_.elevator_loop_->U(), fridge_.elevator_loop_->U_uncapped());
-}
-
-// Tests that the arm zeroing goals don't wind up too far.
-TEST_F(FridgeTest, ArmGoalPositiveWindupTest) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
-
- int i = 0;
- while (fridge_.state() != Fridge::ZEROING_ARM) {
- RunIteration();
- ++i;
- ASSERT_LE(i, 10000);
- }
-
- // Kick it.
- RunForTime(Time::InMS(50));
- double orig_fridge_goal = fridge_.arm_goal_;
- fridge_.arm_goal_ += 100.0;
-
- RunIteration();
- EXPECT_NEAR(orig_fridge_goal, fridge_.arm_goal_, 0.05);
-
- RunIteration();
-
- EXPECT_EQ(fridge_.arm_loop_->U(), fridge_.arm_loop_->U_uncapped());
-}
-
-// Tests that the elevator zeroing goals don't wind up too far.
-TEST_F(FridgeTest, ElevatorGoalNegativeWindupTest) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
-
- while (fridge_.state() != Fridge::ZEROING_ELEVATOR) {
- RunIteration();
- }
-
- // Kick it.
- RunForTime(Time::InMS(50));
- double orig_fridge_goal = fridge_.elevator_goal_;
- fridge_.elevator_goal_ -= 100.0;
-
- RunIteration();
- EXPECT_NEAR(orig_fridge_goal, fridge_.elevator_goal_, 0.05);
-
- RunIteration();
-
- EXPECT_EQ(fridge_.elevator_loop_->U(), fridge_.elevator_loop_->U_uncapped());
-}
-
-// Tests that the arm zeroing goals don't wind up too far.
-TEST_F(FridgeTest, ArmGoalNegativeWindupTest) {
- fridge_queue_.goal.MakeWithBuilder().angle(0.03).height(0.45).Send();
-
- while (fridge_.state() != Fridge::ZEROING_ARM) {
- RunIteration();
- }
-
- // Kick it.
- RunForTime(Time::InMS(50));
- double orig_fridge_goal = fridge_.arm_goal_;
- fridge_.arm_goal_ -= 100.0;
-
- RunIteration();
- EXPECT_NEAR(orig_fridge_goal, fridge_.arm_goal_, 0.05);
-
- RunIteration();
-
- EXPECT_EQ(fridge_.arm_loop_->U(), fridge_.arm_loop_->U_uncapped());
-}
-
-// Tests that the loop zeroes when run for a while.
-TEST_F(FridgeTest, ZeroNoGoal) {
- RunForTime(Time::InSeconds(5));
-
- EXPECT_EQ(Fridge::RUNNING, fridge_.state());
-}
-
-// Tests that if we start at the bottom, the elevator moves to a safe height
-// before zeroing the arm.
-TEST_F(FridgeTest, SafeArmZeroing) {
- auto &values = constants::GetValues();
- fridge_plant_.InitializeElevatorPosition(
- values.fridge.elevator.lower_hard_limit);
- fridge_plant_.InitializeArmPosition(M_PI / 4.0);
-
- const auto start_time = Time::Now();
- double last_arm_goal = fridge_.arm_goal_;
- while (Time::Now() < start_time + Time::InMS(4000)) {
- RunIteration();
-
- if (fridge_.state() != Fridge::ZEROING_ELEVATOR) {
- // Wait until we are zeroing the elevator.
- continue;
- }
-
- fridge_queue_.status.FetchLatest();
- ASSERT_TRUE(fridge_queue_.status.get() != nullptr);
- if (fridge_queue_.status->height > values.fridge.arm_zeroing_height) {
- // We had better not be trying to zero the arm...
- EXPECT_EQ(last_arm_goal, fridge_.arm_goal_);
- last_arm_goal = fridge_.arm_goal_;
- }
- }
-}
-
-// Tests that the arm integrator works.
-TEST_F(FridgeTest, ArmIntegratorTest) {
- fridge_plant_.InitializeArmPosition(
- (constants::GetValues().fridge.arm.lower_hard_limit +
- constants::GetValues().fridge.arm.lower_hard_limit) /
- 2.0);
- fridge_plant_.set_arm_power_error(1.0);
- fridge_queue_.goal.MakeWithBuilder().angle(0.0).height(0.4).Send();
-
- RunForTime(Time::InMS(8000));
-
- VerifyNearGoal();
-}
-
-// Phil:
-// TODO(austin): Check that we e-stop if encoder index pulse is not n
-// revolutions away from last one. (got extra counts from noise, etc).
-// TODO(austin): Check that we e-stop if pot disagrees too much with encoder
-// after we are zeroed.
-
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/fridge/fridge_main.cc b/frc971/control_loops/fridge/fridge_main.cc
deleted file mode 100644
index f92ced3..0000000
--- a/frc971/control_loops/fridge/fridge_main.cc
+++ /dev/null
@@ -1,11 +0,0 @@
-#include "frc971/control_loops/fridge/fridge.h"
-
-#include "aos/linux_code/init.h"
-
-int main() {
- ::aos::Init();
- frc971::control_loops::Fridge fridge;
- fridge.Run();
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/control_loops/fridge/integral_arm_plant.cc b/frc971/control_loops/fridge/integral_arm_plant.cc
deleted file mode 100644
index a101044..0000000
--- a/frc971/control_loops/fridge/integral_arm_plant.cc
+++ /dev/null
@@ -1,49 +0,0 @@
-#include "frc971/control_loops/fridge/integral_arm_plant.h"
-
-#include <vector>
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<5, 2, 2> MakeIntegralArmPlantCoefficients() {
- Eigen::Matrix<double, 5, 5> A;
- A << 1.0, 0.00479642025454, 0.0, 0.0, 4.92993559969e-05, 0.0, 0.919688585028, 0.0, 0.0, 0.0194484035162, 0.0, 0.0, 0.999539771613, 0.00479566382645, 0.0, 0.0, 0.0, -0.18154390621, 0.919241022297, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0;
- Eigen::Matrix<double, 5, 2> B;
- B << 2.46496779984e-05, 2.46496779984e-05, 0.00972420175808, 0.00972420175808, 2.46477449538e-05, -2.46477449538e-05, 0.00972266818532, -0.00972266818532, 0.0, 0.0;
- Eigen::Matrix<double, 2, 5> C;
- C << 1.0, 0.0, 1.0, 0.0, 0.0, 1.0, 0.0, -1.0, 0.0, 0.0;
- Eigen::Matrix<double, 2, 2> D;
- D << 0, 0, 0, 0;
- Eigen::Matrix<double, 2, 1> U_max;
- U_max << 12.0, 12.0;
- Eigen::Matrix<double, 2, 1> U_min;
- U_min << -12.0, -12.0;
- return StateFeedbackPlantCoefficients<5, 2, 2>(A, B, C, D, U_max, U_min);
-}
-
-StateFeedbackController<5, 2, 2> MakeIntegralArmController() {
- Eigen::Matrix<double, 5, 2> L;
- L << 0.461805946837, 0.461805946837, 5.83483983392, 5.83483983392, 0.429725467802, -0.429725467802, 0.18044816586, -0.18044816586, 31.0623964848, 31.0623964848;
- Eigen::Matrix<double, 2, 5> K;
- K << 320.979606093, 21.0129517955, 884.233784759, 36.3637782119, 1.0, 320.979606095, 21.0129517956, -884.233784749, -36.3637782119, 1.0;
- Eigen::Matrix<double, 5, 5> A_inv;
- A_inv << 1.0, -0.00521526561559, 0.0, 0.0, 5.21292341391e-05, 0.0, 1.08732457517, 0.0, 0.0, -0.0211467270909, 0.0, 0.0, 0.999513354044, -0.00521444313273, 0.0, 0.0, 0.0, 0.197397150694, 1.08682415753, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0;
- return StateFeedbackController<5, 2, 2>(L, K, A_inv, MakeIntegralArmPlantCoefficients());
-}
-
-StateFeedbackPlant<5, 2, 2> MakeIntegralArmPlant() {
- ::std::vector< ::std::unique_ptr<StateFeedbackPlantCoefficients<5, 2, 2>>> plants(1);
- plants[0] = ::std::unique_ptr<StateFeedbackPlantCoefficients<5, 2, 2>>(new StateFeedbackPlantCoefficients<5, 2, 2>(MakeIntegralArmPlantCoefficients()));
- return StateFeedbackPlant<5, 2, 2>(&plants);
-}
-
-StateFeedbackLoop<5, 2, 2> MakeIntegralArmLoop() {
- ::std::vector< ::std::unique_ptr<StateFeedbackController<5, 2, 2>>> controllers(1);
- controllers[0] = ::std::unique_ptr<StateFeedbackController<5, 2, 2>>(new StateFeedbackController<5, 2, 2>(MakeIntegralArmController()));
- return StateFeedbackLoop<5, 2, 2>(&controllers);
-}
-
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/fridge/integral_arm_plant.h b/frc971/control_loops/fridge/integral_arm_plant.h
deleted file mode 100644
index f43f915..0000000
--- a/frc971/control_loops/fridge/integral_arm_plant.h
+++ /dev/null
@@ -1,20 +0,0 @@
-#ifndef FRC971_CONTROL_LOOPS_FRIDGE_INTEGRAL_ARM_PLANT_H_
-#define FRC971_CONTROL_LOOPS_FRIDGE_INTEGRAL_ARM_PLANT_H_
-
-#include "frc971/control_loops/state_feedback_loop.h"
-
-namespace frc971 {
-namespace control_loops {
-
-StateFeedbackPlantCoefficients<5, 2, 2> MakeIntegralArmPlantCoefficients();
-
-StateFeedbackController<5, 2, 2> MakeIntegralArmController();
-
-StateFeedbackPlant<5, 2, 2> MakeIntegralArmPlant();
-
-StateFeedbackLoop<5, 2, 2> MakeIntegralArmLoop();
-
-} // namespace control_loops
-} // namespace frc971
-
-#endif // FRC971_CONTROL_LOOPS_FRIDGE_INTEGRAL_ARM_PLANT_H_
diff --git a/frc971/control_loops/fridge/replay_fridge.cc b/frc971/control_loops/fridge/replay_fridge.cc
deleted file mode 100644
index 87833ef..0000000
--- a/frc971/control_loops/fridge/replay_fridge.cc
+++ /dev/null
@@ -1,24 +0,0 @@
-#include "aos/common/controls/replay_control_loop.h"
-#include "aos/linux_code/init.h"
-
-#include "frc971/control_loops/fridge/fridge.q.h"
-
-// Reads one or more log files and sends out all the queue messages (in the
-// correct order and at the correct time) to feed a "live" fridge process.
-
-int main(int argc, char **argv) {
- if (argc <= 1) {
- fprintf(stderr, "Need at least one file to replay!\n");
- return EXIT_FAILURE;
- }
-
- ::aos::InitNRT();
-
- ::aos::controls::ControlLoopReplayer<::frc971::control_loops::FridgeQueue>
- replayer(&::frc971::control_loops::fridge_queue, "fridge");
- for (int i = 1; i < argc; ++i) {
- replayer.ProcessFile(argv[i]);
- }
-
- ::aos::Cleanup();
-}
diff --git a/frc971/control_loops/matlab/drivetrain_controller.m b/frc971/control_loops/matlab/drivetrain_controller.m
deleted file mode 100644
index f9ee4be..0000000
--- a/frc971/control_loops/matlab/drivetrain_controller.m
+++ /dev/null
@@ -1,240 +0,0 @@
-close all;
-load 'drivetrain_spin_low'
-load 'drivetrain_strait_low'
-% Max power amps of CIM or maybe half the mass of the robot in lbs or the whole robot in kg.
-m = 68;
-% Must be in meters. Maybe width of robot (distance of center wheels from center).
-rb = 0.617998644 / 2.0;
-% Moment of Inertia
-J = 7;
-stall_current = 133.0;
-% Resistance of the motor, divided by the number of motors.
-R = 12.0 / stall_current / 4 / 0.43;
-% Motor Constant
-Km = (12.0 - R * 2.7) / (4650.0 / 60.0 * 2.0 * pi);
-% Torque Constant
-Kt = 0.008;
-r = 0.04445; % 3.5 inches diameter
-G_low = 60.0 / 15.0 * 50.0 / 15.0;
-G_high = 45.0 / 30.0 * 50.0 / 15.0;
-dt = 0.01;
-
-G = G_low;
-
-% must refer to how each side of the robot affects the other? Units of 1 / kg
-% I think that if the center of mass is in the center of the robot, then
-% msp will evaluate to 2/(mass of robot) and msn will evaluate to 0.
-msp = (1.0 / m + rb ^ 2.0 / J);
-msn = (1.0 / m - rb ^ 2.0 / J);
-tc = -Km * Kt * G ^ 2.0 / (R * r ^ 2.0);
-mp = G * Kt / (R * r);
-
-A = [0 1 0 0; 0 msp*tc 0 msn*tc; 0 0 0 1; 0 msn*tc 0 msp*tc];
-B = [0 0; msp * mp msn * mp; 0 0; msn * mp msp * mp];
-C = [1 0 0 0; 0 0 1 0];
-D = [0 0; 0 0];
-
-dm = c2d(ss(A, B, C, D), dt);
-
-hp = .8;
-lp = .85;
-K = place(dm.a, dm.b, [hp, hp, lp, lp]);
-
-hlp = 0.07;
-llp = 0.09;
-L = place(dm.a', dm.c', [hlp, hlp, llp, llp])';
-
-% Plot what we computed
-
-fd = fopen('/home/aschuh/frc971/2012/trunk/src/prime/control_loops/Drivetrain.mat', 'w');
-n = 1;
-sm = [];
-writeMatHeader(fd, size(dm.a, 1), size(dm.b, 2));
-writeMat(fd, dm.a, 'A');
-writeMat(fd, dm.b, 'B');
-writeMat(fd, dm.c, 'C');
-writeMat(fd, dm.d, 'D');
-writeMat(fd, L, 'L');
-writeMat(fd, K, 'K');
-writeMat(fd, [12; 12], 'U_max');
-writeMat(fd, [-12; -12], 'U_min');
-writeMatFooter(fd);
-fclose(fd);
-
-full_model = dss([dm.a (-dm.b * K); eye(4) (dm.a - dm.b * K - L * dm.c)], [0, 0; 0, 0; 0, 0; 0, 0; L], [C, [0, 0, 0, 0; 0, 0, 0, 0]], 0, eye(8), 0.01);
-
-n = 1;
-sm_strait = [];
-t = drivetrain_strait_low(1, 1) + dt * (n - 1);
-x = [drivetrain_strait_low(1, 2); 0; drivetrain_strait_low(1, 3); 0];
-while t < drivetrain_strait_low(end, 1)
- sm_strait(n, 1) = t;
- sm_strait(n, 2) = (x(1,1) + x(3,1)) / 2.0;
- t = t + dt;
- x = dm.a * x + dm.b * [drivetrain_strait_low(n, 4); drivetrain_strait_low(n, 5)];
- n = n + 1;
-end
-
-figure;
-plot(drivetrain_strait_low(:, 1), (drivetrain_strait_low(:, 2) + drivetrain_strait_low(:, 3)) / 2.0, sm_strait(:, 1), sm_strait(:, 2));
-legend('actual', 'sim');
-
-n = 1;
-sm_spin = [];
-t = drivetrain_spin_low(1, 1) + dt * (n - 1);
-x = [drivetrain_spin_low(1, 2); 0; drivetrain_spin_low(1, 3); 0];
-while t < drivetrain_spin_low(end, 1)
- sm_spin(n, 1) = t;
- sm_spin(n, 2) = (x(1,1) - x(3,1)) / 2.0;
- t = t + dt;
- x = dm.a * x + dm.b * [drivetrain_spin_low(n, 4); drivetrain_spin_low(n, 5)];
- n = n + 1;
-end
-
-figure;
-plot(drivetrain_spin_low(:, 1), (drivetrain_spin_low(:, 2) - drivetrain_spin_low(:, 3)) / 2.0, sm_spin(:, 1), sm_spin(:, 2));
-legend('actual', 'sim');
-
-%figure;
-%nyquist(full_model);
-
-
-%%
-t = 0;
-x = [0; 0; 0; 0;];
-while t < logging(end, 1)
- sm(n, 1) = t;
- sm(n, 2) = x(1,1);
- sm(n, 3) = x(3,1);
- t = t + dt;
- x = dm.a * x + dm.b * [12.0; 12.0];
- n = n + 1;
-end
-
-figure;
-plot(logging(:, 1), logging(:, 2), sm(:, 1), sm(:, 2));
-legend('actual', 'sim');
-
-%% Simulation of a small turn angle with a large distance to travel
-tf = 2;
-x = [0; 0; 0.1; 0;];
-r = [10; 0; 10; 0];
-
-smt = zeros(tf / dt, 8);
-t = 0;
-xhat = x;
-n = 1;
-% 1 means scale
-% 2 means just limit to 12 volts
-% 3 means preserve the difference in power
-captype = 1;
-while n <= size(smt, 1)
- smt(n, 1) = t;
- smt(n, 2) = x(1,1);
- smt(n, 3) = x(3,1);
- t = t + dt;
-
- u = K * (r - xhat);
- smt(n, 4) = u(1,1);
- smt(n, 5) = u(2,1);
-
- if captype == 1
- if sum(abs(u) > 12.0)
- % We have a problem!
- % Check to see if it's a big steering power problem,
- % or a big drive error.
- turnPower = (u(1, 1) - u(2, 1));
- drivePower = (u(1, 1) + u(2, 1));
- scaleFactor = 12.0 / max(abs(u));
- smt(n, 8) = 1.0 / scaleFactor;
- % Only start scaling the turn power up if we are far out of
- % range.
- if abs(turnPower) < 0.5 * abs(drivePower)
- % Turn power is swamped.
- deltaTurn = turnPower / 2.0 / scaleFactor * 0.5;
- u(1, 1) = u(1, 1) + deltaTurn;
- u(2, 1) = u(2, 1) - deltaTurn;
- scaleFactor = 12.0 / max(abs(u));
- else
- if 0.5 * abs(turnPower) > abs(drivePower)
- % Drive power is swamped.
- deltaDrive = drivePower / 2.0 / scaleFactor * 0.5;
- u(1, 1) = u(1, 1) + deltaDrive;
- u(2, 1) = u(2, 1) + deltaDrive;
- scaleFactor = 12.0 / max(abs(u));
- end
- end
- u = u * scaleFactor;
- end
- else
- if captype == 2
- if u(1, 1) > 12.0
- u(1, 1) = 12.0;
- end
- if u(1, 1) < -12.0
- u(1, 1) = -12.0;
- end
- if u(2, 1) > 12.0
- u(2, 1) = 12.0;
- end
- if u(2, 1) < -12.0
- u(2, 1) = -12.0;
- end
- else
- if captype == 3
- if u(1, 1) > 12.0
- u(2, 1) = u(2, 1) - (u(1, 1) - 12.0);
- else
- if u(1, 1) < -12.0
- u(2, 1) = u(2, 1) - (u(1, 1) + 12.0);
- end
- end
- if u(2, 1) > 12.0
- u(1, 1) = u(1, 1) - (u(2, 1) - 12.0);
- else
- if u(2, 1) < -12.0
- u(1, 1) = u(1, 1) - (u(2, 1) + 12.0);
- end
- end
- if u(1, 1) > 12.0
- u(1, 1) = 12.0;
- end
- if u(1, 1) < -12.0
- u(1, 1) = -12.0;
- end
- if u(2, 1) > 12.0
- u(2, 1) = 12.0;
- end
- if u(2, 1) < -12.0
- u(2, 1) = -12.0;
- end
- end
- end
-
- end
- smt(n, 6) = u(1,1);
- smt(n, 7) = u(2,1);
- xhat = dm.a * xhat + dm.b * u + L * (dm.c * x - dm.c * xhat);
- x = dm.a * x + dm.b * u;
-
- n = n + 1;
-end
-
-figure;
-subplot(6, 1, 1);
-plot(smt(:, 1), smt(:, 2) + smt(:, 3));
-legend('dist');
-subplot(6, 1, 2);
-plot(smt(:, 1), smt(:, 2) - smt(:, 3));
-legend('angle');
-subplot(3, 1, 2);
-plot(smt(:, 1), smt(:, 4), smt(:, 1), smt(:, 5));
-legend('lu', 'ru');
-subplot(3, 1, 3);
-plot(smt(:, 1), smt(:, 6), smt(:, 1), smt(:, 7));
-legend('lu_{real}', 'ru_{real}');
-
-%figure;
-%plot(smt(:, 1), smt(:, 8))
-%legend('Scale Factor');
-
diff --git a/frc971/control_loops/matlab/drivetrain_spin_fast.csv b/frc971/control_loops/matlab/drivetrain_spin_fast.csv
deleted file mode 100644
index 5768209..0000000
--- a/frc971/control_loops/matlab/drivetrain_spin_fast.csv
+++ /dev/null
@@ -1,215 +0,0 @@
-12038,8.037056,-7.571709,1.000000
-12039,8.037056,-7.571709,1.000000
-12040,8.037056,-7.571709,1.000000
-12041,8.037254,-7.572700,1.000000
-12042,8.044792,-7.577064,1.000000
-12043,8.053718,-7.583610,1.000000
-12044,8.066016,-7.593330,1.000000
-12045,8.078909,-7.602652,1.000000
-12046,8.094183,-7.613760,1.000000
-12047,8.109655,-7.624670,1.000000
-12048,8.126118,-7.637167,1.000000
-12049,8.141789,-7.650060,1.000000
-12050,8.156070,-7.662556,1.000000
-12051,8.174716,-7.677433,1.000000
-12052,8.190188,-7.690128,1.000000
-12053,8.208635,-7.704608,1.000000
-12054,8.225694,-7.717303,1.000000
-12055,8.242951,-7.729800,1.000000
-12056,8.261200,-7.745073,1.000000
-12057,8.276077,-7.758363,1.000000
-12058,8.289565,-7.771058,1.000000
-12059,8.308012,-7.787720,1.000000
-12060,8.327253,-7.805771,1.000000
-12061,8.345105,-7.819457,1.000000
-12062,8.360379,-7.830565,1.000000
-12063,8.377041,-7.844252,1.000000
-12064,8.396083,-7.860914,1.000000
-12065,8.413539,-7.877378,1.000000
-12066,8.430597,-7.895230,1.000000
-12067,8.445871,-7.910107,1.000000
-12068,8.460153,-7.923397,1.000000
-12069,8.478600,-7.938274,1.000000
-12070,8.497444,-7.954341,1.000000
-12071,8.516288,-7.970408,1.000000
-12072,8.535132,-7.987268,1.000000
-12073,8.549215,-8.002541,1.000000
-12074,8.563299,-8.018410,1.000000
-12075,8.581944,-8.037651,1.000000
-12076,8.605152,-8.057288,1.000000
-12077,8.623203,-8.070578,1.000000
-12078,8.639865,-8.087637,1.000000
-12079,8.658709,-8.105489,1.000000
-12080,8.676958,-8.122945,1.000000
-12087,8.815213,-8.259811,1.000000
-12088,8.835247,-8.279250,1.000000
-12089,8.852702,-8.298094,1.000000
-12090,8.876307,-8.320310,1.000000
-12091,8.897333,-8.338758,1.000000
-12092,8.922921,-8.360577,1.000000
-12093,8.948311,-8.383983,1.000000
-12094,8.968147,-8.403621,1.000000
-12095,8.988974,-8.426035,1.000000
-12096,9.009405,-8.447656,1.000000
-12097,9.035191,-8.474633,1.000000
-12098,9.055027,-8.494865,1.000000
-12099,9.076450,-8.516288,1.000000
-12100,9.101641,-8.540686,1.000000
-12101,9.121675,-8.560323,1.000000
-12102,9.144090,-8.583729,1.000000
-12103,9.171066,-8.609119,1.000000
-12104,9.195663,-8.630542,1.000000
-12105,9.218672,-8.653155,1.000000
-12106,9.240690,-8.671602,1.000000
-12107,9.265881,-8.693421,1.000000
-12108,9.290676,-8.717621,1.000000
-12109,9.315868,-8.741424,1.000000
-12110,9.343043,-8.767210,1.000000
-12111,9.365655,-8.788038,1.000000
-12112,9.392632,-8.813626,1.000000
-12113,9.417427,-8.836635,1.000000
-12114,9.441230,-8.857066,1.000000
-12115,9.468801,-8.881464,1.000000
-12116,9.499150,-8.906656,1.000000
-12117,9.521564,-8.928475,1.000000
-12118,9.551120,-8.953666,1.000000
-12119,9.574724,-8.974692,1.000000
-12120,9.604081,-9.003454,1.000000
-12121,9.631455,-9.030629,1.000000
-12122,9.656646,-9.054829,1.000000
-12123,9.686400,-9.084979,1.000000
-12124,9.711789,-9.111559,1.000000
-12125,9.737576,-9.136552,1.000000
-12126,9.761776,-9.158570,1.000000
-12127,9.788554,-9.182770,1.000000
-12128,9.815927,-9.208754,1.000000
-12129,9.845681,-9.235334,1.000000
-12130,9.872261,-9.259534,1.000000
-12131,9.896460,-9.282543,1.000000
-12132,9.924627,-9.308528,1.000000
-12133,9.954976,-9.336893,1.000000
-12134,9.982746,-9.362283,1.000000
-12135,10.007739,-9.385293,1.000000
-12136,10.038881,-9.414055,1.000000
-12137,10.065064,-9.437262,1.000000
-12138,10.097595,-9.464437,1.000000
-12139,10.123977,-9.488042,1.000000
-12140,10.155912,-9.517201,1.000000
-12141,10.180905,-9.539813,1.000000
-12142,10.213039,-9.568377,1.000000
-12143,10.238429,-9.592973,1.000000
-12144,10.270166,-9.622529,1.000000
-12145,10.296548,-9.646728,1.000000
-12146,10.326897,-9.673705,1.000000
-12147,10.356253,-9.700285,1.000000
-12148,10.388784,-9.728650,1.000000
-12149,10.419133,-9.755230,1.000000
-12150,10.449878,-9.783992,1.000000
-12151,10.481020,-9.814935,1.000000
-12152,10.508592,-9.843499,1.000000
-12153,10.536759,-9.875633,1.000000
-12154,10.568099,-9.908560,1.000000
-12155,10.594679,-9.934347,1.000000
-12156,10.624036,-9.961323,1.000000
-12157,10.653195,-9.988300,1.000000
-12158,10.682949,-10.015078,1.000000
-12159,10.716074,-10.045824,1.000000
-12160,10.745828,-10.074189,1.000000
-12161,10.773003,-10.098587,1.000000
-12162,10.804542,-10.127944,1.000000
-12163,10.831518,-10.152342,1.000000
-12164,10.865041,-10.183881,1.000000
-12165,10.893406,-10.211254,1.000000
-12166,10.924945,-10.240413,1.000000
-12167,10.960054,-10.269968,1.000000
-12168,10.989411,-10.294168,1.000000
-12169,11.020950,-10.322334,1.000000
-12170,11.057249,-10.352881,1.000000
-12171,11.086210,-10.379263,1.000000
-12172,11.116162,-10.407231,1.000000
-12173,11.144130,-10.434605,1.000000
-12174,11.176859,-10.466342,1.000000
-12175,11.212564,-10.498873,1.000000
-12176,11.240929,-10.524461,1.000000
-12177,11.271872,-10.553818,1.000000
-12178,11.306387,-10.587737,1.000000
-12179,11.337926,-10.620863,1.000000
-12180,11.364704,-10.651410,1.000000
-12186,11.552945,-10.839849,1.000000
-12187,11.580517,-10.865041,1.000000
-12188,11.612056,-10.895588,1.000000
-12189,11.642603,-10.925738,1.000000
-12190,11.676125,-10.957674,1.000000
-12191,11.707268,-10.987031,1.000000
-12192,11.736823,-11.013214,1.000000
-12193,11.773122,-11.045943,1.000000
-12194,11.802479,-11.072920,1.000000
-12195,11.834415,-11.103268,1.000000
-12196,11.868532,-11.136394,1.000000
-12197,11.900865,-11.167338,1.000000
-12198,11.931808,-11.197488,1.000000
-12199,11.964141,-11.227440,1.000000
-12200,11.997068,-11.256797,1.000000
-12201,12.026623,-11.283576,1.000000
-12202,12.063121,-11.316701,1.000000
-12203,12.092676,-11.344273,1.000000
-12204,12.128778,-11.377200,1.000000
-12205,12.158333,-11.404574,1.000000
-12206,12.193641,-11.437699,1.000000
-12207,12.223394,-11.465668,1.000000
-12208,12.259297,-11.499785,1.000000
-12209,12.292621,-11.532514,1.000000
-12210,12.321581,-11.563458,1.000000
-12211,12.357087,-11.601345,1.000000
-12212,12.389618,-11.637049,1.000000
-12213,12.418776,-11.669580,1.000000
-12214,12.454481,-11.707466,1.000000
-12215,12.482648,-11.737021,1.000000
-12216,12.517757,-11.769155,1.000000
-12217,12.547511,-11.796528,1.000000
-12218,12.584802,-11.830844,1.000000
-12219,12.614754,-11.859209,1.000000
-12220,12.647284,-11.890153,1.000000
-12221,12.679815,-11.920502,1.000000
-12222,12.715520,-11.954818,1.000000
-12223,12.749042,-11.986158,1.000000
-12224,12.781969,-12.017896,1.000000
-12225,12.811723,-12.045071,1.000000
-12226,12.844849,-12.075816,1.000000
-12227,12.878371,-12.106363,1.000000
-12228,12.913084,-12.137902,1.000000
-12229,12.947995,-12.169639,1.000000
-12230,12.982707,-12.200385,1.000000
-12231,13.019602,-12.233510,1.000000
-12232,13.051736,-12.264057,1.000000
-12233,13.086448,-12.296191,1.000000
-12234,13.117590,-12.326143,1.000000
-12235,13.156072,-12.363236,1.000000
-12236,13.186222,-12.393982,1.000000
-12237,13.219745,-12.428496,1.000000
-12238,13.255846,-12.467771,1.000000
-12239,13.285401,-12.499310,1.000000
-12240,13.320907,-12.536998,1.000000
-12241,13.353834,-12.570322,1.000000
-12242,13.387754,-12.601861,1.000000
-12243,13.419689,-12.629234,1.000000
-12244,13.457774,-12.663550,1.000000
-12245,13.492090,-12.695089,1.000000
-12246,13.522438,-12.723652,1.000000
-12247,13.558738,-12.758563,1.000000
-12248,13.591269,-12.790895,1.000000
-12249,13.621419,-12.819261,1.000000
-12250,13.659305,-12.854965,1.000000
-12251,13.691241,-12.883132,1.000000
-12252,13.726350,-12.914076,1.000000
-12253,13.760864,-12.944623,1.000000
-12254,13.798751,-12.979335,-1.000000
-12255,13.829694,-13.008295,-1.000000
-12256,13.866391,-13.044000,-1.000000
-12257,13.894557,-13.069985,-1.000000
-12258,13.918360,-13.087242,-1.000000
-12259,13.925898,-13.091209,-1.000000
-12260,13.924311,-13.085060,-1.000000
-12261,13.919551,-13.075340,-1.000000
-12262,13.915980,-13.064629,-1.000000
-12263,13.913005,-13.050942,-1.000000
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/drivetrain_spin_low.csv b/frc971/control_loops/matlab/drivetrain_spin_low.csv
deleted file mode 100644
index a96acbe..0000000
--- a/frc971/control_loops/matlab/drivetrain_spin_low.csv
+++ /dev/null
@@ -1,280 +0,0 @@
-120.220000,16.662837,-14.612612,12.000000,-12.000000
-120.230000,16.662837,-14.612612,12.000000,-12.000000
-120.240000,16.662837,-14.612612,12.000000,-12.000000
-120.250000,16.662837,-14.612612,12.000000,-12.000000
-120.260000,16.662837,-14.612612,12.000000,-12.000000
-120.270000,16.665217,-14.617571,12.000000,-12.000000
-120.280000,16.673152,-14.624117,12.000000,-12.000000
-120.290000,16.682474,-14.632051,12.000000,-12.000000
-120.300000,16.692194,-14.640977,12.000000,-12.000000
-120.310000,16.702112,-14.650895,12.000000,-12.000000
-120.320000,16.713220,-14.660020,12.000000,-12.000000
-120.330000,16.724526,-14.671326,12.000000,-12.000000
-120.340000,16.736626,-14.682632,12.000000,-12.000000
-120.350000,16.748527,-14.693939,12.000000,-12.000000
-120.360000,16.761024,-14.705245,12.000000,-12.000000
-120.370000,16.773719,-14.716552,12.000000,-12.000000
-120.380000,16.786017,-14.728255,12.000000,-12.000000
-120.390000,16.799109,-14.740156,12.000000,-12.000000
-120.400000,16.812002,-14.751661,12.000000,-12.000000
-120.410000,16.824895,-14.763364,12.000000,-12.000000
-120.420000,16.837193,-14.775861,12.000000,-12.000000
-120.430000,16.850087,-14.787960,12.000000,-12.000000
-120.440000,0.0,-0.0,12.000000,-12.000000
-120.450000,0.0,-0.0,12.000000,-12.000000
-120.460000,0.0,-0.0,12.000000,-12.000000
-120.470000,0.0,-0.0,12.000000,-12.000000
-120.480000,16.913759,-14.847864,12.000000,-12.000000
-120.490000,16.926653,-14.860361,12.000000,-12.000000
-120.500000,16.939546,-14.873453,12.000000,-12.000000
-120.510000,16.952439,-14.886147,12.000000,-12.000000
-120.520000,16.965134,-14.899041,12.000000,-12.000000
-120.530000,16.978821,-14.911537,12.000000,-12.000000
-120.540000,16.991714,-14.924232,12.000000,-12.000000
-120.550000,17.004409,-14.936729,12.000000,-12.000000
-120.560000,17.018294,-14.950019,12.000000,-12.000000
-120.570000,17.030592,-14.963110,12.000000,-12.000000
-120.580000,17.043882,-14.976400,12.000000,-12.000000
-120.590000,17.057569,-14.989690,12.000000,-12.000000
-120.600000,17.071850,-15.003178,12.000000,-12.000000
-120.610000,17.085537,-15.016270,12.000000,-12.000000
-120.620000,17.099422,-15.029758,12.000000,-12.000000
-120.630000,17.113109,-15.043048,12.000000,-12.000000
-120.640000,17.127192,-15.056735,12.000000,-12.000000
-120.650000,17.141672,-15.070818,12.000000,-12.000000
-120.660000,17.155756,-15.084505,12.000000,-12.000000
-120.670000,17.170434,-15.098192,12.000000,-12.000000
-120.680000,17.185113,-15.112275,12.000000,-12.000000
-120.690000,17.199990,-15.126359,12.000000,-12.000000
-120.700000,17.214073,-15.140442,12.000000,-12.000000
-120.710000,17.228553,-15.155120,12.000000,-12.000000
-120.720000,17.243430,-15.170196,12.000000,-12.000000
-120.730000,17.258307,-15.184279,12.000000,-12.000000
-120.740000,17.273183,-15.198561,12.000000,-12.000000
-120.750000,17.288259,-15.212842,12.000000,-12.000000
-120.760000,17.303731,-15.227521,12.000000,-12.000000
-120.770000,17.319202,-15.242398,12.000000,-12.000000
-120.780000,17.334674,-15.256878,12.000000,-12.000000
-120.790000,17.350345,-15.272151,12.000000,-12.000000
-120.800000,17.365618,-15.287425,12.000000,-12.000000
-120.810000,17.381288,-15.302500,12.000000,-12.000000
-120.820000,17.396959,-15.317972,12.000000,-12.000000
-120.830000,17.412431,-15.333444,12.000000,-12.000000
-120.840000,17.428101,-15.349313,12.000000,-12.000000
-120.850000,17.443176,-15.364388,12.000000,-12.000000
-120.860000,17.458846,-15.379265,12.000000,-12.000000
-120.870000,17.474318,-15.394340,12.000000,-12.000000
-120.880000,17.489988,-15.409812,12.000000,-12.000000
-120.890000,17.505064,-15.424887,12.000000,-12.000000
-120.900000,17.520932,-15.439962,12.000000,-12.000000
-120.910000,17.536404,-15.455236,12.000000,-12.000000
-120.920000,17.552074,-15.469914,12.000000,-12.000000
-120.930000,17.567745,-15.485188,12.000000,-12.000000
-120.940000,17.584208,-15.501255,12.000000,-12.000000
-120.950000,17.600275,-15.515735,12.000000,-12.000000
-120.960000,17.616541,-15.531207,12.000000,-12.000000
-120.970000,17.633004,-15.546282,12.000000,-12.000000
-120.980000,17.649865,-15.561555,12.000000,-12.000000
-120.990000,17.666527,-15.576234,12.000000,-12.000000
-121.000000,17.682792,-15.591111,12.000000,-12.000000
-121.010000,17.699256,-15.606384,12.000000,-12.000000
-121.020000,17.715521,-15.621658,12.000000,-12.000000
-121.030000,17.731786,-15.636534,12.000000,-12.000000
-121.040000,17.747853,-15.652006,12.000000,-12.000000
-121.050000,17.763722,-15.666883,12.000000,-12.000000
-121.060000,17.779789,-15.682355,12.000000,-12.000000
-121.070000,17.796253,-15.698025,12.000000,-12.000000
-121.080000,17.812716,-15.713696,12.000000,-12.000000
-121.090000,17.828585,-15.728771,12.000000,-12.000000
-121.100000,17.845247,-15.744441,12.000000,-12.000000
-121.110000,17.861512,-15.760310,12.000000,-12.000000
-121.120000,17.877778,-15.775980,12.000000,-12.000000
-121.130000,17.894241,-15.791650,12.000000,-12.000000
-121.140000,17.910507,-15.807519,12.000000,-12.000000
-121.150000,17.926970,-15.822991,12.000000,-12.000000
-121.160000,17.943037,-15.838066,12.000000,-12.000000
-121.170000,17.959104,-15.853736,12.000000,-12.000000
-121.180000,17.975568,-15.869605,12.000000,-12.000000
-121.190000,17.992032,-15.884680,12.000000,-12.000000
-121.200000,18.008694,-15.900747,12.000000,-12.000000
-121.210000,18.024364,-15.916814,12.000000,-12.000000
-121.220000,18.040828,-15.932286,12.000000,-12.000000
-121.230000,18.057291,-15.947559,12.000000,-12.000000
-121.240000,18.073755,-15.963825,12.000000,-12.000000
-121.250000,18.090615,-15.979495,12.000000,-12.000000
-121.260000,18.107476,-15.995959,12.000000,-12.000000
-121.270000,18.123939,-16.011232,12.000000,-12.000000
-121.280000,18.140998,-16.027299,12.000000,-12.000000
-121.290000,18.157462,-16.042573,12.000000,-12.000000
-121.300000,18.174719,-16.058838,12.000000,-12.000000
-121.310000,18.191183,-16.074707,12.000000,-12.000000
-121.320000,18.208242,-16.090575,12.000000,-12.000000
-121.330000,18.225102,-16.106444,12.000000,-12.000000
-121.340000,18.242161,-16.122511,12.000000,-12.000000
-121.350000,18.258823,-16.138181,12.000000,-12.000000
-121.360000,18.276080,-16.154248,12.000000,-12.000000
-121.370000,18.292742,-16.169918,12.000000,-12.000000
-121.380000,18.309801,-16.185588,12.000000,-12.000000
-121.390000,18.326463,-16.201655,12.000000,-12.000000
-121.400000,18.343521,-16.217524,12.000000,-12.000000
-121.410000,18.359985,-16.232996,12.000000,-12.000000
-121.420000,18.377242,-16.249063,12.000000,-12.000000
-121.430000,18.394301,-16.265130,12.000000,-12.000000
-121.440000,18.411558,-16.280800,12.000000,-12.000000
-121.450000,0.0,-0.0,12.000000,-12.000000
-121.460000,0.0,-0.0,12.000000,-12.000000
-121.470000,0.0,-0.0,12.000000,-12.000000
-121.480000,18.480587,-16.345068,12.000000,-12.000000
-121.490000,18.497447,-16.360738,12.000000,-12.000000
-121.500000,18.514506,-16.377202,12.000000,-12.000000
-121.510000,18.531564,-16.392475,12.000000,-12.000000
-121.520000,18.548623,-16.408542,12.000000,-12.000000
-121.530000,18.565880,-16.424609,12.000000,-12.000000
-121.540000,18.582542,-16.441073,12.000000,-12.000000
-121.550000,18.599601,-16.456743,12.000000,-12.000000
-121.560000,18.616858,-16.473009,12.000000,-12.000000
-121.570000,18.633520,-16.489274,12.000000,-12.000000
-121.580000,18.650381,-16.505738,12.000000,-12.000000
-121.590000,18.666646,-16.522003,12.000000,-12.000000
-121.600000,18.683705,-16.537673,12.000000,-12.000000
-121.610000,18.700764,-16.553542,12.000000,-12.000000
-121.620000,18.718219,-16.570204,12.000000,-12.000000
-121.630000,18.734683,-16.585676,12.000000,-12.000000
-121.640000,18.752138,-16.602140,12.000000,-12.000000
-121.650000,18.768602,-16.618008,12.000000,-12.000000
-121.660000,18.785661,-16.634075,12.000000,-12.000000
-121.670000,18.802521,-16.649745,12.000000,-12.000000
-121.680000,18.819977,-16.666011,12.000000,-12.000000
-121.690000,18.836440,-16.681879,12.000000,-12.000000
-121.700000,18.853301,-16.697748,12.000000,-12.000000
-121.710000,18.870161,-16.713617,12.000000,-12.000000
-121.720000,18.887815,-16.729882,12.000000,-12.000000
-121.730000,18.904675,-16.745949,12.000000,-12.000000
-121.740000,18.921932,-16.762214,12.000000,-12.000000
-121.750000,18.938594,-16.777686,12.000000,-12.000000
-121.760000,18.955653,-16.793555,12.000000,-12.000000
-121.770000,18.972910,-16.809423,12.000000,-12.000000
-121.780000,18.990564,-16.825689,12.000000,-12.000000
-121.790000,19.007623,-16.841359,12.000000,-12.000000
-121.800000,19.025078,-16.857426,12.000000,-12.000000
-121.810000,19.041740,-16.873096,12.000000,-12.000000
-121.820000,19.058998,-16.889163,12.000000,-12.000000
-121.830000,19.076056,-16.905032,12.000000,-12.000000
-121.840000,19.094107,-16.921694,12.000000,-12.000000
-121.850000,19.110372,-16.937364,12.000000,-12.000000
-121.860000,19.128423,-16.953828,12.000000,-12.000000
-121.870000,19.144886,-16.969300,12.000000,-12.000000
-121.880000,19.162540,-16.986160,12.000000,-12.000000
-121.890000,19.179004,-17.001433,12.000000,-12.000000
-121.900000,19.196459,-17.017897,12.000000,-12.000000
-121.910000,19.213716,-17.033964,12.000000,-12.000000
-121.920000,19.231172,-17.050428,12.000000,-12.000000
-121.930000,19.248231,-17.066098,12.000000,-12.000000
-121.940000,19.265885,-17.082562,12.000000,-12.000000
-121.950000,19.283340,-17.099025,12.000000,-12.000000
-121.960000,19.301192,-17.115886,12.000000,-12.000000
-121.970000,19.318251,-17.131754,12.000000,-12.000000
-121.980000,19.335905,-17.148218,12.000000,-12.000000
-121.990000,19.352765,-17.164285,12.000000,-12.000000
-122.000000,19.370022,-17.180947,12.000000,-12.000000
-122.010000,19.387081,-17.197411,12.000000,-12.000000
-122.020000,19.404933,-17.214073,12.000000,-12.000000
-122.030000,19.421199,-17.229942,12.000000,-12.000000
-122.040000,19.439448,-17.247000,12.000000,-12.000000
-122.050000,19.455514,-17.262472,12.000000,-12.000000
-122.060000,19.472772,-17.279333,12.000000,-12.000000
-122.070000,19.489632,-17.295400,12.000000,-12.000000
-122.080000,19.507087,-17.311665,12.000000,-12.000000
-122.090000,19.523948,-17.327930,12.000000,-12.000000
-122.100000,19.541403,-17.343799,12.000000,-12.000000
-122.110000,19.558462,-17.360064,12.000000,-12.000000
-122.120000,19.576116,-17.376925,12.000000,-12.000000
-122.130000,19.592976,-17.392992,12.000000,-12.000000
-122.140000,19.610432,-17.409654,12.000000,-12.000000
-122.150000,19.627491,-17.425125,12.000000,-12.000000
-122.160000,19.644946,-17.441788,12.000000,-12.000000
-122.170000,19.661608,-17.457458,12.000000,-12.000000
-122.180000,19.679262,-17.473525,12.000000,-12.000000
-122.190000,19.696321,-17.489195,12.000000,-12.000000
-122.200000,19.713379,-17.505262,12.000000,-12.000000
-122.210000,19.730438,-17.520932,12.000000,-12.000000
-122.220000,19.748687,-17.537198,12.000000,-12.000000
-122.230000,19.765349,-17.552868,12.000000,-12.000000
-122.240000,19.783003,-17.569728,12.000000,-12.000000
-122.250000,19.799665,-17.585398,12.000000,-12.000000
-122.260000,19.817517,-17.601862,12.000000,-12.000000
-122.270000,19.834378,-17.617136,12.000000,-12.000000
-122.280000,19.851635,-17.633401,12.000000,-12.000000
-122.290000,19.869090,-17.649270,12.000000,-12.000000
-122.300000,19.886347,-17.665535,12.000000,-12.000000
-122.310000,19.903604,-17.681404,12.000000,-12.000000
-122.320000,19.921258,-17.698066,12.000000,-12.000000
-122.330000,19.938119,-17.713934,12.000000,-12.000000
-122.340000,19.955177,-17.729803,12.000000,-12.000000
-122.350000,19.972435,-17.746068,12.000000,-12.000000
-122.360000,19.989692,-17.762532,12.000000,-12.000000
-122.370000,20.005957,-17.778400,12.000000,-12.000000
-122.380000,20.023611,-17.794864,12.000000,-12.000000
-122.390000,20.040075,-17.810534,12.000000,-12.000000
-122.400000,20.057530,-17.826998,12.000000,-12.000000
-122.410000,20.074589,-17.842867,12.000000,-12.000000
-122.420000,20.092243,-17.859925,12.000000,-12.000000
-122.430000,20.109103,-17.875199,12.000000,-12.000000
-122.440000,20.126360,-17.891663,12.000000,-12.000000
-122.450000,0.0,-0.0,12.000000,-12.000000
-122.460000,0.0,-0.0,12.000000,-12.000000
-122.470000,0.0,-0.0,12.000000,-12.000000
-122.480000,20.195587,-17.957319,12.000000,-12.000000
-122.490000,20.212249,-17.973188,12.000000,-12.000000
-122.500000,20.229506,-17.989651,12.000000,-12.000000
-122.510000,20.246565,-18.005520,12.000000,-12.000000
-122.520000,20.263822,-18.022182,12.000000,-12.000000
-122.530000,20.281079,-18.038051,12.000000,-12.000000
-122.540000,20.298733,-18.054911,12.000000,-12.000000
-122.550000,20.314998,-18.070185,12.000000,-12.000000
-122.560000,20.333049,-18.087243,12.000000,-12.000000
-122.570000,20.350108,-18.102914,12.000000,-12.000000
-122.580000,20.367761,-18.119576,12.000000,-12.000000
-122.590000,20.385018,-18.135643,12.000000,-12.000000
-122.600000,20.402276,-18.152106,12.000000,-12.000000
-122.610000,20.419929,-18.167777,12.000000,-12.000000
-122.620000,20.437782,-18.184835,12.000000,-12.000000
-122.630000,20.455039,-18.200704,12.000000,-12.000000
-122.640000,20.472296,-18.216969,12.000000,-12.000000
-122.650000,20.489355,-18.233036,12.000000,-12.000000
-122.660000,20.507604,-18.249698,12.000000,-12.000000
-122.670000,20.524861,-18.265170,12.000000,-12.000000
-122.680000,20.542118,-18.281634,12.000000,-12.000000
-122.690000,20.559177,-18.297106,12.000000,-12.000000
-122.700000,20.576235,-18.313371,12.000000,-12.000000
-122.710000,20.593492,-18.329240,12.000000,-12.000000
-122.720000,20.610948,-18.346100,12.000000,-12.000000
-122.730000,20.628205,-18.361770,12.000000,-12.000000
-122.740000,20.646454,-18.378631,12.000000,-12.000000
-122.750000,20.662918,-18.393904,12.000000,-12.000000
-122.760000,20.681166,-18.410765,12.000000,-12.000000
-122.770000,20.697829,-18.426435,12.000000,-12.000000
-122.780000,20.715681,-18.442700,12.000000,-12.000000
-122.790000,20.732739,-18.458767,12.000000,-12.000000
-122.800000,20.749997,-18.474636,12.000000,-12.000000
-122.810000,20.767254,-18.491100,12.000000,-12.000000
-122.820000,20.784709,-18.507762,12.000000,-12.000000
-122.830000,20.802958,-18.525217,12.000000,-12.000000
-122.840000,20.820017,-18.541681,12.000000,-12.000000
-122.850000,20.835290,-18.555962,12.000000,-12.000000
-122.860000,20.852547,-18.572228,12.000000,-12.000000
-122.870000,0.0,-0.0,12.000000,-12.000000
-122.880000,0.0,-0.0,12.000000,-12.000000
-122.890000,0.0,-0.0,12.000000,-12.000000
-122.900000,0.0,-0.0,12.000000,-12.000000
-122.910000,20.938833,-18.652959,12.000000,-12.000000
-122.920000,20.956289,-18.669026,12.000000,-12.000000
-122.930000,20.973744,-18.685292,12.000000,-12.000000
-122.940000,20.991596,-18.702350,12.000000,-12.000000
-122.950000,21.008258,-18.718021,12.000000,-12.000000
-122.960000,21.025912,-18.734683,12.000000,-12.000000
-122.970000,21.042772,-18.750948,12.000000,-12.000000
-122.980000,21.061021,-18.768205,12.000000,-12.000000
-122.990000,21.077882,-18.783875,12.000000,-12.000000
-123.000000,21.094941,-18.800141,12.000000,-12.000000
-123.010000,21.111999,-18.816406,12.000000,-12.000000
diff --git a/frc971/control_loops/matlab/drivetrain_spin_low.mat b/frc971/control_loops/matlab/drivetrain_spin_low.mat
deleted file mode 100644
index 457083f..0000000
--- a/frc971/control_loops/matlab/drivetrain_spin_low.mat
+++ /dev/null
Binary files differ
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low.csv b/frc971/control_loops/matlab/drivetrain_strait_low.csv
deleted file mode 100644
index 6966f5b..0000000
--- a/frc971/control_loops/matlab/drivetrain_strait_low.csv
+++ /dev/null
@@ -1,103 +0,0 @@
-11.590000,15.318369,-16.398228,12.000000,12.000000
-11.600000,15.318369,-16.398228,12.000000,12.000000
-11.610000,15.318369,-16.398228,12.000000,12.000000
-11.620000,15.318369,-16.398228,12.000000,12.000000
-11.630000,15.318369,-16.398228,12.000000,12.000000
-11.640000,15.321146,-16.395649,12.000000,12.000000
-11.650000,15.329278,-16.388707,12.000000,12.000000
-11.660000,15.338403,-16.380772,12.000000,12.000000
-11.670000,15.347924,-16.372045,12.000000,12.000000
-11.680000,15.358635,-16.362325,12.000000,12.000000
-11.690000,15.369545,-16.351812,12.000000,12.000000
-11.700000,15.381050,-16.341101,12.000000,12.000000
-11.710000,15.392555,-16.329993,12.000000,12.000000
-11.720000,15.404258,-16.319083,12.000000,12.000000
-11.730000,15.415961,-16.308173,12.000000,12.000000
-11.740000,15.428061,-16.294685,12.000000,12.000000
-11.750000,15.440954,-16.283379,12.000000,12.000000
-11.760000,15.453847,-16.268502,12.000000,12.000000
-11.770000,15.466939,-16.255014,12.000000,12.000000
-11.780000,15.479038,-16.241327,12.000000,12.000000
-11.790000,15.491138,-16.228235,12.000000,12.000000
-11.800000,15.503635,-16.216136,12.000000,12.000000
-11.810000,15.515933,-16.204234,12.000000,12.000000
-11.820000,15.528628,-16.192134,12.000000,12.000000
-11.830000,15.541521,-16.179043,12.000000,12.000000
-11.840000,15.554811,-16.165951,12.000000,12.000000
-11.850000,15.568299,-16.152859,12.000000,12.000000
-11.860000,15.581589,-16.139569,12.000000,12.000000
-11.870000,15.595673,-16.126081,12.000000,12.000000
-11.880000,15.610153,-16.112791,12.000000,12.000000
-11.890000,15.624435,-16.098708,12.000000,12.000000
-11.900000,15.638716,-16.084228,12.000000,12.000000
-11.910000,15.653395,-16.069946,12.000000,12.000000
-11.920000,15.668272,-16.055466,12.000000,12.000000
-11.930000,15.683347,-16.040787,12.000000,12.000000
-11.940000,15.698620,-16.026307,12.000000,12.000000
-11.950000,15.714092,-16.011430,12.000000,12.000000
-11.960000,15.728969,-15.996554,12.000000,12.000000
-11.970000,15.744243,-15.981478,12.000000,12.000000
-11.980000,15.759715,-15.966205,12.000000,12.000000
-11.990000,15.774988,-15.950931,12.000000,12.000000
-12.000000,15.789865,-15.935459,12.000000,12.000000
-12.010000,15.805535,-15.920186,12.000000,12.000000
-12.020000,15.821205,-15.904516,12.000000,12.000000
-12.030000,15.836876,-15.888845,12.000000,12.000000
-12.040000,15.852744,-15.873175,12.000000,12.000000
-12.050000,15.868613,-15.857703,12.000000,12.000000
-12.060000,15.884680,-15.841835,12.000000,12.000000
-12.070000,15.900747,-15.826164,12.000000,12.000000
-12.080000,15.916615,-15.810296,12.000000,12.000000
-12.090000,15.932881,-15.794427,12.000000,12.000000
-12.100000,15.949146,-15.778162,12.000000,12.000000
-12.110000,15.965213,-15.762293,12.000000,12.000000
-12.120000,15.981677,-15.746226,12.000000,12.000000
-12.130000,0.0,-0.0,12.000000,12.000000
-12.140000,0.0,-0.0,12.000000,12.000000
-12.150000,0.0,-0.0,12.000000,12.000000
-12.160000,16.048127,-15.680173,12.000000,12.000000
-12.170000,16.064194,-15.663709,12.000000,12.000000
-12.180000,16.081649,-15.647047,12.000000,12.000000
-12.190000,16.098113,-15.630385,12.000000,12.000000
-12.200000,16.114973,-15.613525,12.000000,12.000000
-12.210000,16.131834,-15.597061,12.000000,12.000000
-12.220000,16.148892,-15.580399,12.000000,12.000000
-12.230000,16.165951,-15.563340,12.000000,12.000000
-12.240000,16.183010,-15.546877,12.000000,12.000000
-12.250000,16.200069,-15.530016,12.000000,12.000000
-12.260000,16.217326,-15.512958,12.000000,12.000000
-12.270000,16.234583,-15.495700,12.000000,12.000000
-12.280000,16.251840,-15.478840,12.000000,12.000000
-12.290000,16.268899,-15.461980,12.000000,12.000000
-12.300000,16.286156,-15.445119,12.000000,12.000000
-12.310000,16.303215,-15.428061,12.000000,12.000000
-12.320000,16.320273,-15.411002,12.000000,12.000000
-12.330000,16.337729,-15.393943,12.000000,12.000000
-12.340000,16.354589,-15.376884,12.000000,12.000000
-12.350000,16.371648,-15.359825,12.000000,12.000000
-12.360000,16.389103,-15.342767,12.000000,12.000000
-12.370000,16.406162,-15.325708,12.000000,12.000000
-12.380000,16.423221,-15.308649,12.000000,12.000000
-12.390000,16.440676,-15.291590,12.000000,12.000000
-12.400000,16.457934,-15.274333,12.000000,12.000000
-12.410000,16.475191,-15.257671,12.000000,12.000000
-12.420000,16.492646,-15.240216,12.000000,12.000000
-12.430000,16.509903,-15.222959,12.000000,12.000000
-12.440000,16.527557,-15.205900,12.000000,12.000000
-12.450000,16.544616,-15.189040,12.000000,12.000000
-12.460000,16.561873,-15.171782,12.000000,12.000000
-12.470000,16.579130,-15.154922,12.000000,12.000000
-12.480000,16.596982,-15.137665,12.000000,12.000000
-12.490000,16.614239,-15.120209,12.000000,12.000000
-12.500000,16.631100,-15.103151,12.000000,12.000000
-12.510000,16.648159,-15.085894,12.000000,12.000000
-12.520000,16.666011,-15.068636,12.000000,12.000000
-12.530000,16.683069,-15.051379,12.000000,12.000000
-12.540000,16.700327,-15.034321,12.000000,12.000000
-12.550000,16.717782,-15.017262,12.000000,12.000000
-12.560000,16.734841,-15.000203,12.000000,12.000000
-12.570000,16.752495,-14.982946,12.000000,12.000000
-12.580000,16.769752,-14.965887,12.000000,12.000000
-12.590000,16.787009,-14.948828,12.000000,12.000000
-12.600000,16.804464,-14.931175,12.000000,12.000000
-12.610000,16.821920,-14.914314,12.000000,12.000000
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low.mat b/frc971/control_loops/matlab/drivetrain_strait_low.mat
deleted file mode 100644
index e6a4973..0000000
--- a/frc971/control_loops/matlab/drivetrain_strait_low.mat
+++ /dev/null
Binary files differ
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.csv b/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.csv
deleted file mode 100644
index 0091dd2..0000000
--- a/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.csv
+++ /dev/null
@@ -1,185 +0,0 @@
-31783,-2.373349,-1.651328,1.000000
-31784,-2.373349,-1.651328,1.000000
-31785,-2.373349,-1.651328,1.000000
-31786,-2.373349,-1.651328,1.000000
-31787,-2.370771,-1.651328,1.000000
-31788,-2.364622,-1.649344,1.000000
-31789,-2.356489,-1.639624,1.000000
-31790,-2.348158,-1.632880,1.000000
-31791,-2.336257,-1.622367,1.000000
-31792,-2.325744,-1.612449,1.000000
-31793,-2.312652,-1.599755,1.000000
-31794,-2.301941,-1.589440,1.000000
-31795,-2.288651,-1.577142,1.000000
-31796,-2.278138,-1.567224,1.000000
-31797,-2.263856,-1.553934,1.000000
-31798,-2.251558,-1.542231,1.000000
-31799,-2.236681,-1.526957,1.000000
-31800,-2.223589,-1.513072,1.000000
-31801,-2.211093,-1.499386,1.000000
-31802,-2.198200,-1.486294,1.000000
-31803,-2.185505,-1.473004,1.000000
-31804,-2.173603,-1.462491,1.000000
-31805,-2.160115,-1.450193,1.000000
-31806,-2.145238,-1.436506,1.000000
-31807,-2.131353,-1.423613,1.000000
-31808,-2.117666,-1.410521,1.000000
-31809,-2.103980,-1.397231,1.000000
-31810,-2.089500,-1.383148,1.000000
-31811,-2.076011,-1.369660,1.000000
-31812,-2.063316,-1.357163,1.000000
-31813,-2.047646,-1.341493,1.000000
-31814,-2.034356,-1.328600,1.000000
-31815,-2.017496,-1.312533,1.000000
-31816,-2.002619,-1.297854,1.000000
-31817,-1.987544,-1.282977,1.000000
-31818,-1.974055,-1.269886,1.000000
-31819,-1.957195,-1.253819,1.000000
-31820,-1.941525,-1.238347,1.000000
-31821,-1.927441,-1.224859,1.000000
-31822,-1.910383,-1.208197,1.000000
-31823,-1.896299,-1.194311,1.000000
-31824,-1.879042,-1.177253,1.000000
-31825,-1.862578,-1.161384,1.000000
-31826,-1.846908,-1.145515,1.000000
-31827,-1.829254,-1.128060,1.000000
-31828,-1.814378,-1.114175,1.000000
-31829,-1.798906,-1.098306,1.000000
-31830,-1.782442,-1.081644,1.000000
-31831,-1.765978,-1.065776,1.000000
-31832,-1.751697,-1.051097,1.000000
-31833,-1.735233,-1.035229,1.000000
-31834,-1.718571,-1.019162,1.000000
-31835,-1.700124,-1.000913,1.000000
-31836,-1.683461,-0.984846,1.000000
-31837,-1.666799,-0.968382,1.000000
-31838,-1.650137,-0.952117,1.000000
-31839,-1.633277,-0.935851,1.000000
-31840,-1.616020,-0.919189,1.000000
-31841,-1.599358,-0.902527,1.000000
-31842,-1.582696,-0.885469,1.000000
-31843,-1.565835,-0.868608,1.000000
-31844,-1.548975,-0.851748,1.000000
-31845,-1.533305,-0.836474,1.000000
-31846,-1.516643,-0.820209,1.000000
-31847,-1.497997,-0.801762,1.000000
-31848,-1.481137,-0.784901,1.000000
-31849,-1.463880,-0.767843,1.000000
-31850,-1.446424,-0.750784,1.000000
-31851,-1.430952,-0.735709,1.000000
-31852,-1.411711,-0.717261,1.000000
-31853,-1.396240,-0.701789,1.000000
-31854,-1.377197,-0.682747,1.000000
-31855,-1.359543,-0.665688,1.000000
-31856,-1.342286,-0.648630,1.000000
-31857,-1.325029,-0.631174,1.000000
-31864,-1.204626,-0.512358,1.000000
-31865,-1.187171,-0.495299,1.000000
-31866,-1.169517,-0.478240,1.000000
-31867,-1.152260,-0.460785,1.000000
-31868,-1.134606,-0.443726,1.000000
-31869,-1.117150,-0.426667,1.000000
-31870,-1.097116,-0.407228,1.000000
-31871,-1.081446,-0.391756,1.000000
-31872,-1.062205,-0.373111,1.000000
-31873,-1.044551,-0.355457,1.000000
-31874,-1.027096,-0.337803,1.000000
-31875,-1.009045,-0.320546,1.000000
-31876,-0.993574,-0.304876,1.000000
-31877,-0.974134,-0.286032,1.000000
-31878,-0.958861,-0.270560,1.000000
-31879,-0.939422,-0.250724,1.000000
-31880,-0.921371,-0.233467,1.000000
-31881,-0.903916,-0.216408,1.000000
-31882,-0.886659,-0.199349,1.000000
-31883,-0.870592,-0.183679,1.000000
-31884,-0.850954,-0.164439,1.000000
-31885,-0.834887,-0.148768,1.000000
-31886,-0.815448,-0.129726,1.000000
-31887,-0.797795,-0.112667,1.000000
-31888,-0.779942,-0.095013,1.000000
-31889,-0.762090,-0.077955,1.000000
-31890,-0.746420,-0.061689,1.000000
-31891,-0.727179,-0.042647,1.000000
-31892,-0.709525,-0.025390,1.000000
-31893,-0.693657,-0.009720,1.000000
-31894,-0.674416,0.009323,1.000000
-31895,-0.658349,0.025390,1.000000
-31896,-0.640695,0.042449,1.000000
-31897,-0.621455,0.061491,1.000000
-31898,-0.603999,0.078748,1.000000
-31899,-0.586147,0.096402,1.000000
-31900,-0.567898,0.113659,1.000000
-31901,-0.550443,0.130718,1.000000
-31902,-0.532590,0.148570,1.000000
-31903,-0.514936,0.165827,1.000000
-31904,-0.497283,0.183282,1.000000
-31905,-0.481216,0.199151,1.000000
-31906,-0.463562,0.216607,1.000000
-31907,-0.445710,0.234062,1.000000
-31908,-0.428056,0.251518,1.000000
-31909,-0.408815,0.270560,1.000000
-31910,-0.390765,0.288412,1.000000
-31911,-0.373706,0.305471,1.000000
-31912,-0.357441,0.320943,1.000000
-31913,-0.337803,0.340580,1.000000
-31914,-0.321934,0.356052,1.000000
-31915,-0.302495,0.375491,1.000000
-31916,-0.284643,0.392550,1.000000
-31917,-0.266791,0.410005,1.000000
-31918,-0.248939,0.427659,1.000000
-31919,-0.231285,0.444916,1.000000
-31920,-0.213234,0.462570,1.000000
-31921,-0.195581,0.479827,1.000000
-31922,-0.178125,0.497084,1.000000
-31923,-0.160273,0.514738,1.000000
-31924,-0.142818,0.532194,1.000000
-31925,-0.126949,0.548261,1.000000
-31926,-0.109097,0.566113,1.000000
-31927,-0.089459,0.585552,1.000000
-31928,-0.071607,0.602809,1.000000
-31929,-0.053557,0.620463,1.000000
-31930,-0.035308,0.638315,1.000000
-31931,-0.017852,0.655572,1.000000
-31932,0.000198,0.673424,1.000000
-31933,0.016265,0.688896,1.000000
-31934,0.036101,0.708732,1.000000
-31935,0.054152,0.726187,1.000000
-31936,0.071607,0.743841,1.000000
-31937,0.089658,0.761693,1.000000
-31938,0.107113,0.779149,1.000000
-31939,0.124965,0.796803,1.000000
-31940,0.141429,0.812671,1.000000
-31941,0.158884,0.830325,1.000000
-31942,0.177927,0.849368,1.000000
-31943,0.195581,0.867418,1.000000
-31944,0.213433,0.884874,1.000000
-31945,0.229500,0.900742,1.000000
-31946,0.249336,0.919784,1.000000
-31947,0.266989,0.937240,1.000000
-31948,0.285040,0.954695,1.000000
-31949,0.301107,0.970564,1.000000
-31950,0.320943,0.989805,1.000000
-31951,0.338200,1.007260,1.000000
-31952,0.355854,1.024517,1.000000
-31953,0.372119,1.040584,1.000000
-31954,0.391360,1.059627,1.000000
-31955,0.409609,1.077479,1.000000
-31956,0.426866,1.094934,1.000000
-31957,0.444718,1.112191,1.000000
-31964,0.566906,1.232793,1.000000
-31965,0.584362,1.250248,-1.000000
-31966,0.602412,1.267902,-1.000000
-31967,0.620066,1.285556,-1.000000
-31968,0.637720,1.302615,-1.000000
-31969,0.656762,1.317690,-1.000000
-31970,0.664895,1.321062,-1.000000
-31971,0.667077,1.320070,-1.000000
-31972,0.669655,1.316698,-1.000000
-31973,0.666482,1.313524,-1.000000
-31974,0.660928,1.307177,-1.000000
-31975,0.652002,1.297656,-1.000000
-31976,0.641687,1.287143,-1.000000
-31977,0.630777,1.276630,-1.000000
-31978,0.619273,1.268101,-1.000000
-31979,0.608760,1.256992,-1.000000
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.mat b/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.mat
deleted file mode 100644
index e9cd690..0000000
--- a/frc971/control_loops/matlab/drivetrain_strait_low_wgaps.mat
+++ /dev/null
Binary files differ
diff --git a/frc971/control_loops/matlab/writeMat.m b/frc971/control_loops/matlab/writeMat.m
deleted file mode 100644
index b1541f5..0000000
--- a/frc971/control_loops/matlab/writeMat.m
+++ /dev/null
@@ -1,16 +0,0 @@
-function writeMat(fd, matrix, name)
- %fprintf(fd, '%s = init_matrix(%d, %d);\n', name, size(matrix, 1), size(matrix, 2));
- fprintf(fd, '%s << ', name);
- first_loop = 1;
- for i=1:size(matrix, 1)
- for j=1:size(matrix, 2)
- if first_loop
- first_loop = 0;
- else
- fprintf(fd, ', ');
- end
- fprintf(fd, '%.10f', matrix(i, j));
- end
- end
- fprintf(fd, '; \\\n');
-end
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/writeMatFlash.m b/frc971/control_loops/matlab/writeMatFlash.m
deleted file mode 100644
index 10104d0..0000000
--- a/frc971/control_loops/matlab/writeMatFlash.m
+++ /dev/null
@@ -1,16 +0,0 @@
-function writeMatFlash(fd, matrix, name)
- %fprintf(fd, '%s = init_matrix(%d, %d);\n', name, size(matrix, 1), size(matrix, 2));
- fprintf(fd, 'flash_matrix(%s, ', name);
- first_loop = 1;
- for i=1:size(matrix, 1)
- for j=1:size(matrix, 2)
- if first_loop
- first_loop = 0;
- else
- fprintf(fd, ', ');
- end
- fprintf(fd, '%.10f', matrix(i, j));
- end
- end
- fprintf(fd, ');\n');
-end
diff --git a/frc971/control_loops/matlab/writeMatFooter.m b/frc971/control_loops/matlab/writeMatFooter.m
deleted file mode 100644
index b23664e..0000000
--- a/frc971/control_loops/matlab/writeMatFooter.m
+++ /dev/null
@@ -1,3 +0,0 @@
-function writeMatFooter(fd)
- fprintf(fd, '\n');
-end
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/writeMatFooterFlash.m b/frc971/control_loops/matlab/writeMatFooterFlash.m
deleted file mode 100644
index 5326a94..0000000
--- a/frc971/control_loops/matlab/writeMatFooterFlash.m
+++ /dev/null
@@ -1,3 +0,0 @@
-function writeMatFooterFlash(fd)
- fprintf(fd, '\n');
-end
diff --git a/frc971/control_loops/matlab/writeMatHeader.m b/frc971/control_loops/matlab/writeMatHeader.m
deleted file mode 100644
index 5c100f3..0000000
--- a/frc971/control_loops/matlab/writeMatHeader.m
+++ /dev/null
@@ -1,4 +0,0 @@
-function writeMatHeader(fd, number_of_states, number_of_outputs)
- fprintf(fd, 'typedef StateFeedbackLoop<%d, %d> MatrixClass;\n', number_of_states, number_of_outputs);
- fprintf(fd, '#define MATRIX_INIT ');
-end
\ No newline at end of file
diff --git a/frc971/control_loops/matlab/writeMatHeaderFlash.m b/frc971/control_loops/matlab/writeMatHeaderFlash.m
deleted file mode 100644
index 88a6cc6..0000000
--- a/frc971/control_loops/matlab/writeMatHeaderFlash.m
+++ /dev/null
@@ -1,4 +0,0 @@
-function writeMatHeaderFlash(fd, number_of_states, number_of_outputs)
- fprintf(fd, 'typedef StateFeedbackLoop<%d, %d> MatrixClass;\n', number_of_states, number_of_outputs);
- fprintf(fd, '#define MATRIX_INIT ');
-end
diff --git a/frc971/control_loops/python/arm.py b/frc971/control_loops/python/arm.py
deleted file mode 100755
index e17990a..0000000
--- a/frc971/control_loops/python/arm.py
+++ /dev/null
@@ -1,409 +0,0 @@
-#!/usr/bin/python
-
-import control_loop
-import controls
-import polytope
-import polydrivetrain
-import numpy
-import math
-import sys
-import matplotlib
-from matplotlib import pylab
-
-
-class Arm(control_loop.ControlLoop):
- def __init__(self, name="Arm", mass=None):
- super(Arm, self).__init__(name)
- # Stall Torque in N m
- self.stall_torque = 0.476
- # Stall Current in Amps
- self.stall_current = 80.730
- # Free Speed in RPM
- self.free_speed = 13906.0
- # Free Current in Amps
- self.free_current = 5.820
- # Mass of the arm
- if mass is None:
- self.mass = 13.0
- else:
- self.mass = mass
-
- # Resistance of the motor
- self.R = 12.0 / self.stall_current
- # Motor velocity constant
- self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
- # Torque constant
- self.Kt = self.stall_torque / self.stall_current
- # Gear ratio
- self.G = (44.0 / 12.0) * (54.0 / 14.0) * (54.0 / 14.0) * (44.0 / 20.0) * (72.0 / 16.0)
- # Fridge arm length
- self.r = 32 * 0.0254
- # Control loop time step
- self.dt = 0.005
-
- # Arm moment of inertia
- self.J = self.r * self.mass
-
- # Arm left/right spring constant (N*m / radian)
- self.spring = 100.0
-
- # State is [average position, average velocity,
- # position difference/2, velocity difference/2]
- # Position difference is 1 - 2
- # Input is [Voltage 1, Voltage 2]
-
- self.C1 = self.spring / (self.J * 0.5)
- self.C2 = self.Kt * self.G / (self.J * 0.5 * self.R)
- self.C3 = self.G * self.G * self.Kt / (self.R * self.J * 0.5 * self.Kv)
-
- self.A_continuous = numpy.matrix(
- [[0, 1, 0, 0],
- [0, -self.C3, 0, 0],
- [0, 0, 0, 1],
- [0, 0, -self.C1 * 2.0, -self.C3]])
-
- print 'Full speed is', self.C2 / self.C3 * 12.0
-
- print 'Stall arm difference is', 12.0 * self.C2 / self.C1
- print 'Stall arm difference first principles is', self.stall_torque * self.G / self.spring
-
- print '5 degrees of arm error is', self.spring / self.r * (math.pi * 5.0 / 180.0)
-
- # Start with the unmodified input
- self.B_continuous = numpy.matrix(
- [[0, 0],
- [self.C2 / 2.0, self.C2 / 2.0],
- [0, 0],
- [self.C2 / 2.0, -self.C2 / 2.0]])
-
- self.C = numpy.matrix([[1, 0, 1, 0],
- [1, 0, -1, 0]])
- self.D = numpy.matrix([[0, 0],
- [0, 0]])
-
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
-
- controlability = controls.ctrb(self.A, self.B);
- print 'Rank of augmented controlability matrix.', numpy.linalg.matrix_rank(
- controlability)
-
- q_pos = 0.02
- q_vel = 0.300
- q_pos_diff = 0.005
- q_vel_diff = 0.13
- self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
- [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
- [0.0, 0.0, (1.0 / (q_pos_diff ** 2.0)), 0.0],
- [0.0, 0.0, 0.0, (1.0 / (q_vel_diff ** 2.0))]])
-
- self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
- [0.0, 1.0 / (12.0 ** 2.0)]])
- self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
- print 'Controller'
- print self.K
-
- print 'Controller Poles'
- print numpy.linalg.eig(self.A - self.B * self.K)[0]
-
- self.rpl = 0.20
- self.ipl = 0.05
- self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
- self.rpl + 1j * self.ipl,
- self.rpl - 1j * self.ipl,
- self.rpl - 1j * self.ipl])
-
- # The box formed by U_min and U_max must encompass all possible values,
- # or else Austin's code gets angry.
- self.U_max = numpy.matrix([[12.0], [12.0]])
- self.U_min = numpy.matrix([[-12.0], [-12.0]])
-
- print 'Observer (Converted to a KF)', numpy.linalg.inv(self.A) * self.L
-
- self.InitializeState()
-
-
-class IntegralArm(Arm):
- def __init__(self, name="IntegralArm", mass=None):
- super(IntegralArm, self).__init__(name=name, mass=mass)
-
- self.A_continuous_unaugmented = self.A_continuous
- self.A_continuous = numpy.matrix(numpy.zeros((5, 5)))
- self.A_continuous[0:4, 0:4] = self.A_continuous_unaugmented
- self.A_continuous[1, 4] = self.C2
-
- # Start with the unmodified input
- self.B_continuous_unaugmented = self.B_continuous
- self.B_continuous = numpy.matrix(numpy.zeros((5, 2)))
- self.B_continuous[0:4, 0:2] = self.B_continuous_unaugmented
-
- self.C_unaugmented = self.C
- self.C = numpy.matrix(numpy.zeros((2, 5)))
- self.C[0:2, 0:4] = self.C_unaugmented
-
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
- print 'A cont', self.A_continuous
- print 'B cont', self.B_continuous
- print 'A discrete', self.A
-
- q_pos = 0.08
- q_vel = 0.40
-
- q_pos_diff = 0.08
- q_vel_diff = 0.40
- q_voltage = 6.0
- self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0, 0.0, 0.0, 0.0],
- [0.0, (q_vel ** 2.0), 0.0, 0.0, 0.0],
- [0.0, 0.0, (q_pos_diff ** 2.0), 0.0, 0.0],
- [0.0, 0.0, 0.0, (q_vel_diff ** 2.0), 0.0],
- [0.0, 0.0, 0.0, 0.0, (q_voltage ** 2.0)]])
-
- r_volts = 0.05
- self.R = numpy.matrix([[(r_volts ** 2.0), 0.0],
- [0.0, (r_volts ** 2.0)]])
-
- self.KalmanGain, self.Q_steady = controls.kalman(
- A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
-
- self.U_max = numpy.matrix([[12.0], [12.0]])
- self.U_min = numpy.matrix([[-12.0], [-12.0]])
-
- self.K_unaugmented = self.K
- self.K = numpy.matrix(numpy.zeros((2, 5)));
- self.K[0:2, 0:4] = self.K_unaugmented
- self.K[0, 4] = 1;
- self.K[1, 4] = 1;
- print 'Kal', self.KalmanGain
- self.L = self.A * self.KalmanGain
-
- self.InitializeState()
-
-
-def CapU(U):
- if U[0, 0] - U[1, 0] > 24:
- return numpy.matrix([[12], [-12]])
- elif U[0, 0] - U[1, 0] < -24:
- return numpy.matrix([[-12], [12]])
- else:
- max_u = max(U[0, 0], U[1, 0])
- min_u = min(U[0, 0], U[1, 0])
- if max_u > 12:
- return U - (max_u - 12)
- if min_u < -12:
- return U - (min_u + 12)
- return U
-
-
-def run_test(arm, initial_X, goal, max_separation_error=0.01,
- show_graph=True, iterations=200, controller_arm=None,
- observer_arm=None):
- """Runs the arm plant with an initial condition and goal.
-
- The tests themselves are not terribly sophisticated; I just test for
- whether the goal has been reached and whether the separation goes
- outside of the initial and goal values by more than max_separation_error.
- Prints out something for a failure of either condition and returns
- False if tests fail.
- Args:
- arm: arm object to use.
- initial_X: starting state.
- goal: goal state.
- show_graph: Whether or not to display a graph showing the changing
- states and voltages.
- iterations: Number of timesteps to run the model for.
- controller_arm: arm object to get K from, or None if we should
- use arm.
- observer_arm: arm object to use for the observer, or None if we should
- use the actual state.
- """
-
- arm.X = initial_X
-
- if controller_arm is None:
- controller_arm = arm
-
- if observer_arm is not None:
- observer_arm.X_hat = initial_X + 0.01
- observer_arm.X_hat = initial_X
-
- # Various lists for graphing things.
- t = []
- x_avg = []
- x_sep = []
- x_hat_avg = []
- x_hat_sep = []
- v_avg = []
- v_sep = []
- u_left = []
- u_right = []
-
- sep_plot_gain = 100.0
-
- for i in xrange(iterations):
- X_hat = arm.X
- if observer_arm is not None:
- X_hat = observer_arm.X_hat
- x_hat_avg.append(observer_arm.X_hat[0, 0])
- x_hat_sep.append(observer_arm.X_hat[2, 0] * sep_plot_gain)
- U = controller_arm.K * (goal - X_hat)
- U = CapU(U)
- x_avg.append(arm.X[0, 0])
- v_avg.append(arm.X[1, 0])
- x_sep.append(arm.X[2, 0] * sep_plot_gain)
- v_sep.append(arm.X[3, 0])
- if observer_arm is not None:
- observer_arm.PredictObserver(U)
- arm.Update(U)
- if observer_arm is not None:
- observer_arm.Y = arm.Y
- observer_arm.CorrectObserver(U)
-
- t.append(i * arm.dt)
- u_left.append(U[0, 0])
- u_right.append(U[1, 0])
-
- print numpy.linalg.inv(arm.A)
- print "delta time is ", arm.dt
- print "Velocity at t=0 is ", x_avg[0], v_avg[0], x_sep[0], v_sep[0]
- print "Velocity at t=1+dt is ", x_avg[1], v_avg[1], x_sep[1], v_sep[1]
-
- if show_graph:
- pylab.subplot(2, 1, 1)
- pylab.plot(t, x_avg, label='x avg')
- pylab.plot(t, x_sep, label='x sep')
- if observer_arm is not None:
- pylab.plot(t, x_hat_avg, label='x_hat avg')
- pylab.plot(t, x_hat_sep, label='x_hat sep')
- pylab.legend()
-
- pylab.subplot(2, 1, 2)
- pylab.plot(t, u_left, label='u left')
- pylab.plot(t, u_right, label='u right')
- pylab.legend()
- pylab.show()
-
-
-def run_integral_test(arm, initial_X, goal, observer_arm, disturbance,
- max_separation_error=0.01, show_graph=True,
- iterations=400):
- """Runs the integral control arm plant with an initial condition and goal.
-
- The tests themselves are not terribly sophisticated; I just test for
- whether the goal has been reached and whether the separation goes
- outside of the initial and goal values by more than max_separation_error.
- Prints out something for a failure of either condition and returns
- False if tests fail.
- Args:
- arm: arm object to use.
- initial_X: starting state.
- goal: goal state.
- observer_arm: arm object to use for the observer.
- show_graph: Whether or not to display a graph showing the changing
- states and voltages.
- iterations: Number of timesteps to run the model for.
- disturbance: Voltage missmatch between controller and model.
- """
-
- arm.X = initial_X
-
- # Various lists for graphing things.
- t = []
- x_avg = []
- x_sep = []
- x_hat_avg = []
- x_hat_sep = []
- v_avg = []
- v_sep = []
- u_left = []
- u_right = []
- u_error = []
-
- sep_plot_gain = 100.0
-
- unaugmented_goal = goal
- goal = numpy.matrix(numpy.zeros((5, 1)))
- goal[0:4, 0] = unaugmented_goal
-
- for i in xrange(iterations):
- X_hat = observer_arm.X_hat[0:4]
-
- x_hat_avg.append(observer_arm.X_hat[0, 0])
- x_hat_sep.append(observer_arm.X_hat[2, 0] * sep_plot_gain)
-
- U = observer_arm.K * (goal - observer_arm.X_hat)
- u_error.append(observer_arm.X_hat[4,0])
- U = CapU(U)
- x_avg.append(arm.X[0, 0])
- v_avg.append(arm.X[1, 0])
- x_sep.append(arm.X[2, 0] * sep_plot_gain)
- v_sep.append(arm.X[3, 0])
-
- observer_arm.PredictObserver(U)
-
- arm.Update(U + disturbance)
- observer_arm.Y = arm.Y
- observer_arm.CorrectObserver(U)
-
- t.append(i * arm.dt)
- u_left.append(U[0, 0])
- u_right.append(U[1, 0])
-
- print 'End is', observer_arm.X_hat[4, 0]
-
- if show_graph:
- pylab.subplot(2, 1, 1)
- pylab.plot(t, x_avg, label='x avg')
- pylab.plot(t, x_sep, label='x sep')
- if observer_arm is not None:
- pylab.plot(t, x_hat_avg, label='x_hat avg')
- pylab.plot(t, x_hat_sep, label='x_hat sep')
- pylab.legend()
-
- pylab.subplot(2, 1, 2)
- pylab.plot(t, u_left, label='u left')
- pylab.plot(t, u_right, label='u right')
- pylab.plot(t, u_error, label='u error')
- pylab.legend()
- pylab.show()
-
-
-def main(argv):
- loaded_mass = 25
- #loaded_mass = 0
- arm = Arm(mass=13 + loaded_mass)
- #arm_controller = Arm(mass=13 + 15)
- #observer_arm = Arm(mass=13 + 15)
- #observer_arm = None
-
- integral_arm = IntegralArm(mass=13 + loaded_mass)
- integral_arm.X_hat[0, 0] += 0.02
- integral_arm.X_hat[2, 0] += 0.02
- integral_arm.X_hat[4] = 0
-
- # Test moving the arm with constant separation.
- initial_X = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
- R = numpy.matrix([[0.0], [0.0], [0.0], [0.0]])
- run_integral_test(arm, initial_X, R, integral_arm, disturbance=2)
-
- # Write the generated constants out to a file.
- if len(argv) != 5:
- print "Expected .h file name and .cc file name for the arm and augmented arm."
- else:
- arm = Arm("Arm", mass=13)
- loop_writer = control_loop.ControlLoopWriter("Arm", [arm])
- if argv[1][-3:] == '.cc':
- loop_writer.Write(argv[2], argv[1])
- else:
- loop_writer.Write(argv[1], argv[2])
-
- integral_arm = IntegralArm("IntegralArm", mass=13)
- loop_writer = control_loop.ControlLoopWriter("IntegralArm", [integral_arm])
- if argv[3][-3:] == '.cc':
- loop_writer.Write(argv[4], argv[3])
- else:
- loop_writer.Write(argv[3], argv[4])
-
-if __name__ == '__main__':
- sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/claw.py b/frc971/control_loops/python/claw.py
deleted file mode 100755
index 4ca50e9..0000000
--- a/frc971/control_loops/python/claw.py
+++ /dev/null
@@ -1,211 +0,0 @@
-#!/usr/bin/python
-
-import control_loop
-import controls
-import polytope
-import polydrivetrain
-import numpy
-import sys
-import matplotlib
-from matplotlib import pylab
-
-class Claw(control_loop.ControlLoop):
- def __init__(self, name="Claw", mass=None):
- super(Claw, self).__init__(name)
- # Stall Torque in N m
- self.stall_torque = 0.476
- # Stall Current in Amps
- self.stall_current = 80.730
- # Free Speed in RPM
- self.free_speed = 13906.0
- # Free Current in Amps
- self.free_current = 5.820
- # Mass of the claw
- if mass is None:
- self.mass = 5.0
- else:
- self.mass = mass
-
- # Resistance of the motor
- self.R = 12.0 / self.stall_current
- # Motor velocity constant
- self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
- # Torque constant
- self.Kt = self.stall_torque / self.stall_current
- # Gear ratio
- self.G = (56.0 / 12.0) * (54.0 / 14.0) * (64.0 / 14.0) * (72.0 / 18.0)
- # Claw length
- self.r = 18 * 0.0254
-
- self.J = self.r * self.mass
-
- # Control loop time step
- self.dt = 0.005
-
- # State is [position, velocity]
- # Input is [Voltage]
-
- C1 = self.G * self.G * self.Kt / (self.R * self.J * self.Kv)
- C2 = self.Kt * self.G / (self.J * self.R)
-
- self.A_continuous = numpy.matrix(
- [[0, 1],
- [0, -C1]])
-
- # Start with the unmodified input
- self.B_continuous = numpy.matrix(
- [[0],
- [C2]])
-
- self.C = numpy.matrix([[1, 0]])
- self.D = numpy.matrix([[0]])
-
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
-
- controlability = controls.ctrb(self.A, self.B);
-
- print "Free speed is", self.free_speed * numpy.pi * 2.0 / 60.0 / self.G
-
- q_pos = 0.15
- q_vel = 2.5
- self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0],
- [0.0, (1.0 / (q_vel ** 2.0))]])
-
- self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0))]])
- self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
-
- print 'K', self.K
- print 'Poles are', numpy.linalg.eig(self.A - self.B * self.K)[0]
-
- self.rpl = 0.30
- self.ipl = 0.10
- self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
- self.rpl - 1j * self.ipl])
-
- print 'L is', self.L
-
- q_pos = 0.05
- q_vel = 2.65
- self.Q = numpy.matrix([[(q_pos ** 2.0), 0.0],
- [0.0, (q_vel ** 2.0)]])
-
- r_volts = 0.025
- self.R = numpy.matrix([[(r_volts ** 2.0)]])
-
- self.KalmanGain, self.Q_steady = controls.kalman(
- A=self.A, B=self.B, C=self.C, Q=self.Q, R=self.R)
-
- print 'Kal', self.KalmanGain
- self.L = self.A * self.KalmanGain
- print 'KalL is', self.L
-
- # The box formed by U_min and U_max must encompass all possible values,
- # or else Austin's code gets angry.
- self.U_max = numpy.matrix([[12.0]])
- self.U_min = numpy.matrix([[-12.0]])
-
- self.InitializeState()
-
-
-def run_test(claw, initial_X, goal, max_separation_error=0.01,
- show_graph=True, iterations=200, controller_claw=None,
- observer_claw=None):
- """Runs the claw plant with an initial condition and goal.
-
- The tests themselves are not terribly sophisticated; I just test for
- whether the goal has been reached and whether the separation goes
- outside of the initial and goal values by more than max_separation_error.
- Prints out something for a failure of either condition and returns
- False if tests fail.
- Args:
- claw: claw object to use.
- initial_X: starting state.
- goal: goal state.
- show_graph: Whether or not to display a graph showing the changing
- states and voltages.
- iterations: Number of timesteps to run the model for.
- controller_claw: claw object to get K from, or None if we should
- use claw.
- observer_claw: claw object to use for the observer, or None if we should
- use the actual state.
- """
-
- claw.X = initial_X
-
- if controller_claw is None:
- controller_claw = claw
-
- if observer_claw is not None:
- observer_claw.X_hat = initial_X + 0.01
- observer_claw.X_hat = initial_X
-
- # Various lists for graphing things.
- t = []
- x = []
- v = []
- x_hat = []
- u = []
-
- sep_plot_gain = 100.0
-
- for i in xrange(iterations):
- X_hat = claw.X
- if observer_claw is not None:
- X_hat = observer_claw.X_hat
- x_hat.append(observer_claw.X_hat[0, 0])
- U = controller_claw.K * (goal - X_hat)
- U[0, 0] = numpy.clip(U[0, 0], -12, 12)
- x.append(claw.X[0, 0])
- v.append(claw.X[1, 0])
- if observer_claw is not None:
- observer_claw.PredictObserver(U)
- claw.Update(U)
- if observer_claw is not None:
- observer_claw.Y = claw.Y
- observer_claw.CorrectObserver(U)
-
- t.append(i * claw.dt)
- u.append(U[0, 0])
-
- if show_graph:
- pylab.subplot(2, 1, 1)
- pylab.plot(t, x, label='x')
- if observer_claw is not None:
- pylab.plot(t, x_hat, label='x_hat')
- pylab.legend()
-
- pylab.subplot(2, 1, 2)
- pylab.plot(t, u, label='u')
- pylab.legend()
- pylab.show()
-
-
-def main(argv):
- loaded_mass = 0
- #loaded_mass = 0
- claw = Claw(mass=4 + loaded_mass)
- claw_controller = Claw(mass=5 + 0)
- observer_claw = Claw(mass=5 + 0)
- #observer_claw = None
-
- # Test moving the claw with constant separation.
- initial_X = numpy.matrix([[0.0], [0.0]])
- R = numpy.matrix([[1.0], [0.0]])
- run_test(claw, initial_X, R, controller_claw=claw_controller,
- observer_claw=observer_claw)
-
- # Write the generated constants out to a file.
- if len(argv) != 3:
- print "Expected .h file name and .cc file name for the claw."
- else:
- claw = Claw("Claw")
- loop_writer = control_loop.ControlLoopWriter("Claw", [claw])
- if argv[1][-3:] == '.cc':
- loop_writer.Write(argv[2], argv[1])
- else:
- loop_writer.Write(argv[1], argv[2])
-
-if __name__ == '__main__':
- sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/drivetrain.py b/frc971/control_loops/python/drivetrain.py
deleted file mode 100755
index 8ed62d6..0000000
--- a/frc971/control_loops/python/drivetrain.py
+++ /dev/null
@@ -1,242 +0,0 @@
-#!/usr/bin/python
-
-import control_loop
-import controls
-import numpy
-import sys
-from matplotlib import pylab
-
-
-class CIM(control_loop.ControlLoop):
- def __init__(self):
- super(CIM, self).__init__("CIM")
- # Stall Torque in N m
- self.stall_torque = 2.42
- # Stall Current in Amps
- self.stall_current = 133
- # Free Speed in RPM
- self.free_speed = 4650.0
- # Free Current in Amps
- self.free_current = 2.7
- # Moment of inertia of the CIM in kg m^2
- self.J = 0.0001
- # Resistance of the motor, divided by 2 to account for the 2 motors
- self.R = 12.0 / self.stall_current
- # Motor velocity constant
- self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
- # Torque constant
- self.Kt = self.stall_torque / self.stall_current
- # Control loop time step
- self.dt = 0.005
-
- # State feedback matrices
- self.A_continuous = numpy.matrix(
- [[-self.Kt / self.Kv / (self.J * self.R)]])
- self.B_continuous = numpy.matrix(
- [[self.Kt / (self.J * self.R)]])
- self.C = numpy.matrix([[1]])
- self.D = numpy.matrix([[0]])
-
- self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
- self.B_continuous, self.dt)
-
- self.PlaceControllerPoles([0.01])
- self.PlaceObserverPoles([0.01])
-
- self.U_max = numpy.matrix([[12.0]])
- self.U_min = numpy.matrix([[-12.0]])
-
- self.InitializeState()
-
-
-class Drivetrain(control_loop.ControlLoop):
- def __init__(self, name="Drivetrain", left_low=True, right_low=True):
- super(Drivetrain, self).__init__(name)
- # Stall Torque in N m
- self.stall_torque = 2.42
- # Stall Current in Amps
- self.stall_current = 133.0
- # Free Speed in RPM. Used number from last year.
- self.free_speed = 4650.0
- # Free Current in Amps
- self.free_current = 2.7
- # Moment of inertia of the drivetrain in kg m^2
- # Just borrowed from last year.
- self.J = 10
- # Mass of the robot, in kg.
- self.m = 68
- # Radius of the robot, in meters (from last year).
- self.rb = 0.9603 / 2.0
- # Radius of the wheels, in meters.
- self.r = .0515938
- # Resistance of the motor, divided by the number of motors.
- self.R = 12.0 / self.stall_current / 2
- # Motor velocity constant
- self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
- # Torque constant
- self.Kt = self.stall_torque / self.stall_current
- # Gear ratios
- self.G_const = 28.0 / 50.0 * 20.0 / 64.0
-
- self.G_low = self.G_const
- self.G_high = self.G_const
-
- if left_low:
- self.Gl = self.G_low
- else:
- self.Gl = self.G_high
- if right_low:
- self.Gr = self.G_low
- else:
- self.Gr = self.G_high
-
- # Control loop time step
- self.dt = 0.005
-
- # These describe the way that a given side of a robot will be influenced
- # by the other side. Units of 1 / kg.
- self.msp = 1.0 / self.m + self.rb * self.rb / self.J
- self.msn = 1.0 / self.m - self.rb * self.rb / self.J
- # The calculations which we will need for A and B.
- self.tcl = -self.Kt / self.Kv / (self.Gl * self.Gl * self.R * self.r * self.r)
- self.tcr = -self.Kt / self.Kv / (self.Gr * self.Gr * self.R * self.r * self.r)
- self.mpl = self.Kt / (self.Gl * self.R * self.r)
- self.mpr = self.Kt / (self.Gr * self.R * self.r)
-
- # State feedback matrices
- # X will be of the format
- # [[positionl], [velocityl], [positionr], velocityr]]
- self.A_continuous = numpy.matrix(
- [[0, 1, 0, 0],
- [0, self.msp * self.tcl, 0, self.msn * self.tcr],
- [0, 0, 0, 1],
- [0, self.msn * self.tcl, 0, self.msp * self.tcr]])
- self.B_continuous = numpy.matrix(
- [[0, 0],
- [self.msp * self.mpl, self.msn * self.mpr],
- [0, 0],
- [self.msn * self.mpl, self.msp * self.mpr]])
- self.C = numpy.matrix([[1, 0, 0, 0],
- [0, 0, 1, 0]])
- self.D = numpy.matrix([[0, 0],
- [0, 0]])
-
- #print "THE NUMBER I WANT" + str(numpy.linalg.inv(self.A_continuous) * -self.B_continuous * numpy.matrix([[12.0], [12.0]]))
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
-
- # Poles from last year.
- self.hp = 0.65
- self.lp = 0.83
- self.PlaceControllerPoles([self.hp, self.lp, self.hp, self.lp])
- print self.K
- q_pos = 0.07
- q_vel = 1.0
- self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
- [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
- [0.0, 0.0, (1.0 / (q_pos ** 2.0)), 0.0],
- [0.0, 0.0, 0.0, (1.0 / (q_vel ** 2.0))]])
-
- self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
- [0.0, (1.0 / (12.0 ** 2.0))]])
- self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
- print self.A
- print self.B
- print self.K
- print numpy.linalg.eig(self.A - self.B * self.K)[0]
-
- self.hlp = 0.3
- self.llp = 0.4
- self.PlaceObserverPoles([self.hlp, self.hlp, self.llp, self.llp])
-
- self.U_max = numpy.matrix([[12.0], [12.0]])
- self.U_min = numpy.matrix([[-12.0], [-12.0]])
- self.InitializeState()
-
-def main(argv):
- # Simulate the response of the system to a step input.
- drivetrain = Drivetrain()
- simulated_left = []
- simulated_right = []
- for _ in xrange(100):
- drivetrain.Update(numpy.matrix([[12.0], [12.0]]))
- simulated_left.append(drivetrain.X[0, 0])
- simulated_right.append(drivetrain.X[2, 0])
-
- #pylab.plot(range(100), simulated_left)
- #pylab.plot(range(100), simulated_right)
- #pylab.show()
-
- # Simulate forwards motion.
- drivetrain = Drivetrain()
- close_loop_left = []
- close_loop_right = []
- R = numpy.matrix([[1.0], [0.0], [1.0], [0.0]])
- for _ in xrange(100):
- U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
- drivetrain.U_min, drivetrain.U_max)
- drivetrain.UpdateObserver(U)
- drivetrain.Update(U)
- close_loop_left.append(drivetrain.X[0, 0])
- close_loop_right.append(drivetrain.X[2, 0])
-
- #pylab.plot(range(100), close_loop_left)
- #pylab.plot(range(100), close_loop_right)
- #pylab.show()
-
- # Try turning in place
- drivetrain = Drivetrain()
- close_loop_left = []
- close_loop_right = []
- R = numpy.matrix([[-1.0], [0.0], [1.0], [0.0]])
- for _ in xrange(100):
- U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
- drivetrain.U_min, drivetrain.U_max)
- drivetrain.UpdateObserver(U)
- drivetrain.Update(U)
- close_loop_left.append(drivetrain.X[0, 0])
- close_loop_right.append(drivetrain.X[2, 0])
-
- #pylab.plot(range(100), close_loop_left)
- #pylab.plot(range(100), close_loop_right)
- #pylab.show()
-
- # Try turning just one side.
- drivetrain = Drivetrain()
- close_loop_left = []
- close_loop_right = []
- R = numpy.matrix([[0.0], [0.0], [1.0], [0.0]])
- for _ in xrange(100):
- U = numpy.clip(drivetrain.K * (R - drivetrain.X_hat),
- drivetrain.U_min, drivetrain.U_max)
- drivetrain.UpdateObserver(U)
- drivetrain.Update(U)
- close_loop_left.append(drivetrain.X[0, 0])
- close_loop_right.append(drivetrain.X[2, 0])
-
- #pylab.plot(range(100), close_loop_left)
- #pylab.plot(range(100), close_loop_right)
- #pylab.show()
-
- # Write the generated constants out to a file.
- print "Output one"
- drivetrain_low_low = Drivetrain(name="DrivetrainLowLow", left_low=True, right_low=True)
- drivetrain_low_high = Drivetrain(name="DrivetrainLowHigh", left_low=True, right_low=False)
- drivetrain_high_low = Drivetrain(name="DrivetrainHighLow", left_low=False, right_low=True)
- drivetrain_high_high = Drivetrain(name="DrivetrainHighHigh", left_low=False, right_low=False)
-
- if len(argv) != 5:
- print "Expected .h file name and .cc file name"
- else:
- dog_loop_writer = control_loop.ControlLoopWriter(
- "Drivetrain", [drivetrain_low_low, drivetrain_low_high,
- drivetrain_high_low, drivetrain_high_high])
- if argv[1][-3:] == '.cc':
- dog_loop_writer.Write(argv[2], argv[1])
- else:
- dog_loop_writer.Write(argv[1], argv[2])
-
-if __name__ == '__main__':
- sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/elevator.py b/frc971/control_loops/python/elevator.py
deleted file mode 100755
index fba72c8..0000000
--- a/frc971/control_loops/python/elevator.py
+++ /dev/null
@@ -1,246 +0,0 @@
-#!/usr/bin/python
-
-import control_loop
-import controls
-import polytope
-import polydrivetrain
-import numpy
-import sys
-import matplotlib
-from matplotlib import pylab
-
-class Elevator(control_loop.ControlLoop):
- def __init__(self, name="Elevator", mass=None):
- super(Elevator, self).__init__(name)
- # Stall Torque in N m
- self.stall_torque = 0.476
- # Stall Current in Amps
- self.stall_current = 80.730
- # Free Speed in RPM
- self.free_speed = 13906.0
- # Free Current in Amps
- self.free_current = 5.820
- # Mass of the elevator
- if mass is None:
- self.mass = 13.0
- else:
- self.mass = mass
-
- # Resistance of the motor
- self.R = 12.0 / self.stall_current
- # Motor velocity constant
- self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
- # Torque constant
- self.Kt = self.stall_torque / self.stall_current
- # Gear ratio
- self.G = (56.0 / 12.0) * (84.0 / 14.0)
- # Pulley diameter
- self.r = 32 * 0.005 / numpy.pi / 2.0
- # Control loop time step
- self.dt = 0.005
-
- # Elevator left/right spring constant (N/m)
- self.spring = 800.0
-
- # State is [average position, average velocity,
- # position difference/2, velocity difference/2]
- # Input is [V_left, V_right]
-
- C1 = self.spring / (self.mass * 0.5)
- C2 = self.Kt * self.G / (self.mass * 0.5 * self.r * self.R)
- C3 = self.G * self.G * self.Kt / (
- self.R * self.r * self.r * self.mass * 0.5 * self.Kv)
-
- self.A_continuous = numpy.matrix(
- [[0, 1, 0, 0],
- [0, -C3, 0, 0],
- [0, 0, 0, 1],
- [0, 0, -C1 * 2.0, -C3]])
-
- print "Full speed is", C2 / C3 * 12.0
-
- # Start with the unmodified input
- self.B_continuous = numpy.matrix(
- [[0, 0],
- [C2 / 2.0, C2 / 2.0],
- [0, 0],
- [C2 / 2.0, -C2 / 2.0]])
-
- self.C = numpy.matrix([[1, 0, 1, 0],
- [1, 0, -1, 0]])
- self.D = numpy.matrix([[0, 0],
- [0, 0]])
-
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
-
- print self.A
-
- controlability = controls.ctrb(self.A, self.B);
- print "Rank of augmented controlability matrix.", numpy.linalg.matrix_rank(
- controlability)
-
- q_pos = 0.02
- q_vel = 0.400
- q_pos_diff = 0.01
- q_vel_diff = 0.45
- self.Q = numpy.matrix([[(1.0 / (q_pos ** 2.0)), 0.0, 0.0, 0.0],
- [0.0, (1.0 / (q_vel ** 2.0)), 0.0, 0.0],
- [0.0, 0.0, (1.0 / (q_pos_diff ** 2.0)), 0.0],
- [0.0, 0.0, 0.0, (1.0 / (q_vel_diff ** 2.0))]])
-
- self.R = numpy.matrix([[(1.0 / (12.0 ** 2.0)), 0.0],
- [0.0, 1.0 / (12.0 ** 2.0)]])
- self.K = controls.dlqr(self.A, self.B, self.Q, self.R)
- print self.K
-
- print numpy.linalg.eig(self.A - self.B * self.K)[0]
-
- self.rpl = 0.20
- self.ipl = 0.05
- self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
- self.rpl + 1j * self.ipl,
- self.rpl - 1j * self.ipl,
- self.rpl - 1j * self.ipl])
-
- # The box formed by U_min and U_max must encompass all possible values,
- # or else Austin's code gets angry.
- self.U_max = numpy.matrix([[12.0], [12.0]])
- self.U_min = numpy.matrix([[-12.0], [-12.0]])
-
- self.InitializeState()
-
-
-def CapU(U):
- if U[0, 0] - U[1, 0] > 24:
- return numpy.matrix([[12], [-12]])
- elif U[0, 0] - U[1, 0] < -24:
- return numpy.matrix([[-12], [12]])
- else:
- max_u = max(U[0, 0], U[1, 0])
- min_u = min(U[0, 0], U[1, 0])
- if max_u > 12:
- return U - (max_u - 12)
- if min_u < -12:
- return U - (min_u + 12)
- return U
-
-
-def run_test(elevator, initial_X, goal, max_separation_error=0.01,
- show_graph=True, iterations=200, controller_elevator=None,
- observer_elevator=None):
- """Runs the elevator plant with an initial condition and goal.
-
- The tests themselves are not terribly sophisticated; I just test for
- whether the goal has been reached and whether the separation goes
- outside of the initial and goal values by more than max_separation_error.
- Prints out something for a failure of either condition and returns
- False if tests fail.
- Args:
- elevator: elevator object to use.
- initial_X: starting state.
- goal: goal state.
- show_graph: Whether or not to display a graph showing the changing
- states and voltages.
- iterations: Number of timesteps to run the model for.
- controller_elevator: elevator object to get K from, or None if we should
- use elevator.
- observer_elevator: elevator object to use for the observer, or None if we
- should use the actual state.
- """
-
- elevator.X = initial_X
-
- if controller_elevator is None:
- controller_elevator = elevator
-
- if observer_elevator is not None:
- observer_elevator.X_hat = initial_X + 0.01
- observer_elevator.X_hat = initial_X
-
- # Various lists for graphing things.
- t = []
- x_avg = []
- x_sep = []
- x_hat_avg = []
- x_hat_sep = []
- v_avg = []
- v_sep = []
- u_left = []
- u_right = []
-
- sep_plot_gain = 100.0
-
- for i in xrange(iterations):
- X_hat = elevator.X
- if observer_elevator is not None:
- X_hat = observer_elevator.X_hat
- x_hat_avg.append(observer_elevator.X_hat[0, 0])
- x_hat_sep.append(observer_elevator.X_hat[2, 0] * sep_plot_gain)
- U = controller_elevator.K * (goal - X_hat)
- U = CapU(U)
- x_avg.append(elevator.X[0, 0])
- v_avg.append(elevator.X[1, 0])
- x_sep.append(elevator.X[2, 0] * sep_plot_gain)
- v_sep.append(elevator.X[3, 0])
- if observer_elevator is not None:
- observer_elevator.PredictObserver(U)
- elevator.Update(U)
- if observer_elevator is not None:
- observer_elevator.Y = elevator.Y
- observer_elevator.CorrectObserver(U)
-
- t.append(i * elevator.dt)
- u_left.append(U[0, 0])
- u_right.append(U[1, 0])
-
- print numpy.linalg.inv(elevator.A)
- print "delta time is ", elevator.dt
- print "Velocity at t=0 is ", x_avg[0], v_avg[0], x_sep[0], v_sep[0]
- print "Velocity at t=1+dt is ", x_avg[1], v_avg[1], x_sep[1], v_sep[1]
-
- if show_graph:
- pylab.subplot(2, 1, 1)
- pylab.plot(t, x_avg, label='x avg')
- pylab.plot(t, x_sep, label='x sep')
- if observer_elevator is not None:
- pylab.plot(t, x_hat_avg, label='x_hat avg')
- pylab.plot(t, x_hat_sep, label='x_hat sep')
- pylab.legend()
-
- pylab.subplot(2, 1, 2)
- pylab.plot(t, u_left, label='u left')
- pylab.plot(t, u_right, label='u right')
- pylab.legend()
- pylab.show()
-
-
-def main(argv):
- loaded_mass = 25
- #loaded_mass = 0
- elevator = Elevator(mass=13 + loaded_mass)
- elevator_controller = Elevator(mass=13 + 15)
- observer_elevator = Elevator(mass=13 + 15)
- #observer_elevator = None
-
- # Test moving the elevator with constant separation.
- initial_X = numpy.matrix([[0.0], [0.0], [0.01], [0.0]])
- #initial_X = numpy.matrix([[0.0], [0.0], [0.00], [0.0]])
- R = numpy.matrix([[1.0], [0.0], [0.0], [0.0]])
- run_test(elevator, initial_X, R, controller_elevator=elevator_controller,
- observer_elevator=observer_elevator)
-
- # Write the generated constants out to a file.
- if len(argv) != 3:
- print "Expected .h file name and .cc file name for the elevator."
- else:
- elevator = Elevator("Elevator")
- loop_writer = control_loop.ControlLoopWriter("Elevator", [elevator])
- if argv[1][-3:] == '.cc':
- loop_writer.Write(argv[2], argv[1])
- else:
- loop_writer.Write(argv[1], argv[2])
-
-if __name__ == '__main__':
- sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/polydrivetrain.py b/frc971/control_loops/python/polydrivetrain.py
deleted file mode 100755
index a62c8c8..0000000
--- a/frc971/control_loops/python/polydrivetrain.py
+++ /dev/null
@@ -1,504 +0,0 @@
-#!/usr/bin/python
-
-import numpy
-import sys
-import polytope
-import drivetrain
-import control_loop
-import controls
-from matplotlib import pylab
-
-__author__ = 'Austin Schuh (austin.linux@gmail.com)'
-
-
-def CoerceGoal(region, K, w, R):
- """Intersects a line with a region, and finds the closest point to R.
-
- Finds a point that is closest to R inside the region, and on the line
- defined by K X = w. If it is not possible to find a point on the line,
- finds a point that is inside the region and closest to the line. This
- function assumes that
-
- Args:
- region: HPolytope, the valid goal region.
- K: numpy.matrix (2 x 1), the matrix for the equation [K1, K2] [x1; x2] = w
- w: float, the offset in the equation above.
- R: numpy.matrix (2 x 1), the point to be closest to.
-
- Returns:
- numpy.matrix (2 x 1), the point.
- """
- return DoCoerceGoal(region, K, w, R)[0]
-
-def DoCoerceGoal(region, K, w, R):
- if region.IsInside(R):
- return (R, True)
-
- perpendicular_vector = K.T / numpy.linalg.norm(K)
- parallel_vector = numpy.matrix([[perpendicular_vector[1, 0]],
- [-perpendicular_vector[0, 0]]])
-
- # We want to impose the constraint K * X = w on the polytope H * X <= k.
- # We do this by breaking X up into parallel and perpendicular components to
- # the half plane. This gives us the following equation.
- #
- # parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) = X
- #
- # Then, substitute this into the polytope.
- #
- # H * (parallel * (parallel.T \dot X) + perpendicular * (perpendicular \dot X)) <= k
- #
- # Substitute K * X = w
- #
- # H * parallel * (parallel.T \dot X) + H * perpendicular * w <= k
- #
- # Move all the knowns to the right side.
- #
- # H * parallel * ([parallel1 parallel2] * X) <= k - H * perpendicular * w
- #
- # Let t = parallel.T \dot X, the component parallel to the surface.
- #
- # H * parallel * t <= k - H * perpendicular * w
- #
- # This is a polytope which we can solve, and use to figure out the range of X
- # that we care about!
-
- t_poly = polytope.HPolytope(
- region.H * parallel_vector,
- region.k - region.H * perpendicular_vector * w)
-
- vertices = t_poly.Vertices()
-
- if vertices.shape[0]:
- # The region exists!
- # Find the closest vertex
- min_distance = numpy.infty
- closest_point = None
- for vertex in vertices:
- point = parallel_vector * vertex + perpendicular_vector * w
- length = numpy.linalg.norm(R - point)
- if length < min_distance:
- min_distance = length
- closest_point = point
-
- return (closest_point, True)
- else:
- # Find the vertex of the space that is closest to the line.
- region_vertices = region.Vertices()
- min_distance = numpy.infty
- closest_point = None
- for vertex in region_vertices:
- point = vertex.T
- length = numpy.abs((perpendicular_vector.T * point)[0, 0])
- if length < min_distance:
- min_distance = length
- closest_point = point
-
- return (closest_point, False)
-
-
-class VelocityDrivetrainModel(control_loop.ControlLoop):
- def __init__(self, left_low=True, right_low=True, name="VelocityDrivetrainModel"):
- super(VelocityDrivetrainModel, self).__init__(name)
- self._drivetrain = drivetrain.Drivetrain(left_low=left_low,
- right_low=right_low)
- self.dt = 0.01
- self.A_continuous = numpy.matrix(
- [[self._drivetrain.A_continuous[1, 1], self._drivetrain.A_continuous[1, 3]],
- [self._drivetrain.A_continuous[3, 1], self._drivetrain.A_continuous[3, 3]]])
-
- self.B_continuous = numpy.matrix(
- [[self._drivetrain.B_continuous[1, 0], self._drivetrain.B_continuous[1, 1]],
- [self._drivetrain.B_continuous[3, 0], self._drivetrain.B_continuous[3, 1]]])
- self.C = numpy.matrix(numpy.eye(2));
- self.D = numpy.matrix(numpy.zeros((2, 2)));
-
- self.A, self.B = self.ContinuousToDiscrete(self.A_continuous,
- self.B_continuous, self.dt)
-
- # FF * X = U (steady state)
- self.FF = self.B.I * (numpy.eye(2) - self.A)
-
- self.PlaceControllerPoles([0.6, 0.6])
- self.PlaceObserverPoles([0.02, 0.02])
-
- self.G_high = self._drivetrain.G_high
- self.G_low = self._drivetrain.G_low
- self.R = self._drivetrain.R
- self.r = self._drivetrain.r
- self.Kv = self._drivetrain.Kv
- self.Kt = self._drivetrain.Kt
-
- self.U_max = self._drivetrain.U_max
- self.U_min = self._drivetrain.U_min
-
-
-class VelocityDrivetrain(object):
- HIGH = 'high'
- LOW = 'low'
- SHIFTING_UP = 'up'
- SHIFTING_DOWN = 'down'
-
- def __init__(self):
- self.drivetrain_low_low = VelocityDrivetrainModel(
- left_low=True, right_low=True, name='VelocityDrivetrainLowLow')
- self.drivetrain_low_high = VelocityDrivetrainModel(left_low=True, right_low=False, name='VelocityDrivetrainLowHigh')
- self.drivetrain_high_low = VelocityDrivetrainModel(left_low=False, right_low=True, name = 'VelocityDrivetrainHighLow')
- self.drivetrain_high_high = VelocityDrivetrainModel(left_low=False, right_low=False, name = 'VelocityDrivetrainHighHigh')
-
- # X is [lvel, rvel]
- self.X = numpy.matrix(
- [[0.0],
- [0.0]])
-
- self.U_poly = polytope.HPolytope(
- numpy.matrix([[1, 0],
- [-1, 0],
- [0, 1],
- [0, -1]]),
- numpy.matrix([[12],
- [12],
- [12],
- [12]]))
-
- self.U_max = numpy.matrix(
- [[12.0],
- [12.0]])
- self.U_min = numpy.matrix(
- [[-12.0000000000],
- [-12.0000000000]])
-
- self.dt = 0.01
-
- self.R = numpy.matrix(
- [[0.0],
- [0.0]])
-
- # ttrust is the comprimise between having full throttle negative inertia,
- # and having no throttle negative inertia. A value of 0 is full throttle
- # inertia. A value of 1 is no throttle negative inertia.
- self.ttrust = 1.1
-
- self.left_gear = VelocityDrivetrain.LOW
- self.right_gear = VelocityDrivetrain.LOW
- self.left_shifter_position = 0.0
- self.right_shifter_position = 0.0
- self.left_cim = drivetrain.CIM()
- self.right_cim = drivetrain.CIM()
-
- def IsInGear(self, gear):
- return gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.LOW
-
- def MotorRPM(self, shifter_position, velocity):
- if shifter_position > 0.5:
- return (velocity / self.CurrentDrivetrain().G_high /
- self.CurrentDrivetrain().r)
- else:
- return (velocity / self.CurrentDrivetrain().G_low /
- self.CurrentDrivetrain().r)
-
- def CurrentDrivetrain(self):
- if self.left_shifter_position > 0.5:
- if self.right_shifter_position > 0.5:
- return self.drivetrain_high_high
- else:
- return self.drivetrain_high_low
- else:
- if self.right_shifter_position > 0.5:
- return self.drivetrain_low_high
- else:
- return self.drivetrain_low_low
-
- def SimShifter(self, gear, shifter_position):
- if gear is VelocityDrivetrain.HIGH or gear is VelocityDrivetrain.SHIFTING_UP:
- shifter_position = min(shifter_position + 0.5, 1.0)
- else:
- shifter_position = max(shifter_position - 0.5, 0.0)
-
- if shifter_position == 1.0:
- gear = VelocityDrivetrain.HIGH
- elif shifter_position == 0.0:
- gear = VelocityDrivetrain.LOW
-
- return gear, shifter_position
-
- def ComputeGear(self, wheel_velocity, should_print=False, current_gear=False, gear_name=None):
- high_omega = (wheel_velocity / self.CurrentDrivetrain().G_high /
- self.CurrentDrivetrain().r)
- low_omega = (wheel_velocity / self.CurrentDrivetrain().G_low /
- self.CurrentDrivetrain().r)
- #print gear_name, "Motor Energy Difference.", 0.5 * 0.000140032647 * (low_omega * low_omega - high_omega * high_omega), "joules"
- high_torque = ((12.0 - high_omega / self.CurrentDrivetrain().Kv) *
- self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
- low_torque = ((12.0 - low_omega / self.CurrentDrivetrain().Kv) *
- self.CurrentDrivetrain().Kt / self.CurrentDrivetrain().R)
- high_power = high_torque * high_omega
- low_power = low_torque * low_omega
- #if should_print:
- # print gear_name, "High omega", high_omega, "Low omega", low_omega
- # print gear_name, "High torque", high_torque, "Low torque", low_torque
- # print gear_name, "High power", high_power, "Low power", low_power
-
- # Shift algorithm improvements.
- # TODO(aschuh):
- # It takes time to shift. Shifting down for 1 cycle doesn't make sense
- # because you will end up slower than without shifting. Figure out how
- # to include that info.
- # If the driver is still in high gear, but isn't asking for the extra power
- # from low gear, don't shift until he asks for it.
- goal_gear_is_high = high_power > low_power
- #goal_gear_is_high = True
-
- if not self.IsInGear(current_gear):
- print gear_name, 'Not in gear.'
- return current_gear
- else:
- is_high = current_gear is VelocityDrivetrain.HIGH
- if is_high != goal_gear_is_high:
- if goal_gear_is_high:
- print gear_name, 'Shifting up.'
- return VelocityDrivetrain.SHIFTING_UP
- else:
- print gear_name, 'Shifting down.'
- return VelocityDrivetrain.SHIFTING_DOWN
- else:
- return current_gear
-
- def FilterVelocity(self, throttle):
- # Invert the plant to figure out how the velocity filter would have to work
- # out in order to filter out the forwards negative inertia.
- # This math assumes that the left and right power and velocity are equal.
-
- # The throttle filter should filter such that the motor in the highest gear
- # should be controlling the time constant.
- # Do this by finding the index of FF that has the lowest value, and computing
- # the sums using that index.
- FF_sum = self.CurrentDrivetrain().FF.sum(axis=1)
- min_FF_sum_index = numpy.argmin(FF_sum)
- min_FF_sum = FF_sum[min_FF_sum_index, 0]
- min_K_sum = self.CurrentDrivetrain().K[min_FF_sum_index, :].sum()
- # Compute the FF sum for high gear.
- high_min_FF_sum = self.drivetrain_high_high.FF[0, :].sum()
-
- # U = self.K[0, :].sum() * (R - x_avg) + self.FF[0, :].sum() * R
- # throttle * 12.0 = (self.K[0, :].sum() + self.FF[0, :].sum()) * R
- # - self.K[0, :].sum() * x_avg
-
- # R = (throttle * 12.0 + self.K[0, :].sum() * x_avg) /
- # (self.K[0, :].sum() + self.FF[0, :].sum())
-
- # U = (K + FF) * R - K * X
- # (K + FF) ^-1 * (U + K * X) = R
-
- # Scale throttle by min_FF_sum / high_min_FF_sum. This will make low gear
- # have the same velocity goal as high gear, and so that the robot will hold
- # the same speed for the same throttle for all gears.
- adjusted_ff_voltage = numpy.clip(throttle * 12.0 * min_FF_sum / high_min_FF_sum, -12.0, 12.0)
- return ((adjusted_ff_voltage + self.ttrust * min_K_sum * (self.X[0, 0] + self.X[1, 0]) / 2.0)
- / (self.ttrust * min_K_sum + min_FF_sum))
-
- def Update(self, throttle, steering):
- # Shift into the gear which sends the most power to the floor.
- # This is the same as sending the most torque down to the floor at the
- # wheel.
-
- self.left_gear = self.right_gear = True
- if False:
- self.left_gear = self.ComputeGear(self.X[0, 0], should_print=True,
- current_gear=self.left_gear,
- gear_name="left")
- self.right_gear = self.ComputeGear(self.X[1, 0], should_print=True,
- current_gear=self.right_gear,
- gear_name="right")
- if self.IsInGear(self.left_gear):
- self.left_cim.X[0, 0] = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
-
- if self.IsInGear(self.right_gear):
- self.right_cim.X[0, 0] = self.MotorRPM(self.right_shifter_position, self.X[0, 0])
-
- steering *= 2.3
- if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
- # Filter the throttle to provide a nicer response.
- fvel = self.FilterVelocity(throttle)
-
- # Constant radius means that angualar_velocity / linear_velocity = constant.
- # Compute the left and right velocities.
- steering_velocity = numpy.abs(fvel) * steering
- left_velocity = fvel - steering_velocity
- right_velocity = fvel + steering_velocity
-
- # Write this constraint in the form of K * R = w
- # angular velocity / linear velocity = constant
- # (left - right) / (left + right) = constant
- # left - right = constant * left + constant * right
-
- # (fvel - steering * numpy.abs(fvel) - fvel - steering * numpy.abs(fvel)) /
- # (fvel - steering * numpy.abs(fvel) + fvel + steering * numpy.abs(fvel)) =
- # constant
- # (- 2 * steering * numpy.abs(fvel)) / (2 * fvel) = constant
- # (-steering * sign(fvel)) = constant
- # (-steering * sign(fvel)) * (left + right) = left - right
- # (steering * sign(fvel) + 1) * left + (steering * sign(fvel) - 1) * right = 0
-
- equality_k = numpy.matrix(
- [[1 + steering * numpy.sign(fvel), -(1 - steering * numpy.sign(fvel))]])
- equality_w = 0.0
-
- self.R[0, 0] = left_velocity
- self.R[1, 0] = right_velocity
-
- # Construct a constraint on R by manipulating the constraint on U
- # Start out with H * U <= k
- # U = FF * R + K * (R - X)
- # H * (FF * R + K * R - K * X) <= k
- # H * (FF + K) * R <= k + H * K * X
- R_poly = polytope.HPolytope(
- self.U_poly.H * (self.CurrentDrivetrain().K + self.CurrentDrivetrain().FF),
- self.U_poly.k + self.U_poly.H * self.CurrentDrivetrain().K * self.X)
-
- # Limit R back inside the box.
- self.boxed_R = CoerceGoal(R_poly, equality_k, equality_w, self.R)
-
- FF_volts = self.CurrentDrivetrain().FF * self.boxed_R
- self.U_ideal = self.CurrentDrivetrain().K * (self.boxed_R - self.X) + FF_volts
- else:
- print 'Not all in gear'
- if not self.IsInGear(self.left_gear) and not self.IsInGear(self.right_gear):
- # TODO(austin): Use battery volts here.
- R_left = self.MotorRPM(self.left_shifter_position, self.X[0, 0])
- self.U_ideal[0, 0] = numpy.clip(
- self.left_cim.K * (R_left - self.left_cim.X) + R_left / self.left_cim.Kv,
- self.left_cim.U_min, self.left_cim.U_max)
- self.left_cim.Update(self.U_ideal[0, 0])
-
- R_right = self.MotorRPM(self.right_shifter_position, self.X[1, 0])
- self.U_ideal[1, 0] = numpy.clip(
- self.right_cim.K * (R_right - self.right_cim.X) + R_right / self.right_cim.Kv,
- self.right_cim.U_min, self.right_cim.U_max)
- self.right_cim.Update(self.U_ideal[1, 0])
- else:
- assert False
-
- self.U = numpy.clip(self.U_ideal, self.U_min, self.U_max)
-
- # TODO(austin): Model the robot as not accelerating when you shift...
- # This hack only works when you shift at the same time.
- if True or self.IsInGear(self.left_gear) and self.IsInGear(self.right_gear):
- self.X = self.CurrentDrivetrain().A * self.X + self.CurrentDrivetrain().B * self.U
-
- self.left_gear, self.left_shifter_position = self.SimShifter(
- self.left_gear, self.left_shifter_position)
- self.right_gear, self.right_shifter_position = self.SimShifter(
- self.right_gear, self.right_shifter_position)
-
- print "U is", self.U[0, 0], self.U[1, 0]
- print "Left shifter", self.left_gear, self.left_shifter_position, "Right shifter", self.right_gear, self.right_shifter_position
-
-
-def main(argv):
- vdrivetrain = VelocityDrivetrain()
-
- if len(argv) != 7:
- print "Expected .h file name and .cc file name"
- else:
- dog_loop_writer = control_loop.ControlLoopWriter(
- "VelocityDrivetrain", [vdrivetrain.drivetrain_low_low,
- vdrivetrain.drivetrain_low_high,
- vdrivetrain.drivetrain_high_low,
- vdrivetrain.drivetrain_high_high])
-
- if argv[1][-3:] == '.cc':
- dog_loop_writer.Write(argv[2], argv[1])
- else:
- dog_loop_writer.Write(argv[1], argv[2])
-
- cim_writer = control_loop.ControlLoopWriter(
- "CIM", [drivetrain.CIM()])
-
- if argv[5][-3:] == '.cc':
- cim_writer.Write(argv[6], argv[5])
- else:
- cim_writer.Write(argv[5], argv[6])
- return
-
- vl_plot = []
- vr_plot = []
- ul_plot = []
- ur_plot = []
- radius_plot = []
- t_plot = []
- left_gear_plot = []
- right_gear_plot = []
- vdrivetrain.left_shifter_position = 0.0
- vdrivetrain.right_shifter_position = 0.0
- vdrivetrain.left_gear = VelocityDrivetrain.LOW
- vdrivetrain.right_gear = VelocityDrivetrain.LOW
-
- print "K is", vdrivetrain.CurrentDrivetrain().K
-
- if vdrivetrain.left_gear is VelocityDrivetrain.HIGH:
- print "Left is high"
- else:
- print "Left is low"
- if vdrivetrain.right_gear is VelocityDrivetrain.HIGH:
- print "Right is high"
- else:
- print "Right is low"
-
- for t in numpy.arange(0, 1.7, vdrivetrain.dt):
- if t < 0.5:
- vdrivetrain.Update(throttle=0.00, steering=1.0)
- elif t < 1.2:
- vdrivetrain.Update(throttle=0.5, steering=1.0)
- else:
- vdrivetrain.Update(throttle=0.00, steering=1.0)
- t_plot.append(t)
- vl_plot.append(vdrivetrain.X[0, 0])
- vr_plot.append(vdrivetrain.X[1, 0])
- ul_plot.append(vdrivetrain.U[0, 0])
- ur_plot.append(vdrivetrain.U[1, 0])
- left_gear_plot.append((vdrivetrain.left_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
- right_gear_plot.append((vdrivetrain.right_gear is VelocityDrivetrain.HIGH) * 2.0 - 10.0)
-
- fwd_velocity = (vdrivetrain.X[1, 0] + vdrivetrain.X[0, 0]) / 2
- turn_velocity = (vdrivetrain.X[1, 0] - vdrivetrain.X[0, 0])
- if abs(fwd_velocity) < 0.0000001:
- radius_plot.append(turn_velocity)
- else:
- radius_plot.append(turn_velocity / fwd_velocity)
-
- cim_velocity_plot = []
- cim_voltage_plot = []
- cim_time = []
- cim = drivetrain.CIM()
- R = numpy.matrix([[300]])
- for t in numpy.arange(0, 0.5, cim.dt):
- U = numpy.clip(cim.K * (R - cim.X) + R / cim.Kv, cim.U_min, cim.U_max)
- cim.Update(U)
- cim_velocity_plot.append(cim.X[0, 0])
- cim_voltage_plot.append(U[0, 0] * 10)
- cim_time.append(t)
- pylab.plot(cim_time, cim_velocity_plot, label='cim spinup')
- pylab.plot(cim_time, cim_voltage_plot, label='cim voltage')
- pylab.legend()
- pylab.show()
-
- # TODO(austin):
- # Shifting compensation.
-
- # Tighten the turn.
- # Closed loop drive.
-
- pylab.plot(t_plot, vl_plot, label='left velocity')
- pylab.plot(t_plot, vr_plot, label='right velocity')
- pylab.plot(t_plot, ul_plot, label='left voltage')
- pylab.plot(t_plot, ur_plot, label='right voltage')
- pylab.plot(t_plot, radius_plot, label='radius')
- pylab.plot(t_plot, left_gear_plot, label='left gear high')
- pylab.plot(t_plot, right_gear_plot, label='right gear high')
- pylab.legend()
- pylab.show()
- return 0
-
-if __name__ == '__main__':
- sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/python/polydrivetrain_test.py b/frc971/control_loops/python/polydrivetrain_test.py
deleted file mode 100755
index 434cdca..0000000
--- a/frc971/control_loops/python/polydrivetrain_test.py
+++ /dev/null
@@ -1,82 +0,0 @@
-#!/usr/bin/python
-
-import polydrivetrain
-import numpy
-from numpy.testing import *
-import polytope
-import unittest
-
-__author__ = 'Austin Schuh (austin.linux@gmail.com)'
-
-
-class TestVelocityDrivetrain(unittest.TestCase):
- def MakeBox(self, x1_min, x1_max, x2_min, x2_max):
- H = numpy.matrix([[1, 0],
- [-1, 0],
- [0, 1],
- [0, -1]])
- K = numpy.matrix([[x1_max],
- [-x1_min],
- [x2_max],
- [-x2_min]])
- return polytope.HPolytope(H, K)
-
- def test_coerce_inside(self):
- """Tests coercion when the point is inside the box."""
- box = self.MakeBox(1, 2, 1, 2)
-
- # x1 = x2
- K = numpy.matrix([[1, -1]])
- w = 0
-
- assert_array_equal(polydrivetrain.CoerceGoal(box, K, w,
- numpy.matrix([[1.5], [1.5]])),
- numpy.matrix([[1.5], [1.5]]))
-
- def test_coerce_outside_intersect(self):
- """Tests coercion when the line intersects the box."""
- box = self.MakeBox(1, 2, 1, 2)
-
- # x1 = x2
- K = numpy.matrix([[1, -1]])
- w = 0
-
- assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
- numpy.matrix([[2.0], [2.0]]))
-
- def test_coerce_outside_no_intersect(self):
- """Tests coercion when the line does not intersect the box."""
- box = self.MakeBox(3, 4, 1, 2)
-
- # x1 = x2
- K = numpy.matrix([[1, -1]])
- w = 0
-
- assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
- numpy.matrix([[3.0], [2.0]]))
-
- def test_coerce_middle_of_edge(self):
- """Tests coercion when the line intersects the middle of an edge."""
- box = self.MakeBox(0, 4, 1, 2)
-
- # x1 = x2
- K = numpy.matrix([[-1, 1]])
- w = 0
-
- assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
- numpy.matrix([[2.0], [2.0]]))
-
- def test_coerce_perpendicular_line(self):
- """Tests coercion when the line does not intersect and is in quadrant 2."""
- box = self.MakeBox(1, 2, 1, 2)
-
- # x1 = -x2
- K = numpy.matrix([[1, 1]])
- w = 0
-
- assert_array_equal(polydrivetrain.CoerceGoal(box, K, w, numpy.matrix([[5], [5]])),
- numpy.matrix([[1.0], [1.0]]))
-
-
-if __name__ == '__main__':
- unittest.main()
diff --git a/frc971/control_loops/python/shooter.py b/frc971/control_loops/python/shooter.py
deleted file mode 100755
index 69f2599..0000000
--- a/frc971/control_loops/python/shooter.py
+++ /dev/null
@@ -1,254 +0,0 @@
-#!/usr/bin/python
-
-import control_loop
-import numpy
-import sys
-from matplotlib import pylab
-
-class SprungShooter(control_loop.ControlLoop):
- def __init__(self, name="RawSprungShooter"):
- super(SprungShooter, self).__init__(name)
- # Stall Torque in N m
- self.stall_torque = .4982
- # Stall Current in Amps
- self.stall_current = 85
- # Free Speed in RPM
- self.free_speed = 19300.0
- # Free Current in Amps
- self.free_current = 1.2
- # Effective mass of the shooter in kg.
- # This rough estimate should about include the effect of the masses
- # of the gears. If this number is too low, the eigen values of self.A
- # will start to become extremely small.
- self.J = 200
- # Resistance of the motor, divided by the number of motors.
- self.R = 12.0 / self.stall_current / 2.0
- # Motor velocity constant
- self.Kv = ((self.free_speed / 60.0 * 2.0 * numpy.pi) /
- (12.0 - self.R * self.free_current))
- # Torque constant
- self.Kt = self.stall_torque / self.stall_current
- # Spring constant for the springs, N/m
- self.Ks = 2800.0
- # Maximum extension distance (Distance from the 0 force point on the
- # spring to the latch position.)
- self.max_extension = 0.32385
- # Gear ratio multiplied by radius of final sprocket.
- self.G = 10.0 / 40.0 * 20.0 / 54.0 * 24.0 / 54.0 * 20.0 / 84.0 * 16.0 * (3.0 / 8.0) / (2.0 * numpy.pi) * 0.0254
-
- # Control loop time step
- self.dt = 0.01
-
- # State feedback matrices
- self.A_continuous = numpy.matrix(
- [[0, 1],
- [-self.Ks / self.J,
- -self.Kt / self.Kv / (self.J * self.G * self.G * self.R)]])
- self.B_continuous = numpy.matrix(
- [[0],
- [self.Kt / (self.J * self.G * self.R)]])
- self.C = numpy.matrix([[1, 0]])
- self.D = numpy.matrix([[0]])
-
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
-
- self.PlaceControllerPoles([0.45, 0.45])
-
- self.rpl = .05
- self.ipl = 0.008
- self.PlaceObserverPoles([self.rpl,
- self.rpl])
-
- self.U_max = numpy.matrix([[12.0]])
- self.U_min = numpy.matrix([[-12.0]])
-
- self.InitializeState()
-
-
-class Shooter(SprungShooter):
- def __init__(self, name="RawShooter"):
- super(Shooter, self).__init__(name)
-
- # State feedback matrices
- self.A_continuous = numpy.matrix(
- [[0, 1],
- [0, -self.Kt / self.Kv / (self.J * self.G * self.G * self.R)]])
- self.B_continuous = numpy.matrix(
- [[0],
- [self.Kt / (self.J * self.G * self.R)]])
-
- self.A, self.B = self.ContinuousToDiscrete(
- self.A_continuous, self.B_continuous, self.dt)
-
- self.PlaceControllerPoles([0.45, 0.45])
-
- self.rpl = .05
- self.ipl = 0.008
- self.PlaceObserverPoles([self.rpl,
- self.rpl])
-
- self.U_max = numpy.matrix([[12.0]])
- self.U_min = numpy.matrix([[-12.0]])
-
- self.InitializeState()
-
-
-class SprungShooterDeltaU(SprungShooter):
- def __init__(self, name="SprungShooter"):
- super(SprungShooterDeltaU, self).__init__(name)
- A_unaugmented = self.A
- B_unaugmented = self.B
-
- self.A = numpy.matrix([[0.0, 0.0, 0.0],
- [0.0, 0.0, 0.0],
- [0.0, 0.0, 1.0]])
- self.A[0:2, 0:2] = A_unaugmented
- self.A[0:2, 2] = B_unaugmented
-
- self.B = numpy.matrix([[0.0],
- [0.0],
- [1.0]])
-
- self.C = numpy.matrix([[1.0, 0.0, 0.0]])
- self.D = numpy.matrix([[0.0]])
-
- self.PlaceControllerPoles([0.50, 0.35, 0.80])
-
- print "K"
- print self.K
- print "Placed controller poles are"
- print numpy.linalg.eig(self.A - self.B * self.K)[0]
-
- self.rpl = .05
- self.ipl = 0.008
- self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
- self.rpl - 1j * self.ipl, 0.90])
- print "Placed observer poles are"
- print numpy.linalg.eig(self.A - self.L * self.C)[0]
-
- self.U_max = numpy.matrix([[12.0]])
- self.U_min = numpy.matrix([[-12.0]])
-
- self.InitializeState()
-
-
-class ShooterDeltaU(Shooter):
- def __init__(self, name="Shooter"):
- super(ShooterDeltaU, self).__init__(name)
- A_unaugmented = self.A
- B_unaugmented = self.B
-
- self.A = numpy.matrix([[0.0, 0.0, 0.0],
- [0.0, 0.0, 0.0],
- [0.0, 0.0, 1.0]])
- self.A[0:2, 0:2] = A_unaugmented
- self.A[0:2, 2] = B_unaugmented
-
- self.B = numpy.matrix([[0.0],
- [0.0],
- [1.0]])
-
- self.C = numpy.matrix([[1.0, 0.0, 0.0]])
- self.D = numpy.matrix([[0.0]])
-
- self.PlaceControllerPoles([0.55, 0.45, 0.80])
-
- print "K"
- print self.K
- print "Placed controller poles are"
- print numpy.linalg.eig(self.A - self.B * self.K)[0]
-
- self.rpl = .05
- self.ipl = 0.008
- self.PlaceObserverPoles([self.rpl + 1j * self.ipl,
- self.rpl - 1j * self.ipl, 0.90])
- print "Placed observer poles are"
- print numpy.linalg.eig(self.A - self.L * self.C)[0]
-
- self.U_max = numpy.matrix([[12.0]])
- self.U_min = numpy.matrix([[-12.0]])
-
- self.InitializeState()
-
-
-def ClipDeltaU(shooter, old_voltage, delta_u):
- old_u = old_voltage
- new_u = numpy.clip(old_u + delta_u, shooter.U_min, shooter.U_max)
- return new_u - old_u
-
-def main(argv):
- # Simulate the response of the system to a goal.
- sprung_shooter = SprungShooterDeltaU()
- raw_sprung_shooter = SprungShooter()
- close_loop_x = []
- close_loop_u = []
- goal_position = -0.3
- R = numpy.matrix([[goal_position], [0.0], [-sprung_shooter.A[1, 0] / sprung_shooter.A[1, 2] * goal_position]])
- voltage = numpy.matrix([[0.0]])
- for _ in xrange(500):
- U = sprung_shooter.K * (R - sprung_shooter.X_hat)
- U = ClipDeltaU(sprung_shooter, voltage, U)
- sprung_shooter.Y = raw_sprung_shooter.Y + 0.01
- sprung_shooter.UpdateObserver(U)
- voltage += U;
- raw_sprung_shooter.Update(voltage)
- close_loop_x.append(raw_sprung_shooter.X[0, 0] * 10)
- close_loop_u.append(voltage[0, 0])
-
- pylab.plot(range(500), close_loop_x)
- pylab.plot(range(500), close_loop_u)
- pylab.show()
-
- shooter = ShooterDeltaU()
- raw_shooter = Shooter()
- close_loop_x = []
- close_loop_u = []
- goal_position = -0.3
- R = numpy.matrix([[goal_position], [0.0], [-shooter.A[1, 0] / shooter.A[1, 2] * goal_position]])
- voltage = numpy.matrix([[0.0]])
- for _ in xrange(500):
- U = shooter.K * (R - shooter.X_hat)
- U = ClipDeltaU(shooter, voltage, U)
- shooter.Y = raw_shooter.Y + 0.01
- shooter.UpdateObserver(U)
- voltage += U;
- raw_shooter.Update(voltage)
- close_loop_x.append(raw_shooter.X[0, 0] * 10)
- close_loop_u.append(voltage[0, 0])
-
- pylab.plot(range(500), close_loop_x)
- pylab.plot(range(500), close_loop_u)
- pylab.show()
-
- # Write the generated constants out to a file.
- if len(argv) != 5:
- print "Expected .h file name and .cc file name for"
- print "both the plant and unaugmented plant"
- else:
- unaug_sprung_shooter = SprungShooter("RawSprungShooter")
- unaug_shooter = Shooter("RawShooter")
- unaug_loop_writer = control_loop.ControlLoopWriter("RawShooter",
- [unaug_sprung_shooter,
- unaug_shooter])
- if argv[3][-3:] == '.cc':
- unaug_loop_writer.Write(argv[4], argv[3])
- else:
- unaug_loop_writer.Write(argv[3], argv[4])
-
- sprung_shooter = SprungShooterDeltaU()
- shooter = ShooterDeltaU()
- loop_writer = control_loop.ControlLoopWriter("Shooter", [sprung_shooter,
- shooter])
-
- loop_writer.AddConstant(control_loop.Constant("kMaxExtension", "%f",
- sprung_shooter.max_extension))
- loop_writer.AddConstant(control_loop.Constant("kSpringConstant", "%f",
- sprung_shooter.Ks))
- if argv[1][-3:] == '.cc':
- loop_writer.Write(argv[2], argv[1])
- else:
- loop_writer.Write(argv[1], argv[2])
-
-if __name__ == '__main__':
- sys.exit(main(sys.argv))
diff --git a/frc971/control_loops/update_arm.sh b/frc971/control_loops/update_arm.sh
deleted file mode 100755
index c4c1ab9..0000000
--- a/frc971/control_loops/update_arm.sh
+++ /dev/null
@@ -1,10 +0,0 @@
-#!/bin/bash
-#
-# Updates the arm controllers (for both robots).
-
-cd $(dirname $0)
-
-./python/arm.py fridge/arm_motor_plant.cc \
- fridge/arm_motor_plant.h \
- fridge/integral_arm_plant.cc \
- fridge/integral_arm_plant.h
diff --git a/frc971/control_loops/update_claw.sh b/frc971/control_loops/update_claw.sh
deleted file mode 100755
index 3ef6921..0000000
--- a/frc971/control_loops/update_claw.sh
+++ /dev/null
@@ -1,8 +0,0 @@
-#!/bin/bash
-#
-# Updates the claw controllers (for both robots).
-
-cd $(dirname $0)
-
-./python/claw.py claw/claw_motor_plant.cc \
- claw/claw_motor_plant.h
diff --git a/frc971/control_loops/update_drivetrain.sh b/frc971/control_loops/update_drivetrain.sh
deleted file mode 100755
index bad1074..0000000
--- a/frc971/control_loops/update_drivetrain.sh
+++ /dev/null
@@ -1,10 +0,0 @@
-#!/bin/bash
-#
-# Updates the drivetrain controllers (for both robots).
-
-cd $(dirname $0)
-
-./python/drivetrain.py drivetrain/drivetrain_dog_motor_plant.h \
- drivetrain/drivetrain_dog_motor_plant.cc \
- drivetrain/drivetrain_clutch_motor_plant.h \
- drivetrain/drivetrain_clutch_motor_plant.cc
diff --git a/frc971/control_loops/update_elevator.sh b/frc971/control_loops/update_elevator.sh
deleted file mode 100755
index 25ea27e..0000000
--- a/frc971/control_loops/update_elevator.sh
+++ /dev/null
@@ -1,8 +0,0 @@
-#!/bin/bash
-#
-# Updates the elevator controllers (for both robots).
-
-cd $(dirname $0)
-
-./python/elevator.py fridge/elevator_motor_plant.cc \
- fridge/elevator_motor_plant.h
diff --git a/frc971/control_loops/update_polydrivetrain.sh b/frc971/control_loops/update_polydrivetrain.sh
deleted file mode 100755
index 2e2748e..0000000
--- a/frc971/control_loops/update_polydrivetrain.sh
+++ /dev/null
@@ -1,12 +0,0 @@
-#!/bin/bash
-#
-# Updates the polydrivetrain controllers (for both robots) and CIM models.
-
-cd $(dirname $0)
-
-./python/polydrivetrain.py drivetrain/polydrivetrain_dog_motor_plant.h \
- drivetrain/polydrivetrain_dog_motor_plant.cc \
- drivetrain/polydrivetrain_clutch_motor_plant.h \
- drivetrain/polydrivetrain_clutch_motor_plant.cc \
- drivetrain/polydrivetrain_cim_plant.h \
- drivetrain/polydrivetrain_cim_plant.cc
diff --git a/frc971/frc971.gyp b/frc971/frc971.gyp
index 4707e66..0f38180 100644
--- a/frc971/frc971.gyp
+++ b/frc971/frc971.gyp
@@ -1,52 +1,15 @@
{
'targets': [
{
- 'target_name': 'constants',
- 'type': 'static_library',
- 'sources': [
- 'constants.cc',
- ],
+ 'target_name': 'All',
+ 'type': 'none',
'dependencies': [
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/common.gyp:once',
- '<(AOS)/common/network/network.gyp:team_number',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:polydrivetrain_plants',
- ],
- 'export_dependent_settings': [
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:state_feedback_loop',
- ],
- },
- {
- 'target_name': 'joystick_reader',
- 'type': 'executable',
- 'sources': [
- 'joystick_reader.cc',
- ],
- 'dependencies': [
- '<(AOS)/prime/input/input.gyp:joystick_input',
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/common/util/util.gyp:log_interval',
- '<(AOS)/common/actions/actions.gyp:action_lib',
+ '<(AOS)/build/aos_all.gyp:Prime',
- '<(DEPTH)/frc971/queues/queues.gyp:gyro',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/autonomous/autonomous.gyp:auto_queue',
- '<(DEPTH)/frc971/actors/actors.gyp:stack_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:stack_and_lift_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:stack_and_hold_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:pickup_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:lift_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:held_to_lift_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:can_pickup_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:score_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:horizontal_can_pickup_action_lib',
- '<(DEPTH)/frc971/actors/actors.gyp:fridge_profile_lib',
+ 'control_loops/control_loops.gyp:state_feedback_loop_test',
+ 'control_loops/control_loops.gyp:position_sensor_sim_test',
+ 'zeroing/zeroing.gyp:zeroing_test',
+ 'control_loops/voltage_cap/voltage_cap.gyp:voltage_cap_test',
],
},
],
diff --git a/frc971/http_status/http_status.cc b/frc971/http_status/http_status.cc
deleted file mode 100644
index e0ee5de..0000000
--- a/frc971/http_status/http_status.cc
+++ /dev/null
@@ -1,296 +0,0 @@
-#include "frc971/http_status/http_status.h"
-
-#include <iostream>
-#include <sstream>
-#include <string>
-#include <thread>
-#include <vector>
-
-#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 "frc971/control_loops/claw/claw.q.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-
-#include "frc971/http_status/embedded.h"
-
-namespace frc971 {
-namespace http_status {
-
-// TODO(comran): Make some of these separate libraries & document them better.
-
-HTTPStatusMessage::HTTPStatusMessage()
- : sample_id_(0),
- measure_index_(0),
- overflow_id_(200),
- num_samples_per_packet_(50) {}
-
-void HTTPStatusMessage::NextSample() {
- int32_t adjusted_index = GetIndex(sample_id_);
-
- ::aos::time::Time time_now = ::aos::time::Time::Now();
-
- if (sample_id_ < overflow_id_) {
- sample_times_.emplace_back(time_now);
- data_values_.emplace_back(::std::vector<double>());
- } else {
- sample_times_[adjusted_index] = time_now;
- }
-
- sample_id_++;
- measure_index_ = 0;
-
- CHECK(!mutex_.Lock()); // Lock the mutex so measures can be added.
-}
-
-void HTTPStatusMessage::EndSample() { mutex_.Unlock(); }
-
-int32_t HTTPStatusMessage::GetIndex(int32_t sample_id) {
- return sample_id % overflow_id_;
-}
-
-void HTTPStatusMessage::AddMeasure(::std::string name, double value) {
- // Mutex should be locked when this method is called to synchronize packets.
- assert(mutex_.OwnedBySelf());
-
- int32_t index = GetIndex(sample_id_ - 1);
-
- if (measure_index_ >= static_cast<int32_t>(data_names_.size())) {
- data_names_.emplace_back(name);
- }
-
- if (measure_index_ >= static_cast<int32_t>(data_values_.at(index).size())) {
- data_values_.at(index).emplace_back(value);
- } else {
- data_values_.at(index).at(measure_index_) = value;
- }
- measure_index_++;
-}
-
-::std::string HTTPStatusMessage::Fetch(size_t from_sample) {
- ::aos::MutexLocker locker(&mutex_);
-
- ::std::stringstream message;
- message.precision(10); // Cap how precise the time/measurement data is.
-
- // To save space, data is being sent with a custom protocol over to the
- // client.
- // Initially, a message containing all the names of the measurements is sent
- // and is preceeded with a *.
- // Names begin with a star and are split with commas.
-
- // Example: *test,test2
- if (static_cast<int32_t>(from_sample) == -1) {
- message << "*";
- for (int32_t cur_data_name = 0;
- cur_data_name < static_cast<int32_t>(data_names_.size());
- cur_data_name++) {
- if (cur_data_name > 0) {
- message << ",";
- }
- message << data_names_.at(cur_data_name);
- }
- return message.str();
- }
-
- // TODO(comran): Use from_sample to determine the speed packets should be sent
- // out to avoid skipping packets.
- from_sample = sample_id_ - num_samples_per_packet_;
-
- // Data packets are sent, with raw data being placed at the same index as the
- // original index of the measurement name sent in the initial packet.
- // Samples are split with dollar signs, info with percent signs, and
- // measurements with commas.
- // This special format system is helpful for debugging issues and looping
- // through the data on the client side.
-
- // Example of two samples that correspond with the initialized example:
- // 289%2803.135127%10,67$290%2803.140109%12,68
- for (int32_t cur_sample = from_sample;
- cur_sample <
- static_cast<int32_t>(from_sample + num_samples_per_packet_) &&
- GetIndex(cur_sample) < static_cast<int32_t>(data_values_.size());
- cur_sample++) {
- if (cur_sample != static_cast<int32_t>(from_sample)) {
- message << "$";
- }
-
- int32_t adjusted_index = GetIndex(cur_sample);
-
- message << cur_sample << "%" << sample_times_.at(adjusted_index).ToSeconds()
- << "%";
- for (int32_t cur_measure = 0;
- cur_measure < static_cast<int32_t>(data_names_.size());
- cur_measure++) {
- if (cur_measure > 0) {
- message << ",";
- }
- message << data_values_.at(adjusted_index).at(cur_measure);
- }
- }
- return message.str();
-}
-
-DataCollector::DataCollector() : cur_raw_data_("no data") {}
-
-void DataCollector::RunIteration() {
- auto& fridge_queue = control_loops::fridge_queue;
- auto& claw_queue = control_loops::claw_queue;
-
- fridge_queue.status.FetchAnother();
- claw_queue.status.FetchAnother();
-
- message_.NextSample();
- // Add recorded data here. /////
- // NOTE: Try to use fewer than 30 measures, or the whole thing will lag.
- // Abbreviate names if long, otherwise just use the command to get the value
- // from the queue.
-
- // TODO(comran): Make it so that the name doesn't have to be copied as a
- // string.
-
- // //// Fridge
- // Positions
- message_.AddMeasure("(fridge position left arm encoder)",
- fridge_queue.position->arm.left.encoder);
- message_.AddMeasure("(fridge position right arm encoder)",
- fridge_queue.position->arm.right.encoder);
- message_.AddMeasure("(fridge position left elev encoder)",
- fridge_queue.position->elevator.left.encoder);
- message_.AddMeasure("(fridge position right elev encoder)",
- fridge_queue.position->elevator.right.encoder);
- // Goals
- message_.AddMeasure("fridge_queue.goal->profiling_type",
- fridge_queue.goal->profiling_type);
- message_.AddMeasure("fridge_queue.goal->angle", fridge_queue.goal->angle);
- message_.AddMeasure("fridge_queue.goal->angular_velocity",
- fridge_queue.goal->angular_velocity);
- message_.AddMeasure("fridge_queue.goal->height", fridge_queue.goal->height);
- message_.AddMeasure("fridge_queue.goal->velocity",
- fridge_queue.goal->velocity);
- message_.AddMeasure("fridge_queue.x", fridge_queue.goal->x);
- message_.AddMeasure("fridge_queue.x_velocity", fridge_queue.goal->x_velocity);
- message_.AddMeasure("fridge_queue.y", fridge_queue.goal->y);
- message_.AddMeasure("fridge_queue.y_velocity", fridge_queue.goal->y_velocity);
- // Statuses
- message_.AddMeasure("fridge_queue.status->height",
- fridge_queue.status->height);
- message_.AddMeasure("fridge_queue.status->velocity",
- fridge_queue.status->velocity);
- message_.AddMeasure("fridge_queue.status->angle", fridge_queue.status->angle);
- message_.AddMeasure("fridge_queue.status->angular_velocity",
- fridge_queue.status->angular_velocity);
- message_.AddMeasure("fridge_queue.status->x", fridge_queue.status->x);
- message_.AddMeasure("fridge_queue.status->x_velocity",
- fridge_queue.status->x_velocity);
- message_.AddMeasure("fridge_queue.status->y", fridge_queue.status->y);
- message_.AddMeasure("fridge_queue.status->y_velocity",
- fridge_queue.status->y_velocity);
- message_.AddMeasure("fridge_queue.status->state", fridge_queue.status->state);
- message_.AddMeasure("fridge_queue.status->zeroed",
- fridge_queue.status->zeroed);
- message_.AddMeasure("fridge_queue.status->estopped",
- fridge_queue.status->estopped);
- // Outputs
- message_.AddMeasure("fridge_queue.output->left_arm",
- fridge_queue.output->left_arm);
- message_.AddMeasure("fridge_queue.output->right_arm",
- fridge_queue.output->right_arm);
- message_.AddMeasure("fridge_queue.output->left_elevator",
- fridge_queue.output->left_elevator);
- message_.AddMeasure("fridge_queue.output->right_elevator",
- fridge_queue.output->right_elevator);
- // End recorded data. /////
- message_.EndSample();
-}
-
-::std::string DataCollector::GetData(int32_t from_sample) {
- return message_.Fetch(from_sample);
-}
-
-void DataCollector::operator()() {
- ::aos::SetCurrentThreadName("HTTPStatusData");
-
- while (run_) {
- ::aos::time::PhasedLoopXMS(5, 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_.GetData(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) {
- 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 http_status
-} // namespace frc971
-
-int main(int, char* []) {
- ::aos::InitNRT();
-
- seasocks::Server server(::std::shared_ptr<seasocks::Logger>(
- new frc971::http_status::SeasocksLogger(seasocks::Logger::INFO)));
- frc971::http_status::SocketHandler socket_handler;
-
- server.addWebSocketHandler(
- "/ws",
- ::std::shared_ptr<frc971::http_status::SocketHandler>(&socket_handler));
- server.serve("www", 8080);
-
- socket_handler.Quit();
-
- ::aos::Cleanup();
- return 0;
-}
diff --git a/frc971/http_status/http_status.gyp b/frc971/http_status/http_status.gyp
deleted file mode 100644
index 410e8b9..0000000
--- a/frc971/http_status/http_status.gyp
+++ /dev/null
@@ -1,46 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'http_status',
- 'type': 'executable',
- 'sources': [
- 'http_status.cc',
- ],
- 'actions': [
- {
- 'action_name': 'http_status_gen_embedded',
- 'inputs': [
- '<!@(find ./www_defaults)',
- '<(AOS)/externals/seasocks/gen_embedded.py',
- ],
- 'outputs': [
- '<(SHARED_INTERMEDIATE_DIR)/http_status/frc971/http_status/embedded.h',
- ],
- 'action': [
- 'python', '<(AOS)/externals/seasocks/gen_embedded.py', '<(_outputs)',
- ],
- },
- ],
- 'include_dirs': [
- '<(SHARED_INTERMEDIATE_DIR)/http_status/'
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/build/aos.gyp:logging',
- '<(EXTERNALS):seasocks',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/common.gyp:time',
- ],
- 'copies': [
- {
- 'destination': '<(rsync_dir)',
- 'files': [
- 'www',
- ],
- },
- ],
- },
- ],
-}
diff --git a/frc971/http_status/http_status.h b/frc971/http_status/http_status.h
deleted file mode 100644
index 2f7497d..0000000
--- a/frc971/http_status/http_status.h
+++ /dev/null
@@ -1,106 +0,0 @@
-#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 frc971 {
-namespace http_status {
-
-// A class for storing data from DataCollector and packaging it as a custom
-// message for the websocket.
-// Samples are stored in a vector that wraps around at a certain point to avoid
-// clogging up memory. These samples should be already on all clients before
-// they are overwritten. To avoid losing samples, there must be a balance
-// between the rate samples are being recorded at and the speed of the link
-// between the robot and client.
-
-class HTTPStatusMessage {
- public:
- HTTPStatusMessage();
-
- // Stores an individual measurement in the current sample.
- void AddMeasure(::std::string name, double value);
-
- // Starts a new sample that contains measurements for all the states at a
- // timestep, and lock mutex to synchronize measures.
- void NextSample();
-
- // Unlock mutex.
- void EndSample();
-
- // Method called by the websocket to get a JSON-packaged string containing,
- // at most, a constant number of samples, starting at "from_sample".
- // "from_sample" is a specific index for a sample that is not wrapped.
- ::std::string Fetch(size_t from_sample);
-
- private:
- // Returns the vector index of the sample given.
- // Since the vectors wrap, multiple sample_ids may refer to the same vector
- // index.
- int32_t GetIndex(int32_t sample_id);
-
- // Vectors of vectors to store samples at indexes determined by GetIndex.
- ::std::vector<::std::string> data_names_;
- ::std::vector<::std::vector<double>> data_values_;
- ::std::vector<::aos::time::Time> sample_times_;
-
- int32_t sample_id_; // Last sample id used.
- int32_t measure_index_; // Last measure index used.
- const int32_t overflow_id_; // Vector wrapping size.
- // Number of samples to include in each JSON packet.
- const int32_t num_samples_per_packet_;
-
- // Mutex used to synchronize data.
- ::aos::Mutex mutex_;
-};
-
-class DataCollector {
- public:
- DataCollector();
- void RunIteration();
- ::std::string GetData(int32_t from);
-
- void operator()(); // Will be called by ::std::thread internally.
- void Quit() { run_ = false; }
-
- private:
- ::std::string cur_raw_data_;
- HTTPStatusMessage message_;
- ::std::atomic<bool> run_{true};
-};
-
-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 http_status
-} // namespace frc971
diff --git a/frc971/http_status/www/index.html b/frc971/http_status/www/index.html
deleted file mode 100644
index 0fe83b4..0000000
--- a/frc971/http_status/www/index.html
+++ /dev/null
@@ -1,160 +0,0 @@
-<!DOCTYPE html>
-<html>
-
-<head>
-<title>Hello, world</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 safetyTimeout;
-var safetyIntervalTime = 10;
-var selected = 0;
-
-// Filter out junky JSON packets that will otherwise cause nasty decoding errors.
-function filterUnicode(quoted) {
- escapable.lastIndex = 0;
- if (!escapable.test(quoted)) return quoted;
-
- return quoted.replace(escapable, function(a) {
- return '';
- });
-}
-
-// Change the current data index to plot on the graph.
-function changeSelected(select) {
- selected = select;
- document.getElementById("selected").innerHTML = "Selected: " + selected;
-}
-
-// Get a new JSON packet from the websocket on the robot.
-function refresh() {
- ws.send(lastSampleID);
- safetyTimeout = setTimeout(safetyRefresh, safetyIntervalTime);
-}
-
-function safetyRefresh(){
- console.log("Safety timeout exceeded. Performing additional refresh...");
- refresh();
-}
-
-window.onload = function() {
- var dps = [];
- var numDatas = 0;
- var chart = new CanvasJS.Chart("chartContainer", {
- title: {
- text: "Live Data"
- },
- axisX: {
- title: "Time (sec)"
- },
- axisY: {
- title: "Units"
- },
- zoomEnabled: true,
- panEnabled: true,
- data: [{
- color: 'rgba(119, 152, 191, 1.0)',
- type: "scatter",
- dataPoints: dps
- }],
- });
-
- chart.render();
-
- $(function() {
- ws = new WebSocket('ws://' + document.location.host + '/ws');
- run = true;
- xVal = 1;
- lastSampleID = -1;
-
- // Socket created & first opened.
- ws.onopen = function() {
- run = true;
- refresh();
- };
-
- // Socket disconnected.
- ws.onclose = function() {
- console.log('onclose');
- run = false;
- $('#message').text('Lost connection.');
- };
-
- // Received message over the socket, so parse and chart it.
- ws.onmessage = function(message) {
- console.log(message);
- clearTimeout(safetyTimeout);
- message = message.data;
- //$('#data').html(message);
- if(message.charAt(0) == "*"){
- message = message.substring(1);
- var names = message.split(",");
- for (var i = numDatas; i < names.length; i++) {
- $('#dataTable').append('<tr onClick="changeSelected(' + i +
- ')"><td>' + names[i] + '</td><td></td></tr>');
- numDatas++;
- }
- lastSampleID = 0;
- }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(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]);
- if(y == selected){
- dps.push({
- x: parseFloat(info[1]),
- y: parseFloat(values[y])
- });
- if(dps.length > 10000){
- dps.shift();
- }
- }
- }
- }
- }
- }
-
- chart.render();
- }
-
- if(run){
- setTimeout(refresh, intervalTime);
- }
- };
-
- // Socket error, most likely due to a server-side error.
- ws.onerror = function(error) {
- console.log('onerror ' + error);
- run = false;
- };
- });
-}
-</script>
-<script type="text/javascript" src='/lib/jquery-1.4.4.js'></script>
-<script type="text/javascript" src='/lib/canvasjs.min.js'></script>
-<script type="text/javascript" src='/lib/reconnecting-websocket.min.js'></script>
-</head>
-<body>
-<div style="width: 1200px;margin-left: auto;margin-right:auto">
- <table id="dataTable" style="width: 200px;cell-spacing:0;cell-padding:0;
- text-align:left">
- </table>
- <div id="chartContainer" style="height:600px; width:100%;"></div>
- <div style="width: 1000px;float: right">
- <p id="message" style="color: #FF0000"></p>
- <p id="selected">Selected: 0</p>
- <p id="data"></p>
- </div>
-</div>
-</body>
-</html>
diff --git a/frc971/http_status/www/lib/canvasjs.min.js b/frc971/http_status/www/lib/canvasjs.min.js
deleted file mode 100644
index 67fc83b..0000000
--- a/frc971/http_status/www/lib/canvasjs.min.js
+++ /dev/null
@@ -1,429 +0,0 @@
-/*
- CanvasJS HTML5 & JavaScript Charts - v1.6.1 GA- http://canvasjs.com/
- Copyright 2013 fenopix
-*/
-(function(){function O(a,b){a.prototype=Aa(b.prototype);a.prototype.constructor=a;a.parent=b.prototype}function Aa(a){function b(){}b.prototype=a;return new b}function qa(a,b,c){"millisecond"===c?a.setMilliseconds(a.getMilliseconds()+1*b):"second"===c?a.setSeconds(a.getSeconds()+1*b):"minute"===c?a.setMinutes(a.getMinutes()+1*b):"hour"===c?a.setHours(a.getHours()+1*b):"day"===c?a.setDate(a.getDate()+1*b):"week"===c?a.setDate(a.getDate()+7*b):"month"===c?a.setMonth(a.getMonth()+1*b):"year"===c&&a.setFullYear(a.getFullYear()+
-1*b);return a}function Y(a,b){return z[b+"Duration"]*a}function K(a,b){var c=!1;0>a&&(c=!0,a*=-1);a=""+a;for(b=b?b:1;a.length<b;)a="0"+a;return c?"-"+a:a}function Z(a){if(!a)return a;a=a.replace(/^\s\s*/,"");for(var b=/\s/,c=a.length;b.test(a.charAt(--c)););return a.slice(0,c+1)}function Ba(a){a.roundRect=function(a,c,d,e,f,g,k,p){k&&(this.fillStyle=k);p&&(this.strokeStyle=p);"undefined"===typeof f&&(f=5);this.lineWidth=g;this.beginPath();this.moveTo(a+f,c);this.lineTo(a+d-f,c);this.quadraticCurveTo(a+
-d,c,a+d,c+f);this.lineTo(a+d,c+e-f);this.quadraticCurveTo(a+d,c+e,a+d-f,c+e);this.lineTo(a+f,c+e);this.quadraticCurveTo(a,c+e,a,c+e-f);this.lineTo(a,c+f);this.quadraticCurveTo(a,c,a+f,c);this.closePath();k&&this.fill();p&&0<g&&this.stroke()}}function ra(a,b){return a-b}function Ca(a,b){return a.x-b.x}function C(a){var b=((a&16711680)>>16).toString(16),c=((a&65280)>>8).toString(16);a=((a&255)>>0).toString(16);b=2>b.length?"0"+b:b;c=2>c.length?"0"+c:c;a=2>a.length?"0"+a:a;return"#"+b+c+a}function ca(a,
-b,c){c=c||"normal";var d=a+"_"+b+"_"+c,e=sa[d];if(isNaN(e)){try{a="position:absolute; left:0px; top:-20000px; padding:0px;margin:0px;border:none;white-space:pre;line-height:normal;font-family:"+a+"; font-size:"+b+"px; font-weight:"+c+";";if(!R){var f=document.body;R=document.createElement("span");R.innerHTML="";var g=document.createTextNode("Mpgyi");R.appendChild(g);f.appendChild(R)}R.style.display="";R.setAttribute("style",a);e=Math.round(R.offsetHeight);R.style.display="none"}catch(k){e=Math.ceil(1.1*
-b)}e=Math.max(e,b);sa[d]=e}return e}function E(a,b,c,d){if(a.addEventListener)a.addEventListener(b,c,d||!1);else if(a.attachEvent)a.attachEvent("on"+b,function(b){b=b||window.event;b.preventDefault=b.preventDefault||function(){b.returnValue=!1};b.stopPropagation=b.stopPropagation||function(){b.cancelBubble=!0};c.call(a,b)});else return!1}function ta(a,b,c){a*=H;b*=H;a=c.getImageData(a,b,2,2).data;b=!0;for(c=0;4>c;c++)if(a[c]!==a[c+4]|a[c]!==a[c+8]|a[c]!==a[c+12]){b=!1;break}return b?a[0]<<16|a[1]<<
-8|a[2]:0}function ua(a,b,c){var d;d=a?a+"FontStyle":"fontStyle";var e=a?a+"FontWeight":"fontWeight",f=a?a+"FontSize":"fontSize";a=a?a+"FontFamily":"fontFamily";d=""+(b[d]?b[d]+" ":c&&c[d]?c[d]+" ":"");d+=b[e]?b[e]+" ":c&&c[e]?c[e]+" ":"";d+=b[f]?b[f]+"px ":c&&c[f]?c[f]+"px ":"";b=b[a]?b[a]+"":c&&c[a]?c[a]+"":"";!t&&b&&(b=b.split(",")[0],"'"!==b[0]&&'"'!==b[0]&&(b="'"+b+"'"));return d+=b}function T(a,b,c){return a in b?b[a]:c[a]}function da(a,b,c){if(t&&va){var d=a.getContext("2d");ea=d.webkitBackingStorePixelRatio||
-d.mozBackingStorePixelRatio||d.msBackingStorePixelRatio||d.oBackingStorePixelRatio||d.backingStorePixelRatio||1;H=ja/ea;a.width=b*H;a.height=c*H;ja!==ea&&(a.style.width=b+"px",a.style.height=c+"px",d.scale(H,H))}else a.width=b,a.height=c}function U(a,b){var c=document.createElement("canvas");c.setAttribute("class","canvasjs-chart-canvas");da(c,a,b);t||"undefined"===typeof G_vmlCanvasManager||G_vmlCanvasManager.initElement(c);return c}function wa(a,b,c){if(a&&b&&c){c=c+"."+("jpeg"===b?"jpg":b);var d=
-"image/"+b;a=a.toDataURL(d);var e=!1,f=document.createElement("a");f.download=c;f.href=a;f.target="_blank";if("undefined"!==typeof Blob&&new Blob){for(var g=a.replace(/^data:[a-z/]*;base64,/,""),g=atob(g),k=new ArrayBuffer(g.length),p=new Uint8Array(k),h=0;h<g.length;h++)p[h]=g.charCodeAt(h);b=new Blob([k],{type:"image/"+b});try{window.navigator.msSaveBlob(b,c),e=!0}catch(l){f.dataset.downloadurl=[d,f.download,f.href].join(":"),f.href=window.URL.createObjectURL(b)}}if(!e)try{event=document.createEvent("MouseEvents"),
-event.initMouseEvent("click",!0,!1,window,0,0,0,0,0,!1,!1,!1,!1,0,null),f.dispatchEvent?f.dispatchEvent(event):f.fireEvent&&f.fireEvent("onclick")}catch(r){b=window.open(),b.document.write("<img src='"+a+"'></img><div>Please right click on the image and save it to your device</div>"),b.document.close()}}}function M(a,b,c){b.getAttribute("state")!==c&&(b.setAttribute("state",c),b.setAttribute("type","button"),b.style.position="relative",b.style.margin="0px 0px 0px 0px",b.style.padding="3px 4px 0px 4px",
-b.style.cssFloat="left",b.setAttribute("title",a._cultureInfo[c+"Text"]),b.innerHTML="<img style='height:16px;' src='"+Da[c].image+"' alt='"+a._cultureInfo[c+"Text"]+"' />")}function ka(){for(var a=null,b=0;b<arguments.length;b++)a=arguments[b],a.style&&(a.style.display="inline")}function S(){for(var a=null,b=0;b<arguments.length;b++)(a=arguments[b])&&a.style&&(a.style.display="none")}function L(a,b,c){this._defaultsKey=a;var d={};c&&(W[c]&&W[c][a])&&(d=W[c][a]);this._options=b?b:{};this.setOptions(this._options,
-d)}function v(a,b,c){this._publicChartReference=c;b=b||{};v.parent.constructor.call(this,"Chart",b,b.theme?b.theme:"theme1");var d=this;this._containerId=a;this._objectsInitialized=!1;this.overlaidCanvasCtx=this.ctx=null;this._indexLabels=[];this._panTimerId=0;this._lastTouchEventType="";this._lastTouchData=null;this.isAnimating=!1;this.renderCount=0;this.panEnabled=this.disableToolTip=this.animatedRender=!1;this._defaultCursor="default";this.plotArea={canvas:null,ctx:null,x1:0,y1:0,x2:0,y2:0,width:0,
-height:0};this._dataInRenderedOrder=[];(this._container="string"===typeof this._containerId?document.getElementById(this._containerId):this._containerId)?(this._container.innerHTML="",b=a=0,a=this._options.width?this.width:0<this._container.clientWidth?this._container.clientWidth:this.width,b=this._options.height?this.height:0<this._container.clientHeight?this._container.clientHeight:this.height,this.width=a,this.height=b,this._selectedColorSet="undefined"!==typeof V[this.colorSet]?V[this.colorSet]:
-V.colorSet1,this._canvasJSContainer=document.createElement("div"),this._canvasJSContainer.setAttribute("class","canvasjs-chart-container"),this._canvasJSContainer.style.position="relative",this._canvasJSContainer.style.textAlign="left",this._canvasJSContainer.style.cursor="auto",t||(this._canvasJSContainer.style.height="0px"),this._container.appendChild(this._canvasJSContainer),this.canvas=U(a,b),this.canvas.style.position="absolute",this.canvas.getContext&&(this._canvasJSContainer.appendChild(this.canvas),
-this.ctx=this.canvas.getContext("2d"),this.ctx.textBaseline="top",Ba(this.ctx),t?this.plotArea.ctx=this.ctx:(this.plotArea.canvas=U(a,b),this.plotArea.canvas.style.position="absolute",this.plotArea.canvas.setAttribute("class","plotAreaCanvas"),this._canvasJSContainer.appendChild(this.plotArea.canvas),this.plotArea.ctx=this.plotArea.canvas.getContext("2d")),this.overlaidCanvas=U(a,b),this.overlaidCanvas.style.position="absolute",this._canvasJSContainer.appendChild(this.overlaidCanvas),this.overlaidCanvasCtx=
-this.overlaidCanvas.getContext("2d"),this.overlaidCanvasCtx.textBaseline="top",this._eventManager=new $(this),E(window,"resize",function(){d._updateSize()&&d.render()}),this._toolBar=document.createElement("div"),this._toolBar.setAttribute("class","canvasjs-chart-toolbar"),this._toolBar.style.cssText="position: absolute; right: 2px; top: 0px;",this._canvasJSContainer.appendChild(this._toolBar),this.bounds={x1:0,y1:0,x2:this.width,y2:this.height},E(this.overlaidCanvas,"click",function(a){d._mouseEventHandler(a)}),
-E(this.overlaidCanvas,"mousemove",function(a){d._mouseEventHandler(a)}),E(this.overlaidCanvas,"mouseup",function(a){d._mouseEventHandler(a)}),E(this.overlaidCanvas,"mousedown",function(a){d._mouseEventHandler(a);S(d._dropdownMenu)}),E(this.overlaidCanvas,"mouseout",function(a){d._mouseEventHandler(a)}),E(this.overlaidCanvas,window.navigator.msPointerEnabled?"MSPointerDown":"touchstart",function(a){d._touchEventHandler(a)}),E(this.overlaidCanvas,window.navigator.msPointerEnabled?"MSPointerMove":"touchmove",
-function(a){d._touchEventHandler(a)}),E(this.overlaidCanvas,window.navigator.msPointerEnabled?"MSPointerUp":"touchend",function(a){d._touchEventHandler(a)}),E(this.overlaidCanvas,window.navigator.msPointerEnabled?"MSPointerCancel":"touchcancel",function(a){d._touchEventHandler(a)}),this._creditLink||(this._creditLink=document.createElement("a"),this._creditLink.setAttribute("class","canvasjs-chart-credit"),this._creditLink.setAttribute("style","outline:none;margin:0px;position:absolute;right:3px;top:"+
-(this.height-14)+"px;color:dimgrey;text-decoration:none;font-size:10px;font-family:Lucida Grande, Lucida Sans Unicode, Arial, sans-serif"),this._creditLink.setAttribute("tabIndex",-1),this._creditLink.setAttribute("target","_blank")),this._toolTip=new N(this,this._options.toolTip,this.theme),this.layoutManager=new aa(this),this.axisY2=this.axisY=this.axisX=this.data=null,this.sessionVariables={axisX:{internalMinimum:null,internalMaximum:null},axisY:{internalMinimum:null,internalMaximum:null},axisY2:{internalMinimum:null,
-internalMaximum:null}})):window.console&&window.console.log('CanvasJS Error: Chart Container with id "'+this._containerId+'" was not found')}function fa(a,b){for(var c=[],d=0;d<a.length;d++)if(0==d)c.push(a[0]);else{var e,f,g;g=d-1;e=0===g?0:g-1;f=g===a.length-1?g:g+1;c[c.length]={x:a[g].x+(a[f].x-a[e].x)/b/3,y:a[g].y+(a[f].y-a[e].y)/b/3};g=d;e=0===g?0:g-1;f=g===a.length-1?g:g+1;c[c.length]={x:a[g].x-(a[f].x-a[e].x)/b/3,y:a[g].y-(a[f].y-a[e].y)/b/3};c[c.length]=a[d]}return c}function aa(a){this._rightOccupied=
-this._leftOccupied=this._bottomOccupied=this._topOccupied=0;this.chart=a}function I(a,b){I.parent.constructor.call(this,"TextBlock",b);this.ctx=a;this._isDirty=!0;this._wrappedText=null;this._lineHeight=ca(this.fontFamily,this.fontSize,this.fontWeight)}function ba(a,b){ba.parent.constructor.call(this,"Title",b,a.theme);this.chart=a;this.canvas=a.canvas;this.ctx=this.chart.ctx;"undefined"===typeof this._options.fontSize&&(this.fontSize=this.chart.getAutoFontSize(this.fontSize));this.height=this.width=
-null;this.bounds={x1:null,y1:null,x2:null,y2:null}}function ga(a,b,c){ga.parent.constructor.call(this,"Legend",b,c);this.chart=a;this.canvas=a.canvas;this.ctx=this.chart.ctx;this.ghostCtx=this.chart._eventManager.ghostCtx;this.items=[];this.height=this.width=0;this.orientation=null;this.horizontalSpacing=10;this.dataSeries=[];this.bounds={x1:null,y1:null,x2:null,y2:null};"undefined"===typeof this._options.fontSize&&(this.fontSize=this.chart.getAutoFontSize(this.fontSize));this.lineHeight=ca(this.fontFamily,
-this.fontSize,this.fontWeight)}function la(a,b){la.parent.constructor.call(this,b);this.chart=a;this.canvas=a.canvas;this.ctx=this.chart.ctx}function P(a,b,c,d,e){P.parent.constructor.call(this,"DataSeries",b,c);this.chart=a;this.canvas=a.canvas;this._ctx=a.canvas.ctx;this.index=d;this.noDataPointsInPlotArea=0;this.id=e;this.chart._eventManager.objectMap[e]={id:e,objectType:"dataSeries",dataSeriesIndex:d};this.dataPointIds=[];this.plotUnit=[];this.axisY=this.axisX=null;null===this.fillOpacity&&(this.type.match(/area/i)?
-this.fillOpacity=0.7:this.fillOpacity=1);this.axisPlacement=this.getDefaultAxisPlacement();"undefined"===typeof this._options.indexLabelFontSize&&(this.indexLabelFontSize=this.chart.getAutoFontSize(this.indexLabelFontSize))}function A(a,b,c,d){A.parent.constructor.call(this,"Axis",b,a.theme);this.chart=a;this.canvas=a.canvas;this.ctx=a.ctx;this.intervalstartTimePercent=this.maxHeight=this.maxWidth=0;this.labels=[];this._labels=null;this.dataInfo={min:Infinity,max:-Infinity,viewPortMin:Infinity,viewPortMax:-Infinity,
-minDiff:Infinity};"axisX"===c?(this.sessionVariables=this.chart.sessionVariables[c],this._options.interval||(this.intervalType=null)):this.sessionVariables="left"===d||"top"===d?this.chart.sessionVariables.axisY:this.chart.sessionVariables.axisY2;"undefined"===typeof this._options.titleFontSize&&(this.titleFontSize=this.chart.getAutoFontSize(this.titleFontSize));"undefined"===typeof this._options.labelFontSize&&(this.labelFontSize=this.chart.getAutoFontSize(this.labelFontSize));this.type=c;"axisX"!==
-c||b&&"undefined"!==typeof b.gridThickness||(this.gridThickness=0);this._position=d;this.lineCoordinates={x1:null,y1:null,x2:null,y2:null,width:null};this.labelAngle=(this.labelAngle%360+360)%360;90<this.labelAngle&&270>=this.labelAngle?this.labelAngle-=180:180<this.labelAngle&&270>=this.labelAngle?this.labelAngle-=180:270<this.labelAngle&&360>=this.labelAngle&&(this.labelAngle-=360);if(this._options.stripLines&&0<this._options.stripLines.length)for(this.stripLines=[],b=0;b<this._options.stripLines.length;b++)this.stripLines.push(new ma(this.chart,
-this._options.stripLines[b],a.theme,++this.chart._eventManager.lastObjectId));this._absoluteMaximum=this._absoluteMinimum=this._titleTextBlock=null;this.hasOptionChanged("minimum")&&(this.sessionVariables.internalMinimum=this.minimum);this.hasOptionChanged("maximum")&&(this.sessionVariables.internalMaximum=this.maximum);this.trackChanges("minimum");this.trackChanges("maximum")}function ma(a,b,c,d){ma.parent.constructor.call(this,"StripLine",b,c);this._thicknessType="pixel";this.id=d;null!==this.startValue&&
-null!==this.endValue&&(this.value=((this.startValue.getTime?this.startValue.getTime():this.startValue)+(this.endValue.getTime?this.endValue.getTime():this.endValue))/2,this.thickness=Math.max(this.endValue-this.startValue),this._thicknessType="value")}function N(a,b,c){N.parent.constructor.call(this,"ToolTip",b,c);this.chart=a;this.canvas=a.canvas;this.ctx=this.chart.ctx;this.currentDataPointIndex=this.currentSeriesIndex=-1;this._timerId=0;this._prevY=this._prevX=NaN;this._initialize()}function $(a){this.chart=
-a;this.lastObjectId=0;this.objectMap=[];this.rectangularRegionEventSubscriptions=[];this.previousDataPointEventObject=null;this.ghostCanvas=U(this.chart.width,this.chart.height);this.ghostCtx=this.ghostCanvas.getContext("2d");this.mouseoveredObjectMaps=[]}function xa(a,b){var c;b&&na[b]&&(c=na[b]);ba.parent.constructor.call(this,"CultureInfo",c,a.theme);this.chart=a;this.canvas=a.canvas;this.ctx=this.chart.ctx}function oa(a){this.chart=a;this.ctx=this.chart.plotArea.ctx;this.animations=[];this.animationRequestId=
-null}var t=!!document.createElement("canvas").getContext,ha={Chart:{width:500,height:400,zoomEnabled:!1,backgroundColor:"white",theme:"theme1",animationEnabled:!1,animationDuration:1200,colorSet:"colorSet1",culture:"en",creditText:"CanvasJS.com",interactivityEnabled:!0,exportEnabled:!1,exportFileName:"Chart"},Title:{padding:0,text:null,verticalAlign:"top",horizontalAlign:"center",fontSize:20,fontFamily:"Calibri",fontWeight:"normal",fontColor:"black",fontStyle:"normal",borderThickness:0,borderColor:"black",
-cornerRadius:0,backgroundColor:null,margin:5},Legend:{name:null,verticalAlign:"center",horizontalAlign:"right",fontSize:14,fontFamily:"calibri",fontWeight:"normal",fontColor:"black",fontStyle:"normal",cursor:null,itemmouseover:null,itemmouseout:null,itemmousemove:null,itemclick:null},ToolTip:{enabled:!0,borderColor:null,shared:!1,animationEnabled:!0,content:null},Axis:{minimum:null,maximum:null,interval:null,intervalType:null,title:null,titleFontColor:"black",titleFontSize:20,titleFontFamily:"arial",
-titleFontWeight:"normal",titleFontStyle:"normal",labelAngle:0,labelFontFamily:"arial",labelFontColor:"black",labelFontSize:12,labelFontWeight:"normal",labelFontStyle:"normal",labelAutoFit:!1,labelWrap:!0,labelMaxWidth:null,prefix:"",suffix:"",includeZero:!0,tickLength:5,tickColor:"black",tickThickness:1,lineColor:"black",lineThickness:1,gridColor:"A0A0A0",gridThickness:0,interlacedColor:null,valueFormatString:null,margin:2,stripLines:[]},StripLine:{value:null,startValue:null,endValue:null,color:"orange",
-thickness:2,label:"",labelBackgroundColor:"#EEEEEE",labelFontFamily:"arial",labelFontColor:"orange",labelFontSize:12,labelFontWeight:"normal",labelFontStyle:"normal"},DataSeries:{name:null,dataPoints:null,label:"",bevelEnabled:!1,cursor:null,indexLabel:"",indexLabelPlacement:"auto",indexLabelOrientation:"horizontal",indexLabelFontColor:"black",indexLabelFontSize:12,indexLabelFontStyle:"normal",indexLabelFontFamily:"Arial",indexLabelFontWeight:"normal",indexLabelBackgroundColor:null,indexLabelLineColor:null,
-indexLabelLineThickness:1,indexLabelMaxWidth:null,indexLabelWrap:!0,lineThickness:2,color:null,risingColor:"white",fillOpacity:null,startAngle:0,type:"column",xValueType:"number",axisYType:"primary",xValueFormatString:null,yValueFormatString:null,zValueFormatString:null,percentFormatString:null,showInLegend:null,legendMarkerType:null,legendMarkerColor:null,legendText:null,legendMarkerBorderColor:null,legendMarkerBorderThickness:null,markerType:"circle",markerColor:null,markerSize:null,markerBorderColor:null,
-markerBorderThickness:null,mouseover:null,mouseout:null,mousemove:null,click:null,toolTipContent:null,visible:!0},CultureInfo:{decimalSeparator:".",digitGroupSeparator:",",zoomText:"Zoom",panText:"Pan",resetText:"Reset",menuText:"More Options",saveJPGText:"Save as JPG",savePNGText:"Save as PNG",days:"Sunday Monday Tuesday Wednesday Thursday Friday Saturday".split(" "),shortDays:"Sun Mon Tue Wed Thu Fri Sat".split(" "),months:"January February March April May June July August September October November December".split(" "),
-shortMonths:"Jan Feb Mar Apr May Jun Jul Aug Sep Oct Nov Dec".split(" ")},TextBlock:{x:0,y:0,width:null,height:null,maxWidth:null,maxHeight:null,padding:0,angle:0,text:"",horizontalAlign:"center",fontSize:12,fontFamily:"calibri",fontWeight:"normal",fontColor:"black",fontStyle:"normal",borderThickness:0,borderColor:"black",cornerRadius:0,backgroundColor:null,textBaseline:"top"}},na={en:{}},V={colorSet1:"#369EAD #C24642 #7F6084 #86B402 #A2D1CF #C8B631 #6DBCEB #52514E #4F81BC #A064A1 #F79647".split(" "),
-colorSet2:"#4F81BC #C0504E #9BBB58 #23BFAA #8064A1 #4AACC5 #F79647 #33558B".split(" "),colorSet3:"#8CA1BC #36845C #017E82 #8CB9D0 #708C98 #94838D #F08891 #0366A7 #008276 #EE7757 #E5BA3A #F2990B #03557B #782970".split(" ")},W={theme1:{Chart:{colorSet:"colorSet1"},Title:{fontFamily:t?"Calibri, Optima, Candara, Verdana, Geneva, sans-serif":"calibri",fontSize:33,fontColor:"#3A3A3A",fontWeight:"bold",verticalAlign:"top",margin:10},Axis:{titleFontSize:26,titleFontColor:"#666666",titleFontFamily:t?"Calibri, Optima, Candara, Verdana, Geneva, sans-serif":
-"calibri",labelFontFamily:t?"Calibri, Optima, Candara, Verdana, Geneva, sans-serif":"calibri",labelFontSize:18,labelFontColor:"grey",tickColor:"#BBBBBB",tickThickness:2,gridThickness:2,gridColor:"#BBBBBB",lineThickness:2,lineColor:"#BBBBBB"},Legend:{verticalAlign:"bottom",horizontalAlign:"center",fontFamily:t?"monospace, sans-serif,arial black":"calibri"},DataSeries:{indexLabelFontColor:"grey",indexLabelFontFamily:t?"Calibri, Optima, Candara, Verdana, Geneva, sans-serif":"calibri",indexLabelFontSize:18,
-indexLabelLineThickness:1}},theme2:{Chart:{colorSet:"colorSet2"},Title:{fontFamily:"impact, charcoal, arial black, sans-serif",fontSize:32,fontColor:"#333333",verticalAlign:"top",margin:10},Axis:{titleFontSize:22,titleFontColor:"rgb(98,98,98)",titleFontFamily:t?"monospace, sans-serif,arial black":"arial",titleFontWeight:"bold",labelFontFamily:t?"monospace, Courier New, Courier":"arial",labelFontSize:16,labelFontColor:"grey",labelFontWeight:"bold",tickColor:"grey",tickThickness:2,gridThickness:2,gridColor:"grey",
-lineThickness:0},Legend:{verticalAlign:"bottom",horizontalAlign:"center",fontFamily:t?"monospace, sans-serif,arial black":"arial"},DataSeries:{indexLabelFontColor:"grey",indexLabelFontFamily:t?"Courier New, Courier, monospace":"arial",indexLabelFontWeight:"bold",indexLabelFontSize:18,indexLabelLineThickness:1}},theme3:{Chart:{colorSet:"colorSet1"},Title:{fontFamily:t?"Candara, Optima, Trebuchet MS, Helvetica Neue, Helvetica, Trebuchet MS, serif":"calibri",fontSize:32,fontColor:"#3A3A3A",fontWeight:"bold",
-verticalAlign:"top",margin:10},Axis:{titleFontSize:22,titleFontColor:"rgb(98,98,98)",titleFontFamily:t?"Verdana, Geneva, Calibri, sans-serif":"calibri",labelFontFamily:t?"Calibri, Optima, Candara, Verdana, Geneva, sans-serif":"calibri",labelFontSize:18,labelFontColor:"grey",tickColor:"grey",tickThickness:2,gridThickness:2,gridColor:"grey",lineThickness:2,lineColor:"grey"},Legend:{verticalAlign:"bottom",horizontalAlign:"center",fontFamily:t?"monospace, sans-serif,arial black":"calibri"},DataSeries:{bevelEnabled:!0,
-indexLabelFontColor:"grey",indexLabelFontFamily:t?"Candara, Optima, Calibri, Verdana, Geneva, sans-serif":"calibri",indexLabelFontSize:18,indexLabelLineColor:"lightgrey",indexLabelLineThickness:2}}},z={numberDuration:1,yearDuration:314496E5,monthDuration:2592E6,weekDuration:6048E5,dayDuration:864E5,hourDuration:36E5,minuteDuration:6E4,secondDuration:1E3,millisecondDuration:1,dayOfWeekFromInt:"Sunday Monday Tuesday Wednesday Thursday Friday Saturday".split(" ")},sa={},R=null,ya=function(){var a=/D{1,4}|M{1,4}|Y{1,4}|h{1,2}|H{1,2}|m{1,2}|s{1,2}|f{1,3}|t{1,2}|T{1,2}|K|z{1,3}|"[^"]*"|'[^']*'/g,
-b="Sunday Monday Tuesday Wednesday Thursday Friday Saturday".split(" "),c="Sun Mon Tue Wed Thu Fri Sat".split(" "),d="January February March April May June July August September October November December".split(" "),e="Jan Feb Mar Apr May Jun Jul Aug Sep Oct Nov Dec".split(" "),f=/\b(?:[PMCEA][SDP]T|(?:Pacific|Mountain|Central|Eastern|Atlantic) (?:Standard|Daylight|Prevailing) Time|(?:GMT|UTC)(?:[-+]\d{4})?)\b/g,g=/[^-+\dA-Z]/g;return function(k,p,h){var l=h?h.days:b,r=h?h.months:d,m=h?h.shortDays:
-c,q=h?h.shortMonths:e;h="";var n=!1;k=k&&k.getTime?k:k?new Date(k):new Date;if(isNaN(k))throw SyntaxError("invalid date");"UTC:"===p.slice(0,4)&&(p=p.slice(4),n=!0);h=n?"getUTC":"get";var s=k[h+"Date"](),t=k[h+"Day"](),u=k[h+"Month"](),x=k[h+"FullYear"](),w=k[h+"Hours"](),Q=k[h+"Minutes"](),G=k[h+"Seconds"](),v=k[h+"Milliseconds"](),y=n?0:k.getTimezoneOffset();return h=p.replace(a,function(a){switch(a){case "D":return s;case "DD":return K(s,2);case "DDD":return m[t];case "DDDD":return l[t];case "M":return u+
-1;case "MM":return K(u+1,2);case "MMM":return q[u];case "MMMM":return r[u];case "Y":return parseInt(String(x).slice(-2));case "YY":return K(String(x).slice(-2),2);case "YYY":return K(String(x).slice(-3),3);case "YYYY":return K(x,4);case "h":return w%12||12;case "hh":return K(w%12||12,2);case "H":return w;case "HH":return K(w,2);case "m":return Q;case "mm":return K(Q,2);case "s":return G;case "ss":return K(G,2);case "f":return String(v).slice(0,1);case "ff":return K(String(v).slice(0,2),2);case "fff":return K(String(v).slice(0,
-3),3);case "t":return 12>w?"a":"p";case "tt":return 12>w?"am":"pm";case "T":return 12>w?"A":"P";case "TT":return 12>w?"AM":"PM";case "K":return n?"UTC":(String(k).match(f)||[""]).pop().replace(g,"");case "z":return(0<y?"-":"+")+Math.floor(Math.abs(y)/60);case "zz":return(0<y?"-":"+")+K(Math.floor(Math.abs(y)/60),2);case "zzz":return(0<y?"-":"+")+K(Math.floor(Math.abs(y)/60),2)+K(Math.abs(y)%60,2);default:return a.slice(1,a.length-1)}})}}(),X=function(a,b,c){if(null===a)return"";a=Number(a);var d=
-0>a?!0:!1;d&&(a*=-1);var e=c?c.decimalSeparator:".",f=c?c.digitGroupSeparator:",",g="";b=String(b);var g=1,k=c="",p=-1,h=[],l=[],r=0,m=0,q=0,n=!1,s=0,k=b.match(/"[^"]*"|'[^']*'|[eE][+-]*[0]+|[,]+[.]|\u2030|./g);b=null;for(var t=0;k&&t<k.length;t++)if(b=k[t],"."===b&&0>p)p=t;else{if("%"===b)g*=100;else if("\u2030"===b){g*=1E3;continue}else if(","===b[0]&&"."===b[b.length-1]){g/=Math.pow(1E3,b.length-1);p=t+b.length-1;continue}else"E"!==b[0]&&"e"!==b[0]||"0"!==b[b.length-1]||(n=!0);0>p?(h.push(b),"#"===
-b||"0"===b?r++:","===b&&q++):(l.push(b),"#"!==b&&"0"!==b||m++)}n&&(b=Math.floor(a),s=(0===b?"":String(b)).length-r,g/=Math.pow(10,s));0>p&&(p=t);g=(a*g).toFixed(m);b=g.split(".");g=(b[0]+"").split("");a=(b[1]+"").split("");g&&"0"===g[0]&&g.shift();for(t=n=k=m=p=0;0<h.length;)if(b=h.pop(),"#"===b||"0"===b)if(p++,p===r){var u=g,g=[];if("0"===b)for(b=r-m-(u?u.length:0);0<b;)u.unshift("0"),b--;for(;0<u.length;)c=u.pop()+c,t++,0===t%n&&(k===q&&0<u.length)&&(c=f+c);d&&(c="-"+c)}else 0<g.length?(c=g.pop()+
-c,m++,t++):"0"===b&&(c="0"+c,m++,t++),0===t%n&&(k===q&&0<g.length)&&(c=f+c);else"E"!==b[0]&&"e"!==b[0]||"0"!==b[b.length-1]||!/[eE][+-]*[0]+/.test(b)?","===b?(k++,n=t,t=0,0<g.length&&(c=f+c)):c=1<b.length&&('"'===b[0]&&'"'===b[b.length-1]||"'"===b[0]&&"'"===b[b.length-1])?b.slice(1,b.length-1)+c:b+c:(b=0>s?b.replace("+","").replace("-",""):b.replace("-",""),c+=b.replace(/[0]+/,function(a){return K(s,a.length)}));d="";for(f=!1;0<l.length;)b=l.shift(),"#"===b||"0"===b?0<a.length&&0!==Number(a.join(""))?
-(d+=a.shift(),f=!0):"0"===b&&(d+="0",f=!0):1<b.length&&('"'===b[0]&&'"'===b[b.length-1]||"'"===b[0]&&"'"===b[b.length-1])?d+=b.slice(1,b.length-1):"E"!==b[0]&&"e"!==b[0]||"0"!==b[b.length-1]||!/[eE][+-]*[0]+/.test(b)?d+=b:(b=0>s?b.replace("+","").replace("-",""):b.replace("-",""),d+=b.replace(/[0]+/,function(a){return K(s,a.length)}));return c+((f?e:"")+d)},ia=function(a){var b=0,c=0;a=a||window.event;a.offsetX||0===a.offsetX?(b=a.offsetX,c=a.offsetY):a.layerX||0==a.layerX?(b=a.layerX,c=a.layerY):
-(b=a.pageX-a.target.offsetLeft,c=a.pageY-a.target.offsetTop);return{x:b,y:c}},va=!0,ja=window.devicePixelRatio||1,ea=1,H=va?ja/ea:1,Da={reset:{image:"data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACAAAAAcCAYAAAAAwr0iAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAABx0RVh0U29mdHdhcmUAQWRvYmUgRmlyZXdvcmtzIENTNui8sowAAAKRSURBVEiJrdY/iF1FFMfxzwnZrGISUSR/JLGIhoh/QiRNBLWxMLIWEkwbgiAoFgoW2mhlY6dgpY2IlRBRxBSKhSAKIklWJRYuMZKAhiyopAiaTY7FvRtmZ+/ed9/zHRjezLw5v/O9d86cuZGZpmURAfdn5o9DfdZNLXpjz+LziPgyIl6MiG0jPTJzZBuyDrP4BVm0P/AKbljTb4ToY/gGewYA7KyCl+1b3DUYANvwbiHw0gCAGRzBOzjTAXEOu0cC4Ch+r5x/HrpdrcZmvIDFSucMtnYCYC++6HmNDw8FKDT34ETrf639/azOr5vwRk/g5fbeuABtgC04XWk9VQLciMP4EH/3AFzErRNC7MXlQmsesSoHsGPE23hmEoBW+61K66HMXFmIMvN8myilXS36R01ub+KfYvw43ZXwYDX+AHP4BAci4pFJomfmr/ihmNofESsBImJGk7mlncrM45n5JPbhz0kAWpsv+juxaX21YIPmVJS2uNzJMS6ZNexC0d+I7fUWXLFyz2kSZlpWPvASlmqAf/FXNXf3FAF2F/1LuFifAlionB6dRuSI2IwHi6lzmXmp6xR8XY0fiIh7psAwh+3FuDkRHQVjl+a8lkXjo0kLUKH7XaV5oO86PmZ1FTzyP4K/XGl9v/zwfbW7BriiuETGCP5ch9bc9f97HF/vcFzCa5gdEPgWq+t/4v0V63oE1uF4h0DiFJ7HnSWMppDdh1dxtsPvJ2wcBNAKbsJXa0Ck5opdaBPsRNu/usba09i1KsaAVzmLt3sghrRjuK1Tf4xkegInxwy8gKf7dKMVH2QRsV5zXR/Cftyu+aKaKbbkQrsdH+PTzLzcqzkOQAVzM+7FHdiqqe2/YT4zF/t8S/sPmawyvC974vcAAAAASUVORK5CYII="},
-pan:{image:"data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACAAAAAgCAYAAABzenr0AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAALEgAACxIB0t1+/AAAABx0RVh0U29mdHdhcmUAQWRvYmUgRmlyZXdvcmtzIENTNui8sowAAAJVSURBVFiFvZe7a1RBGMV/x2hWI4JpfKCIiSBKOoOCkID/wP4BFqIIFkE02ChIiC8QDKlSiI3YqRBsBVGwUNAUdiIEUgjiAzQIIsuKJsfizsXr5t7d+8jmwLDfzHz3nLOzc7+ZxTZlGyDgZiWOCuJ9wH2gCUyuqQFgF/AGcKJNrYkBYBj40CIet+muGQi/96kM4WS7C/Tm5VUg7whJg8BkEGkCR4BDYfodsADUgP6wErO5iCtswsuJb32hdbXy8qzL5TIdmzJinHdZoZIBZcSFkGlAKs1Z3YCketZcBtouuaQNkrblMiBpBrhme7mAgU4wMCvpcFsDkq4C54DFVRTH9h+i6vlE0r5UA5ImgCuh28jB28iIs7BIVCOeStoZD64P4uPAjUTygKSx2FsK2TIwkugfk9Qkfd/E+yMWHQCeSRqx/R3gOp3LazfaS2C4B5gHDgD7U9x3E3uAH7KNpC3AHHAwTL4FHgM9GQ8vAaPA0dB/Abxqk2/gBLA9MXba9r1k/d4LfA3JtwueBeM58ucS+edXnAW23wP10N3advEi9CXizTnyN4bPS7Zn4sH/dq3t18AY4e1YLYSy3g/csj2VnFshZPuOpOeSKHCodUINuGj7YetE6je1PV9QoNPJ9StNHKodx7nRbiWrGHBGXAi5DUiqtQwtpcWK0Jubt8CltA5MEV1IfwO7+VffPwGfia5m34CT4bXujIIX0Qna1/cGMNqV/wUJE2czxD8CQ4X5Sl7Jz7SILwCDpbjKPBRMHAd+EtX4HWV5Spdc2w8kDQGPbH8py/MXMygM69/FKz4AAAAASUVORK5CYII="},
-zoom:{image:"data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAACAAAAAgCAYAAABzenr0AAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAAK6wAACusBgosNWgAAABx0RVh0U29mdHdhcmUAQWRvYmUgRmlyZXdvcmtzIENTNui8sowAAAMqSURBVFiFvdfbj91TFMDxz57U6GUEMS1aYzyMtCSSDhWjCZMInpAI3khE/QHtgzdRkXgSCS8SES9epKLi0oRKNETjRahREq2KS1stdRujtDPtbA97n5zdn9+5zJxTK9k5v3POXmt991p7r71+IcaoGwkhTOIebMRqzOBTvIG3Y4zTXRmqSoyx5cAKbMJOHMFJnMZ8/jyFaXyMR7G6nb1aH22cP4BvcBxziG3GKfyTIR9D6BYg1KUghPBCDveFlb/24Av8iuUYw41YVsz5G7uxKcZ4aMEpwGt5NY3V/YbHsQ6rcAHOw/kYxigewr5CZw4fYGxBKcCLOFEYehXrMdRhr5yLETxVScsOLOkKAPfn1TYMPIvLFrShUlS2FDZm8XRHACzFAWl3R2xbqPMCYhmeLCAOYEMngAczbcTvuHYxzguIy/FesR9e6gSwU/OoPYHBHgHgviIKX2Flq7k34KhmcVnbi/PC8JX4MgMcxb118wZwdz5aISscqx7VRcox7MrPQ7i+btIAJrAkf9+bI9EPmZY2IAxiTSuAldLq4Y9+AcSUh78KP0tbAcwU35cXMD1JCIFUoGiehlqAz6TNB1f1C0DK+0h+nsNPrQC2a4bqGmlD9kOGcWt+Po6pVgDvSxfJaSkFd4UQBvoAsBYbCoB3a2flM7slA0R8iyt6rAFDeDPbm8eOTpVwGD9qVq7nLbIaZnmksPU1JtsCZMXNmpdRxFasWITzh6Xj3LCzra1OxcD2QjHiGVzdpfORnMqZio2PcF23ABdJF1Np4BPptlyPi6WzPYBzpJZtHe7A6xW9cnyP8TqA//SEIYRL8Bxul7rihvwgtVn78WcGGZXa9HGd5TDujDHuOePXNiHdKjWgZX/YbsxLx/ktqbjVzTlcjUSnvI5JrdlUVp6WesZZ6R1hRrpq9+EVTGS9jTjYAuKIouGpbcurEkIYxC051KNSamazsc+xK8b4S0VnEi/j0hqTP+M27O258egQwZuzs7pI7Mf4WQXIEDc5s9sux+5+1Py2EmP8UOq6GvWhIScxfdYjUERiAt9Jd84J6a16zf8JEKT3yCm8g1UxRv8CC4pyRhzR1uUAAAAASUVORK5CYII="},
-menu:{image:"data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAgCAYAAAAbifjMAAAABHNCSVQICAgIfAhkiAAAAAlwSFlzAAAK6wAACusBgosNWgAAABx0RVh0U29mdHdhcmUAQWRvYmUgRmlyZXdvcmtzIENTNui8sowAAAAWdEVYdENyZWF0aW9uIFRpbWUAMDcvMTUvMTTPsvU0AAAAP0lEQVRIie2SMQoAIBDDUvH/X667g8sJJ9KOhYYOkW0qGaU1MPdC0vGSbV19EACo3YMPAFH5BUBUjsqfAPpVXtNgGDfxEDCtAAAAAElFTkSuQmCC"}};L.prototype.setOptions=function(a,b){if(ha[this._defaultsKey]){var c=ha[this._defaultsKey],d;for(d in c)this[d]=a&&d in a?a[d]:b&&d in b?b[d]:c[d]}};L.prototype.updateOption=
-function(a){var b=ha[this._defaultsKey],c=this._options.theme?this._options.theme:this.chart&&this.chart._options.theme?this.chart._options.theme:"theme1",d={},e=this[a];c&&(W[c]&&W[c][this._defaultsKey])&&(d=W[c][this._defaultsKey]);a in b&&(e=a in this._options?this._options[a]:d&&a in d?d[a]:b[a]);if(e===this[a])return!1;this[a]=e;return!0};L.prototype.trackChanges=function(a){this._options._oldOptions||(this._options._oldOptions={});this._options._oldOptions[a]=this._options[a]};L.prototype.isBeingTracked=
-function(a){this._options._oldOptions||(this._options._oldOptions={});return this._options._oldOptions[a]?!0:!1};L.prototype.hasOptionChanged=function(a){this._options._oldOptions||(this._options._oldOptions={});return this._options._oldOptions[a]!==this._options[a]};O(v,L);v.prototype._updateOptions=function(){var a=this;this.updateOption("width");this.updateOption("height");this.updateOption("theme");this.updateOption("colorSet")&&(this._selectedColorSet="undefined"!==typeof V[this.colorSet]?V[this.colorSet]:
-V.colorSet1);this.updateOption("backgroundColor");this.backgroundColor||(this.backgroundColor="rgba(0,0,0,0)");this.updateOption("culture");this._cultureInfo=new xa(this,this._options.culture);this.updateOption("animationEnabled");this.animationEnabled=this.animationEnabled&&t;this._options.zoomEnabled?(this._zoomButton||(S(this._zoomButton=document.createElement("button")),M(this,this._zoomButton,"pan"),this._toolBar.appendChild(this._zoomButton),E(this._zoomButton,"click",function(){a.zoomEnabled?
-(a.zoomEnabled=!1,a.panEnabled=!0,M(a,a._zoomButton,"zoom")):(a.zoomEnabled=!0,a.panEnabled=!1,M(a,a._zoomButton,"pan"));a.render()})),this._resetButton||(S(this._resetButton=document.createElement("button")),M(this,this._resetButton,"reset"),this._toolBar.appendChild(this._resetButton),E(this._resetButton,"click",function(){a._toolTip.hide();a.zoomEnabled||a.panEnabled?(a.zoomEnabled=!0,a.panEnabled=!1,M(a,a._zoomButton,"pan"),a._defaultCursor="default",a.overlaidCanvas.style.cursor=a._defaultCursor):
-(a.zoomEnabled=!1,a.panEnabled=!1);a.sessionVariables.axisX.internalMinimum=a._options.axisX&&a._options.axisX.minimum?a._options.axisX.minimum:null;a.sessionVariables.axisX.internalMaximum=a._options.axisX&&a._options.axisX.maximum?a._options.axisX.maximum:null;a.resetOverlayedCanvas();S(a._zoomButton,a._resetButton);a.render()}),this.overlaidCanvas.style.cursor=a._defaultCursor),this.zoomEnabled||this.panEnabled||(this._zoomButton?(a._zoomButton.getAttribute("state")===a._cultureInfo.zoomText?(this.panEnabled=
-!0,this.zoomEnabled=!1):(this.zoomEnabled=!0,this.panEnabled=!1),ka(a._zoomButton,a._resetButton)):(this.zoomEnabled=!0,this.panEnabled=!1))):this.panEnabled=this.zoomEnabled=!1;"undefined"!==typeof this._options.exportFileName&&(this.exportFileName=this._options.exportFileName);"undefined"!==typeof this._options.exportEnabled&&(this.exportEnabled=this._options.exportEnabled);this._menuButton?this.exportEnabled?ka(this._menuButton):S(this._menuButton):this.exportEnabled&&t&&(this._menuButton=document.createElement("button"),
-M(this,this._menuButton,"menu"),this._toolBar.appendChild(this._menuButton),E(this._menuButton,"click",function(){"none"!==a._dropdownMenu.style.display||a._dropDownCloseTime&&500>=(new Date).getTime()-a._dropDownCloseTime.getTime()||(a._dropdownMenu.style.display="block",a._menuButton.blur(),a._dropdownMenu.focus())},!0));if(!this._dropdownMenu&&this.exportEnabled&&t){this._dropdownMenu=document.createElement("div");this._dropdownMenu.setAttribute("tabindex",-1);this._dropdownMenu.style.cssText=
-"position: absolute; -webkit-user-select: none; -moz-user-select: none; -ms-user-select: none; user-select: none; cursor: pointer;right: 1px;top: 25px;min-width: 120px;outline: 0;border: 1px solid silver;font-size: 14px;font-family: Calibri, Verdana, sans-serif;padding: 5px 0px 5px 0px;text-align: left;background-color: #fff;line-height: 20px;box-shadow: 2px 2px 10px #888888;";a._dropdownMenu.style.display="none";this._toolBar.appendChild(this._dropdownMenu);E(this._dropdownMenu,"blur",function(){S(a._dropdownMenu);
-a._dropDownCloseTime=new Date},!0);var b=document.createElement("div");b.style.cssText="padding: 2px 15px 2px 10px";b.innerHTML=this._cultureInfo.saveJPGText;this._dropdownMenu.appendChild(b);E(b,"mouseover",function(){this.style.backgroundColor="#EEEEEE"},!0);E(b,"mouseout",function(){this.style.backgroundColor="transparent"},!0);E(b,"click",function(){wa(a.canvas,"jpg",a.exportFileName);S(a._dropdownMenu)},!0);b=document.createElement("div");b.style.cssText="padding: 2px 15px 2px 10px";b.innerHTML=
-this._cultureInfo.savePNGText;this._dropdownMenu.appendChild(b);E(b,"mouseover",function(){this.style.backgroundColor="#EEEEEE"},!0);E(b,"mouseout",function(){this.style.backgroundColor="transparent"},!0);E(b,"click",function(){wa(a.canvas,"png",a.exportFileName);S(a._dropdownMenu)},!0)}"none"!==this._toolBar.style.display&&this._zoomButton&&(this.panEnabled?M(a,a._zoomButton,"zoom"):M(a,a._zoomButton,"pan"),a._resetButton.getAttribute("state")!==a._cultureInfo.resetText&&M(a,a._resetButton,"reset"));
-if("undefined"===typeof ha.Chart.creditHref)this.creditHref="http://canvasjs.com/",this.creditText="CanvasJS.com";else var c=this.updateOption("creditText"),d=this.updateOption("creditHref");if(0===this.renderCount||c||d)this._creditLink.setAttribute("href",this.creditHref),this._creditLink.innerHTML=this.creditText;this.creditHref&&this.creditText?this._creditLink.parentElement||this._canvasJSContainer.appendChild(this._creditLink):this._creditLink.parentElement&&this._canvasJSContainer.removeChild(this._creditLink);
-this._options.toolTip&&this._toolTip._options!==this._options.toolTip&&(this._toolTip._options=this._options.toolTip);this._toolTip.updateOption("enabled");this._toolTip.updateOption("shared");this._toolTip.updateOption("animationEnabled");this._toolTip.updateOption("borderColor");this._toolTip.updateOption("content")};v.prototype._updateSize=function(){var a=0,b=0;this._options.width?a=this.width:this.width=a=0<this._container.clientWidth?this._container.clientWidth:this.width;this._options.height?
-b=this.height:this.height=b=0<this._container.clientHeight?this._container.clientHeight:this.height;return this.canvas.width!==a*H||this.canvas.height!==b*H?(da(this.canvas,a,b),da(this.overlaidCanvas,a,b),da(this._eventManager.ghostCanvas,a,b),!0):!1};v.prototype._initialize=function(){this._animator?this._animator.cancelAllAnimations():this._animator=new oa(this);this.disableToolTip=!1;this.pieDoughnutClickHandler=null;this.animationRequestId&&this.cancelRequestAnimFrame.call(window,this.animationRequestId);
-this._updateOptions();this.animatedRender=t&&this.animationEnabled&&0===this.renderCount;this._updateSize();this.clearCanvas();this.ctx.beginPath();this.axisY2=this.axisY=this.axisX=null;this._indexLabels=[];this._dataInRenderedOrder=[];this._events=[];this._eventManager&&this._eventManager.reset();this.plotInfo={axisPlacement:null,axisXValueType:null,plotTypes:[]};this.layoutManager.reset();this.data=[];for(var a=0,b=0;b<this._options.data.length;b++)if(a++,!this._options.data[b].type||0<=v._supportedChartTypes.indexOf(this._options.data[b].type)){var c=
-new P(this,this._options.data[b],this.theme,a-1,++this._eventManager.lastObjectId);null===c.name&&(c.name="DataSeries "+a);null===c.color?1<this._options.data.length?(c._colorSet=[this._selectedColorSet[c.index%this._selectedColorSet.length]],c.color=this._selectedColorSet[c.index%this._selectedColorSet.length]):c._colorSet="line"===c.type||"stepLine"===c.type||"spline"===c.type||"area"===c.type||"stepArea"===c.type||"splineArea"===c.type||"stackedArea"===c.type||"stackedArea100"===c.type||"rangeArea"===
-c.type||"rangeSplineArea"===c.type||"candlestick"===c.type||"ohlc"===c.type?[this._selectedColorSet[0]]:this._selectedColorSet:c._colorSet=[c.color];null===c.markerSize&&(("line"===c.type||"stepLine"===c.type||"spline"===c.type)&&c.dataPoints&&c.dataPoints.length<this.width/16||"scatter"===c.type)&&(c.markerSize=8);"bubble"!==c.type&&"scatter"!==c.type||!c.dataPoints||c.dataPoints.sort(Ca);this.data.push(c);var d=c.axisPlacement,e;"normal"===d?"xySwapped"===this.plotInfo.axisPlacement?e='You cannot combine "'+
-c.type+'" with bar chart':"none"===this.plotInfo.axisPlacement?e='You cannot combine "'+c.type+'" with pie chart':null===this.plotInfo.axisPlacement&&(this.plotInfo.axisPlacement="normal"):"xySwapped"===d?"normal"===this.plotInfo.axisPlacement?e='You cannot combine "'+c.type+'" with line, area, column or pie chart':"none"===this.plotInfo.axisPlacement?e='You cannot combine "'+c.type+'" with pie chart':null===this.plotInfo.axisPlacement&&(this.plotInfo.axisPlacement="xySwapped"):"none"==d&&("normal"===
-this.plotInfo.axisPlacement?e='You cannot combine "'+c.type+'" with line, area, column or bar chart':"xySwapped"===this.plotInfo.axisPlacement?e='You cannot combine "'+c.type+'" with bar chart':null===this.plotInfo.axisPlacement&&(this.plotInfo.axisPlacement="none"));if(e&&window.console){window.console.log(e);return}}this._objectsInitialized=!0};v._supportedChartTypes="line stepLine spline column area stepArea splineArea bar bubble scatter stackedColumn stackedColumn100 stackedBar stackedBar100 stackedArea stackedArea100 candlestick ohlc rangeColumn rangeBar rangeArea rangeSplineArea pie doughnut funnel".split(" ");
-v._supportedChartTypes.indexOf||(v._supportedChartTypes.indexOf=function(a,b){var c=this.length>>>0,d=Number(b)||0,d=0>d?Math.ceil(d):Math.floor(d);for(0>d&&(d+=c);d<c;d++)if(d in this&&this[d]===a)return d;return-1});v.prototype.render=function(a){a&&(this._options=a);this._initialize();for(a=0;a<this.data.length;a++)if("normal"===this.plotInfo.axisPlacement||"xySwapped"===this.plotInfo.axisPlacement)this.data[a].axisYType&&"primary"!==this.data[a].axisYType?"secondary"===this.data[a].axisYType&&
-(this.axisY2||("normal"===this.plotInfo.axisPlacement?this.axisY2=new A(this,this._options.axisY2,"axisY","right"):"xySwapped"===this.plotInfo.axisPlacement&&(this.axisY2=new A(this,this._options.axisY2,"axisY","top"))),this.data[a].axisY=this.axisY2):(this.axisY||("normal"===this.plotInfo.axisPlacement?this.axisY=new A(this,this._options.axisY,"axisY","left"):"xySwapped"===this.plotInfo.axisPlacement&&(this.axisY=new A(this,this._options.axisY,"axisY","bottom"))),this.data[a].axisY=this.axisY),this.axisX||
-("normal"===this.plotInfo.axisPlacement?this.axisX=new A(this,this._options.axisX,"axisX","bottom"):"xySwapped"===this.plotInfo.axisPlacement&&(this.axisX=new A(this,this._options.axisX,"axisX","left"))),this.data[a].axisX=this.axisX;this._processData();this._options.title&&(this._title=new ba(this,this._options.title),this._title.render());this.legend=new ga(this,this._options.legend,this.theme);for(a=0;a<this.data.length;a++)this.data[a].showInLegend&&this.legend.dataSeries.push(this.data[a]);this.legend.render();
-if("normal"===this.plotInfo.axisPlacement||"xySwapped"===this.plotInfo.axisPlacement)this.layoutManager.getFreeSpace(),A.setLayoutAndRender(this.axisX,this.axisY,this.axisY2,this.plotInfo.axisPlacement,this.layoutManager.getFreeSpace());else if("none"===this.plotInfo.axisPlacement)this.preparePlotArea();else return;var b=[];if(this.animatedRender){var c=U(this.width,this.height);c.getContext("2d").drawImage(this.canvas,0,0,this.width,this.height)}for(a=0;a<this.plotInfo.plotTypes.length;a++)for(var d=
-this.plotInfo.plotTypes[a],e=0;e<d.plotUnits.length;e++){var f=d.plotUnits[e],g=null;f.targetCanvas=null;this.animatedRender&&(f.targetCanvas=U(this.width,this.height),f.targetCanvasCtx=f.targetCanvas.getContext("2d"));"line"===f.type?g=this.renderLine(f):"stepLine"===f.type?g=this.renderStepLine(f):"spline"===f.type?g=this.renderSpline(f):"column"===f.type?g=this.renderColumn(f):"bar"===f.type?g=this.renderBar(f):"area"===f.type?g=this.renderArea(f):"stepArea"===f.type?g=this.renderStepArea(f):"splineArea"===
-f.type?g=this.renderSplineArea(f):"stackedColumn"===f.type?g=this.renderStackedColumn(f):"stackedColumn100"===f.type?g=this.renderStackedColumn100(f):"stackedBar"===f.type?g=this.renderStackedBar(f):"stackedBar100"===f.type?g=this.renderStackedBar100(f):"stackedArea"===f.type?g=this.renderStackedArea(f):"stackedArea100"===f.type?g=this.renderStackedArea100(f):"bubble"===f.type?g=g=this.renderBubble(f):"scatter"===f.type?g=this.renderScatter(f):"pie"===f.type?this.renderPie(f):"doughnut"===f.type?
-this.renderPie(f):"candlestick"===f.type?g=this.renderCandlestick(f):"ohlc"===f.type?g=this.renderCandlestick(f):"rangeColumn"===f.type?g=this.renderRangeColumn(f):"rangeBar"===f.type?g=this.renderRangeBar(f):"rangeArea"===f.type?g=this.renderRangeArea(f):"rangeSplineArea"===f.type&&(g=this.renderRangeSplineArea(f));for(var k=0;k<f.dataSeriesIndexes.length;k++)this._dataInRenderedOrder.push(this.data[f.dataSeriesIndexes[k]]);this.animatedRender&&g&&b.push(g)}this.animatedRender&&0<this._indexLabels.length&&
-(a=U(this.width,this.height).getContext("2d"),b.push(this.renderIndexLabels(a)));var p=this;0<b.length?(p.disableToolTip=!0,p._animator.animate(200,p.animationDuration,function(a){p.ctx.clearRect(0,0,p.width,p.height);p.ctx.drawImage(c,0,0,p.width*H,p.height*H,0,0,p.width,p.height);for(var d=0;d<b.length;d++)g=b[d],1>a&&"undefined"!==typeof g.startTimePercent?a>=g.startTimePercent&&g.animationCallback(g.easingFunction(a-g.startTimePercent,0,1,1-g.startTimePercent),g):g.animationCallback(g.easingFunction(a,
-0,1,1),g)},function(){b=[];for(var a=0;a<p.plotInfo.plotTypes.length;a++)for(var d=p.plotInfo.plotTypes[a],e=0;e<d.plotUnits.length;e++)d.plotUnits[e].targetCanvas=null;c=null;p.disableToolTip=!1})):0<p._indexLabels.length&&p.renderIndexLabels();this.attachPlotAreaEventHandlers();this.zoomEnabled||(this.panEnabled||!this._zoomButton||"none"===this._zoomButton.style.display)||S(this._zoomButton,this._resetButton);this._toolTip._updateToolTip();this.renderCount++};v.prototype.attachPlotAreaEventHandlers=
-function(){this.attachEvent({context:this,chart:this,mousedown:this._plotAreaMouseDown,mouseup:this._plotAreaMouseUp,mousemove:this._plotAreaMouseMove,cursor:this.zoomEnabled?"col-resize":"move",cursor:this.panEnabled?"move":"default",capture:!0,bounds:this.plotArea})};v.prototype.categoriseDataSeries=function(){for(var a="",b=0;b<this.data.length;b++)if(a=this.data[b],a.dataPoints&&(0!==a.dataPoints.length&&a.visible)&&0<=v._supportedChartTypes.indexOf(a.type)){for(var c=null,d=!1,e=null,f=!1,g=
-0;g<this.plotInfo.plotTypes.length;g++)if(this.plotInfo.plotTypes[g].type===a.type){d=!0;c=this.plotInfo.plotTypes[g];break}d||(c={type:a.type,totalDataSeries:0,plotUnits:[]},this.plotInfo.plotTypes.push(c));for(g=0;g<c.plotUnits.length;g++)if(c.plotUnits[g].axisYType===a.axisYType){f=!0;e=c.plotUnits[g];break}f||(e={type:a.type,previousDataSeriesCount:0,index:c.plotUnits.length,plotType:c,axisYType:a.axisYType,axisY:"primary"===a.axisYType?this.axisY:this.axisY2,axisX:this.axisX,dataSeriesIndexes:[],
-yTotals:[]},c.plotUnits.push(e));c.totalDataSeries++;e.dataSeriesIndexes.push(b);a.plotUnit=e}for(b=0;b<this.plotInfo.plotTypes.length;b++)for(c=this.plotInfo.plotTypes[b],g=a=0;g<c.plotUnits.length;g++)c.plotUnits[g].previousDataSeriesCount=a,a+=c.plotUnits[g].dataSeriesIndexes.length};v.prototype.assignIdToDataPoints=function(){for(var a=0;a<this.data.length;a++){var b=this.data[a];if(b.dataPoints)for(var c=b.dataPoints.length,d=0;d<c;d++)b.dataPointIds[d]=++this._eventManager.lastObjectId}};v.prototype._processData=
-function(){this.assignIdToDataPoints();this.categoriseDataSeries();for(var a=0;a<this.plotInfo.plotTypes.length;a++)for(var b=this.plotInfo.plotTypes[a],c=0;c<b.plotUnits.length;c++){var d=b.plotUnits[c];"line"===d.type||"stepLine"===d.type||"spline"===d.type||"column"===d.type||"area"===d.type||"stepArea"===d.type||"splineArea"===d.type||"bar"===d.type||"bubble"===d.type||"scatter"===d.type?this._processMultiseriesPlotUnit(d):"stackedColumn"===d.type||"stackedBar"===d.type||"stackedArea"===d.type?
-this._processStackedPlotUnit(d):"stackedColumn100"===d.type||"stackedBar100"===d.type||"stackedArea100"===d.type?this._processStacked100PlotUnit(d):"candlestick"!==d.type&&"ohlc"!==d.type&&"rangeColumn"!==d.type&&"rangeBar"!==d.type&&"rangeArea"!==d.type&&"rangeSplineArea"!==d.type||this._processMultiYPlotUnit(d)}};v.prototype._processMultiseriesPlotUnit=function(a){if(a.dataSeriesIndexes&&!(1>a.dataSeriesIndexes.length))for(var b=a.axisY.dataInfo,c=a.axisX.dataInfo,d,e,f=!1,g=0;g<a.dataSeriesIndexes.length;g++){var k=
-this.data[a.dataSeriesIndexes[g]],p=0,h=!1,l=!1;if("normal"===k.axisPlacement||"xySwapped"===k.axisPlacement)var r=this.sessionVariables.axisX.internalMinimum?this.sessionVariables.axisX.internalMinimum:this._options.axisX&&this._options.axisX.minimum?this._options.axisX.minimum:-Infinity,m=this.sessionVariables.axisX.internalMaximum?this.sessionVariables.axisX.internalMaximum:this._options.axisX&&this._options.axisX.maximum?this._options.axisX.maximum:Infinity;if(k.dataPoints[p].x&&k.dataPoints[p].x.getTime||
-"dateTime"===k.xValueType)f=!0;for(p=0;p<k.dataPoints.length;p++){"undefined"===typeof k.dataPoints[p].x&&(k.dataPoints[p].x=p);k.dataPoints[p].x.getTime?(f=!0,d=k.dataPoints[p].x.getTime()):d=k.dataPoints[p].x;e=k.dataPoints[p].y;d<c.min&&(c.min=d);d>c.max&&(c.max=d);e<b.min&&(b.min=e);e>b.max&&(b.max=e);if(0<p){var q=d-k.dataPoints[p-1].x;0>q&&(q*=-1);c.minDiff>q&&0!==q&&(c.minDiff=q)}if(!(d<r)||h){if(!h&&(h=!0,0<p)){p-=2;continue}if(d>m&&!l)l=!0;else if(d>m&&l)continue;k.dataPoints[p].label&&(a.axisX.labels[d]=
-k.dataPoints[p].label);d<c.viewPortMin&&(c.viewPortMin=d);d>c.viewPortMax&&(c.viewPortMax=d);null!==e&&(e<b.viewPortMin&&(b.viewPortMin=e),e>b.viewPortMax&&(b.viewPortMax=e))}}this.plotInfo.axisXValueType=k.xValueType=f?"dateTime":"number"}};v.prototype._processStackedPlotUnit=function(a){if(a.dataSeriesIndexes&&!(1>a.dataSeriesIndexes.length)){for(var b=a.axisY.dataInfo,c=a.axisX.dataInfo,d,e,f=!1,g=[],k=[],p=0;p<a.dataSeriesIndexes.length;p++){var h=this.data[a.dataSeriesIndexes[p]],l=0,r=!1,m=
-!1;if("normal"===h.axisPlacement||"xySwapped"===h.axisPlacement)var q=this.sessionVariables.axisX.internalMinimum?this.sessionVariables.axisX.internalMinimum:this._options.axisX&&this._options.axisX.minimum?this._options.axisX.minimum:-Infinity,n=this.sessionVariables.axisX.internalMaximum?this.sessionVariables.axisX.internalMaximum:this._options.axisX&&this._options.axisX.maximum?this._options.axisX.maximum:Infinity;if(h.dataPoints[l].x&&h.dataPoints[l].x.getTime||"dateTime"===h.xValueType)f=!0;
-for(l=0;l<h.dataPoints.length;l++){"undefined"===typeof h.dataPoints[l].x&&(h.dataPoints[l].x=l);h.dataPoints[l].x.getTime?(f=!0,d=h.dataPoints[l].x.getTime()):d=h.dataPoints[l].x;e=h.dataPoints[l].y;d<c.min&&(c.min=d);d>c.max&&(c.max=d);if(0<l){var s=d-h.dataPoints[l-1].x;0>s&&(s*=-1);c.minDiff>s&&0!==s&&(c.minDiff=s)}if(!(d<q)||r){if(!r&&(r=!0,0<l)){l-=2;continue}if(d>n&&!m)m=!0;else if(d>n&&m)continue;h.dataPoints[l].label&&(a.axisX.labels[d]=h.dataPoints[l].label);d<c.viewPortMin&&(c.viewPortMin=
-d);d>c.viewPortMax&&(c.viewPortMax=d);null!==e&&(a.yTotals[d]=(a.yTotals[d]?a.yTotals[d]:0)+Math.abs(e),0<=e?g[d]=g[d]?g[d]+e:e:k[d]=k[d]?k[d]+e:e)}}this.plotInfo.axisXValueType=h.xValueType=f?"dateTime":"number"}for(l in g)isNaN(l)||(a=g[l],a<b.min&&(b.min=a),a>b.max&&(b.max=a),l<c.viewPortMin||l>c.viewPortMax||(a<b.viewPortMin&&(b.viewPortMin=a),a>b.viewPortMax&&(b.viewPortMax=a)));for(l in k)isNaN(l)||(a=k[l],a<b.min&&(b.min=a),a>b.max&&(b.max=a),l<c.viewPortMin||l>c.viewPortMax||(a<b.viewPortMin&&
-(b.viewPortMin=a),a>b.viewPortMax&&(b.viewPortMax=a)))}};v.prototype._processStacked100PlotUnit=function(a){if(a.dataSeriesIndexes&&!(1>a.dataSeriesIndexes.length)){for(var b=a.axisY.dataInfo,c=a.axisX.dataInfo,d,e,f=!1,g=!1,k=!1,p=[],h=0;h<a.dataSeriesIndexes.length;h++){var l=this.data[a.dataSeriesIndexes[h]],r=0,m=!1,q=!1;if("normal"===l.axisPlacement||"xySwapped"===l.axisPlacement)var n=this.sessionVariables.axisX.internalMinimum?this.sessionVariables.axisX.internalMinimum:this._options.axisX&&
-this._options.axisX.minimum?this._options.axisX.minimum:-Infinity,s=this.sessionVariables.axisX.internalMaximum?this.sessionVariables.axisX.internalMaximum:this._options.axisX&&this._options.axisX.maximum?this._options.axisX.maximum:Infinity;if(l.dataPoints[r].x&&l.dataPoints[r].x.getTime||"dateTime"===l.xValueType)f=!0;for(r=0;r<l.dataPoints.length;r++){"undefined"===typeof l.dataPoints[r].x&&(l.dataPoints[r].x=r);l.dataPoints[r].x.getTime?(f=!0,d=l.dataPoints[r].x.getTime()):d=l.dataPoints[r].x;
-e=l.dataPoints[r].y;d<c.min&&(c.min=d);d>c.max&&(c.max=d);if(0<r){var t=d-l.dataPoints[r-1].x;0>t&&(t*=-1);c.minDiff>t&&0!==t&&(c.minDiff=t)}if(!(d<n)||m){if(!m&&(m=!0,0<r)){r-=2;continue}if(d>s&&!q)q=!0;else if(d>s&&q)continue;l.dataPoints[r].label&&(a.axisX.labels[d]=l.dataPoints[r].label);d<c.viewPortMin&&(c.viewPortMin=d);d>c.viewPortMax&&(c.viewPortMax=d);null!==e&&(a.yTotals[d]=(a.yTotals[d]?a.yTotals[d]:0)+Math.abs(e),0<=e?g=!0:k=!0,p[d]=p[d]?p[d]+Math.abs(e):Math.abs(e))}}this.plotInfo.axisXValueType=
-l.xValueType=f?"dateTime":"number"}g&&!k?(b.max=99,b.min=1):g&&k?(b.max=99,b.min=-99):!g&&k&&(b.max=-1,b.min=-99);b.viewPortMin=b.min;b.viewPortMax=b.max;a.dataPointYSums=p}};v.prototype._processMultiYPlotUnit=function(a){if(a.dataSeriesIndexes&&!(1>a.dataSeriesIndexes.length))for(var b=a.axisY.dataInfo,c=a.axisX.dataInfo,d,e,f,g,k=!1,p=0;p<a.dataSeriesIndexes.length;p++){var h=this.data[a.dataSeriesIndexes[p]],l=0,r=!1,m=!1;if("normal"===h.axisPlacement||"xySwapped"===h.axisPlacement)var q=this.sessionVariables.axisX.internalMinimum?
-this.sessionVariables.axisX.internalMinimum:this._options.axisX&&this._options.axisX.minimum?this._options.axisX.minimum:-Infinity,n=this.sessionVariables.axisX.internalMaximum?this.sessionVariables.axisX.internalMaximum:this._options.axisX&&this._options.axisX.maximum?this._options.axisX.maximum:Infinity;if(h.dataPoints[l].x&&h.dataPoints[l].x.getTime||"dateTime"===h.xValueType)k=!0;for(l=0;l<h.dataPoints.length;l++){"undefined"===typeof h.dataPoints[l].x&&(h.dataPoints[l].x=l);h.dataPoints[l].x.getTime?
-(k=!0,d=h.dataPoints[l].x.getTime()):d=h.dataPoints[l].x;(e=h.dataPoints[l].y)&&e.length&&(f=Math.min.apply(null,e),g=Math.max.apply(null,e));d<c.min&&(c.min=d);d>c.max&&(c.max=d);f<b.min&&(b.min=f);g>b.max&&(b.max=g);if(0<l){var s=d-h.dataPoints[l-1].x;0>s&&(s*=-1);c.minDiff>s&&0!==s&&(c.minDiff=s)}if(!(d<q)||r){if(!r&&(r=!0,0<l)){l-=2;continue}if(d>n&&!m)m=!0;else if(d>n&&m)continue;h.dataPoints[l].label&&(a.axisX.labels[d]=h.dataPoints[l].label);d<c.viewPortMin&&(c.viewPortMin=d);d>c.viewPortMax&&
-(c.viewPortMax=d);null!==e&&(f<b.viewPortMin&&(b.viewPortMin=f),g>b.viewPortMax&&(b.viewPortMax=g))}}this.plotInfo.axisXValueType=h.xValueType=k?"dateTime":"number"}};v.prototype.getDataPointAtXY=function(a,b,c){c=c||!1;for(var d=[],e=this._dataInRenderedOrder.length-1;0<=e;e--){var f=null;(f=this._dataInRenderedOrder[e].getDataPointAtXY(a,b,c))&&d.push(f)}a=null;b=!1;for(c=0;c<d.length;c++)if("line"===d[c].dataSeries.type||"stepLine"===d[c].dataSeries.type||"area"===d[c].dataSeries.type||"stepArea"===
-d[c].dataSeries.type)if(e=T("markerSize",d[c].dataPoint,d[c].dataSeries)||8,d[c].distance<=e/2){b=!0;break}for(c=0;c<d.length;c++)b&&"line"!==d[c].dataSeries.type&&"stepLine"!==d[c].dataSeries.type&&"area"!==d[c].dataSeries.type&&"stepArea"!==d[c].dataSeries.type||(a?d[c].distance<=a.distance&&(a=d[c]):a=d[c]);return a};v.prototype.getObjectAtXY=function(a,b,c){var d=null;if(c=this.getDataPointAtXY(a,b,c||!1))d=c.dataSeries.dataPointIds[c.dataPointIndex];else if(t)d=ta(a,b,this._eventManager.ghostCtx);
-else for(c=0;c<this.legend.items.length;c++){var e=this.legend.items[c];a>=e.x1&&(a<=e.x2&&b>=e.y1&&b<=e.y2)&&(d=e.id)}return d};v.prototype.getAutoFontSize=function(a,b,c){a/=400;return Math.round(Math.min(this.width,this.height)*a)};v.prototype.resetOverlayedCanvas=function(){this.overlaidCanvasCtx.clearRect(0,0,this.width,this.height)};v.prototype.clearCanvas=function(){this.ctx.clearRect(0,0,this.width,this.height);this.backgroundColor&&(this.ctx.fillStyle=this.backgroundColor,this.ctx.fillRect(0,
-0,this.width,this.height))};v.prototype.attachEvent=function(a){this._events.push(a)};v.prototype._touchEventHandler=function(a){if(a.changedTouches&&this.interactivityEnabled){var b=[],c=a.changedTouches,d=c?c[0]:a,e=null;switch(a.type){case "touchstart":case "MSPointerDown":b=["mousemove","mousedown"];this._lastTouchData=ia(d);this._lastTouchData.time=new Date;break;case "touchmove":case "MSPointerMove":b=["mousemove"];break;case "touchend":case "MSPointerUp":b="touchstart"===this._lastTouchEventType||
-"MSPointerDown"===this._lastTouchEventType?["mouseup","click"]:["mouseup"];break;default:return}if(!(c&&1<c.length)){e=ia(d);e.time=new Date;try{var f=e.y-this._lastTouchData.y,g=e.time-this._lastTouchData.time;if(15<Math.abs(f)&&(this._lastTouchData.scroll||200>g)){this._lastTouchData.scroll=!0;var k=window.parent||window;k&&k.scrollBy&&k.scrollBy(0,-f)}}catch(p){}this._lastTouchEventType=a.type;if(this._lastTouchData.scroll&&this.zoomEnabled)this.isDrag&&this.resetOverlayedCanvas(),this.isDrag=
-!1;else for(c=0;c<b.length;c++)e=b[c],f=document.createEvent("MouseEvent"),f.initMouseEvent(e,!0,!0,window,1,d.screenX,d.screenY,d.clientX,d.clientY,!1,!1,!1,!1,0,null),d.target.dispatchEvent(f),a.preventManipulation&&a.preventManipulation(),a.preventDefault&&a.preventDefault()}}};v.prototype._mouseEventHandler=function(a){if(this.interactivityEnabled)if(this._ignoreNextEvent)this._ignoreNextEvent=!1;else{a.preventManipulation&&a.preventManipulation();a.preventDefault&&a.preventDefault();"undefined"===
-typeof a.target&&a.srcElement&&(a.target=a.srcElement);var b=ia(a),c=a.type,d,e;a.which?e=3==a.which:a.button&&(e=2==a.button);if(!e){if(v.capturedEventParam)d=v.capturedEventParam,"mouseup"===c&&(v.capturedEventParam=null,d.chart.overlaidCanvas.releaseCapture?d.chart.overlaidCanvas.releaseCapture():document.body.removeEventListener("mouseup",d.chart._mouseEventHandler,!1)),d.hasOwnProperty(c)&&d[c].call(d.context,b.x,b.y);else if(this._events){for(e=0;e<this._events.length;e++)if(this._events[e].hasOwnProperty(c)){d=
-this._events[e];var f=d.bounds;if(b.x>=f.x1&&b.x<=f.x2&&b.y>=f.y1&&b.y<=f.y2){d[c].call(d.context,b.x,b.y);"mousedown"===c&&!0===d.capture?(v.capturedEventParam=d,this.overlaidCanvas.setCapture?this.overlaidCanvas.setCapture():document.body.addEventListener("mouseup",this._mouseEventHandler,!1)):"mouseup"===c&&(d.chart.overlaidCanvas.releaseCapture?d.chart.overlaidCanvas.releaseCapture():document.body.removeEventListener("mouseup",this._mouseEventHandler,!1));break}else d=null}a.target.style.cursor=
-d&&d.cursor?d.cursor:this._defaultCursor}this._toolTip&&this._toolTip.enabled&&(c=this.plotArea,(b.x<c.x1||b.x>c.x2||b.y<c.y1||b.y>c.y2)&&this._toolTip.hide());this.isDrag&&this.zoomEnabled||!this._eventManager||this._eventManager.mouseEventHandler(a)}}};v.prototype._plotAreaMouseDown=function(a,b){this.isDrag=!0;this.dragStartPoint="none"!==this.plotInfo.axisPlacement?{x:a,y:b,xMinimum:this.axisX.minimum,xMaximum:this.axisX.maximum}:{x:a,y:b}};v.prototype._plotAreaMouseUp=function(a,b){var c,d;if(("normal"===
-this.plotInfo.axisPlacement||"xySwapped"===this.plotInfo.axisPlacement)&&this.isDrag){var e=0,e=this.axisX.lineCoordinates,e="xySwapped"===this.plotInfo.axisPlacement?b-this.dragStartPoint.y:this.dragStartPoint.x-a;Math.abs(this.axisX.maximum-this.axisX.minimum);if(2<Math.abs(e)){if(this.panEnabled)e=!1,d=0,this.axisX.sessionVariables.internalMinimum<this.axisX._absoluteMinimum?(d=this.axisX._absoluteMinimum-this.axisX.sessionVariables.internalMinimum,this.axisX.sessionVariables.internalMinimum+=
-d,this.axisX.sessionVariables.internalMaximum+=d,e=!0):this.axisX.sessionVariables.internalMaximum>this.axisX._absoluteMaximum&&(d=this.axisX.sessionVariables.internalMaximum-this.axisX._absoluteMaximum,this.axisX.sessionVariables.internalMaximum-=d,this.axisX.sessionVariables.internalMinimum-=d,e=!0),e&&this.render();else if(this.zoomEnabled){this.resetOverlayedCanvas();if(!this.dragStartPoint)return;"xySwapped"===this.plotInfo.axisPlacement?(c=Math.min(this.dragStartPoint.y,b),d=Math.max(this.dragStartPoint.y,
-b),1<Math.abs(c-d)&&(e=this.axisX.lineCoordinates,d=this.axisX.maximum-(this.axisX.maximum-this.axisX.minimum)/e.height*(d-e.y1),e=this.axisX.maximum-(this.axisX.maximum-this.axisX.minimum)/e.height*(c-e.y1),d=Math.max(d,this.axisX.dataInfo.min),e=Math.min(e,this.axisX.dataInfo.max),Math.abs(e-d)>2*Math.abs(this.axisX.dataInfo.minDiff)&&(this.axisX.sessionVariables.internalMinimum=d,this.axisX.sessionVariables.internalMaximum=e,this.render()))):"normal"===this.plotInfo.axisPlacement&&(d=Math.min(this.dragStartPoint.x,
-a),c=Math.max(this.dragStartPoint.x,a),1<Math.abs(d-c)&&(e=this.axisX.lineCoordinates,d=(this.axisX.maximum-this.axisX.minimum)/e.width*(d-e.x1)+this.axisX.minimum,e=(this.axisX.maximum-this.axisX.minimum)/e.width*(c-e.x1)+this.axisX.minimum,d=Math.max(d,this.axisX.dataInfo.min),e=Math.min(e,this.axisX.dataInfo.max),Math.abs(e-d)>2*Math.abs(this.axisX.dataInfo.minDiff)&&(this.axisX.sessionVariables.internalMinimum=d,this.axisX.sessionVariables.internalMaximum=e,this.render())))}this._ignoreNextEvent=
-!0;this.zoomEnabled&&"none"===this._zoomButton.style.display&&(ka(this._zoomButton,this._resetButton),M(this,this._zoomButton,"pan"),M(this,this._resetButton,"reset"))}}this.isDrag=!1};v.prototype._plotAreaMouseMove=function(a,b){if(this.isDrag&&"none"!==this.plotInfo.axisPlacement){var c=0,d=0,d=this.axisX.lineCoordinates;"xySwapped"===this.plotInfo.axisPlacement?(c=b-this.dragStartPoint.y,d=Math.abs(this.axisX.maximum-this.axisX.minimum)/d.height*c):(c=this.dragStartPoint.x-a,d=Math.abs(this.axisX.maximum-
-this.axisX.minimum)/d.width*c);2<Math.abs(c)&&8>Math.abs(c)&&(this.panEnabled||this.zoomEnabled)?this._toolTip.hide():!this._toolTip.enabled||(this.panEnabled||this.zoomEnabled)||this._toolTip.mouseMoveHandler(a,b);if(2<Math.abs(c)&&(this.panEnabled||this.zoomEnabled))if(this.panEnabled){this.axisX.sessionVariables.internalMinimum=this.dragStartPoint.xMinimum+d;this.axisX.sessionVariables.internalMaximum=this.dragStartPoint.xMaximum+d;c=0;this.axisX.sessionVariables.internalMinimum<this.axisX._absoluteMinimum-
-Y(this.axisX.interval,this.axisX.intervalType)?(c=this.axisX._absoluteMinimum-Y(this.axisX.interval,this.axisX.intervalType)-this.axisX.sessionVariables.internalMinimum,this.axisX.sessionVariables.internalMinimum+=c,this.axisX.sessionVariables.internalMaximum+=c):this.axisX.sessionVariables.internalMaximum>this.axisX._absoluteMaximum+Y(this.axisX.interval,this.axisX.intervalType)&&(c=this.axisX.sessionVariables.internalMaximum-(this.axisX._absoluteMaximum+Y(this.axisX.interval,this.axisX.intervalType)),
-this.axisX.sessionVariables.internalMaximum-=c,this.axisX.sessionVariables.internalMinimum-=c);var e=this;clearTimeout(this._panTimerId);this._panTimerId=setTimeout(function(){e.render()},0)}else this.zoomEnabled&&(c=this.plotArea,this.resetOverlayedCanvas(),d=this.overlaidCanvasCtx.globalAlpha,this.overlaidCanvasCtx.globalAlpha=0.7,this.overlaidCanvasCtx.fillStyle="#A0ABB8","xySwapped"===this.plotInfo.axisPlacement?this.overlaidCanvasCtx.fillRect(c.x1,this.dragStartPoint.y,c.x2-c.x1,b-this.dragStartPoint.y):
-"normal"===this.plotInfo.axisPlacement&&this.overlaidCanvasCtx.fillRect(this.dragStartPoint.x,c.y1,a-this.dragStartPoint.x,c.y2-c.y1),this.overlaidCanvasCtx.globalAlpha=d)}else this._toolTip.enabled&&this._toolTip.mouseMoveHandler(a,b)};v.prototype.preparePlotArea=function(){var a=this.plotArea,b=this.axisY?this.axisY:this.axisY2;!t&&(0<a.x1||0<a.y1)&&a.ctx.translate(a.x1,a.y1);this.axisX&&b?(a.x1=this.axisX.lineCoordinates.x1<this.axisX.lineCoordinates.x2?this.axisX.lineCoordinates.x1:b.lineCoordinates.x1,
-a.y1=this.axisX.lineCoordinates.y1<b.lineCoordinates.y1?this.axisX.lineCoordinates.y1:b.lineCoordinates.y1,a.x2=this.axisX.lineCoordinates.x2>b.lineCoordinates.x2?this.axisX.lineCoordinates.x2:b.lineCoordinates.x2,a.y2=this.axisX.lineCoordinates.y2>this.axisX.lineCoordinates.y1?this.axisX.lineCoordinates.y2:b.lineCoordinates.y2,a.width=a.x2-a.x1,a.height=a.y2-a.y1):(b=this.layoutManager.getFreeSpace(),a.x1=b.x1,a.x2=b.x2,a.y1=b.y1,a.y2=b.y2,a.width=b.width,a.height=b.height);t||(a.canvas.width=a.width,
-a.canvas.height=a.height,a.canvas.style.left=a.x1+"px",a.canvas.style.top=a.y1+"px",(0<a.x1||0<a.y1)&&a.ctx.translate(-a.x1,-a.y1))};v.prototype.getPixelCoordinatesOnPlotArea=function(a,b){return{x:this.axisX.getPixelCoordinatesOnAxis(a).x,y:this.axisY.getPixelCoordinatesOnAxis(b).y}};v.prototype.renderIndexLabels=function(a){a=a||this.plotArea.ctx;a.textBaseline="middle";for(var b=this.plotArea,c=0;c<this._indexLabels.length;c++){var d=this._indexLabels[c],e,f,g;a.fillStyle=T("indexLabelFontColor",
-d.dataPoint,d.dataSeries);a.font=ua("indexLabel",d.dataPoint,d.dataSeries);var k=this.replaceKeywordsWithValue(T("indexLabel",d.dataPoint,d.dataSeries),d.dataPoint,d.dataSeries,null,d.indexKeyword),p=a.measureText(k).width,h=T("indexLabelFontSize",d.dataPoint,d.dataSeries),l=T("indexLabelPlacement",d.dataPoint,d.dataSeries),r=T("indexLabelOrientation",d.dataPoint,d.dataSeries),m=g=0,q=0,n=0,n=m=q=0,s=d.direction,m=d.dataSeries.axisX,n=d.dataSeries.axisY;d.dataPoint.x<m.minimum||(d.dataPoint.x>m.maximum||
-d.dataPoint.y<n.minimum||d.dataPoint.y>n.maximum)||("column"===d.chartType||"stackedColumn"===d.chartType||"stackedColumn100"===d.chartType||"bar"===d.chartType||"stackedBar"===d.chartType||"stackedBar100"===d.chartType||"candlestick"===d.chartType||"ohlc"===d.chartType||"rangeColumn"===d.chartType||"rangeBar"===d.chartType?(m=n=5,Math.abs(d.bounds.x1,d.bounds.x2),Math.abs(d.bounds.y1,d.bounds.y2),"normal"===this.plotInfo.axisPlacement?("inside"!==l?(m=b.y1,q=b.y2):(m=d.bounds.y1,q=d.bounds.y2),"horizontal"===
-r?(e=d.point.x-p/2,f=0<=s?d.point.y-h/2-n<m+h/2?"auto"===l?Math.min(Math.max(d.point.y,m)+h/2+1,q-h/2-n):Math.min(m+h/2+1,q-h/2-n):Math.min(d.point.y-h/2-n+1,q-h/2-n):d.point.y+h/2+n>q-h/2-1?"auto"===l?Math.max(Math.min(d.point.y,q)-h/2-1,m+h/2+n):Math.max(q-h/2-1,m+h/2+n):Math.max(d.point.y+h/2+n,m+h/2+n)):"vertical"===r&&(e=d.point.x,f=0<=s?d.point.y-n<m+p+1?"auto"===l?Math.min(Math.max(d.point.y,m)+p+1,q):Math.min(m+p+1,q):Math.min(d.point.y-n,q-1):d.point.y+p+n>q-1?"auto"===l?Math.max(Math.min(d.point.y,
-q)-n,m):Math.max(q-1,m):Math.max(d.point.y+p+n,m),g=-90)):"xySwapped"===this.plotInfo.axisPlacement&&("inside"!==l?(n=b.x1,q=b.x2):(n=d.bounds.x1,q=d.bounds.x2),"horizontal"===r?(f=d.point.y,e=0<=s?d.point.x+m>q-p?"auto"===l?Math.max(Math.min(d.point.x,q)-p,n):Math.max(q-p,n):Math.max(d.point.x+m,n):d.point.x-p-m<n?"auto"===l?Math.min(Math.max(d.point.x,n)+1,q):Math.min(n+1,q):Math.min(d.point.x-p-m,q)):"vertical"===r&&(f=d.point.y+p/2,e=0<=s?d.point.x+h/2+m>q-h/2?"auto"===l?Math.max(Math.min(d.point.x,
-q)-h/2,n):Math.max(q-h/2,n):Math.max(d.point.x+h/2+m,n):d.point.x-h/2-m<n+h/2?"auto"===l?Math.min(Math.max(d.point.x,n)+h/2,q+h/2):Math.min(n+h/2,q+h/2):Math.min(d.point.x-h/2-m,q+h/2),g=-90))):(n=5,"horizontal"===r?(e=d.point.x-p/2,"bubble"===d.chartType&&(n=-h/2),f=0<s?Math.max(d.point.y-h/2-n,b.y1+h/2):Math.min(d.point.y+h/2+n,b.y2-h/2)):"vertical"===r&&(e=d.point.x,"bubble"===d.chartType&&(n=-p/2),f=0<s?Math.max(d.point.y-n,b.y1+p):Math.min(d.point.y+p+n,b.y2),g=-90)),a.save(),a.translate(e,f),
-a.rotate(Math.PI/180*g),a.fillText(k,0,0),a.restore())}return{source:a,dest:this.plotArea.ctx,animationCallback:y.fadeInAnimation,easingFunction:y.easing.easeInQuad,animationBase:0,startTimePercent:0.7}};v.prototype.renderLine=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=this._eventManager.ghostCtx;b.save();var d=this.plotArea;b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();for(var d=[],e=0;e<a.dataSeriesIndexes.length;e++){var f=a.dataSeriesIndexes[e],
-g=this.data[f];b.lineWidth=g.lineThickness;var k=g.dataPoints,p=g.id;this._eventManager.objectMap[p]={objectType:"dataSeries",dataSeriesIndex:f};p=C(p);c.strokeStyle=p;c.lineWidth=0<g.lineThickness?Math.max(g.lineThickness,4):0;p=g._colorSet[0];b.strokeStyle=p;var h=!0,l=0,r,m;b.beginPath();if(0<k.length){for(var q=!1,l=0;l<k.length;l++)if(r=k[l].x.getTime?k[l].x.getTime():k[l].x,!(r<a.axisX.dataInfo.viewPortMin||r>a.axisX.dataInfo.viewPortMax))if("number"!==typeof k[l].y)0<l&&(b.stroke(),t&&c.stroke()),
-q=!0;else{r=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(r-a.axisX.conversionParameters.minimum)+0.5<<0;m=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(k[l].y-a.axisY.conversionParameters.minimum)+0.5<<0;var n=g.dataPointIds[l];this._eventManager.objectMap[n]={id:n,objectType:"dataPoint",dataSeriesIndex:f,dataPointIndex:l,x1:r,y1:m};h||q?(b.beginPath(),b.moveTo(r,m),t&&(c.beginPath(),c.moveTo(r,m)),q=h=!1):(b.lineTo(r,m),t&&
-c.lineTo(r,m),0==l%500&&(b.stroke(),b.beginPath(),b.moveTo(r,m),t&&(c.stroke(),c.beginPath(),c.moveTo(r,m))));if(0<k[l].markerSize||0<g.markerSize){var s=g.getMarkerProperties(l,r,m,b);d.push(s);n=C(n);t&&d.push({x:r,y:m,ctx:c,type:s.type,size:s.size,color:n,borderColor:n,borderThickness:s.borderThickness})}(k[l].indexLabel||g.indexLabel)&&this._indexLabels.push({chartType:"line",dataPoint:k[l],dataSeries:g,point:{x:r,y:m},direction:0<=k[l].y?1:-1,color:p})}b.stroke();t&&c.stroke()}}J.drawMarkers(d);
-b.restore();b.beginPath();t&&c.beginPath();return{source:b,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderStepLine=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=this._eventManager.ghostCtx;b.save();var d=this.plotArea;b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();for(var d=[],e=0;e<a.dataSeriesIndexes.length;e++){var f=a.dataSeriesIndexes[e],g=this.data[f];
-b.lineWidth=g.lineThickness;var k=g.dataPoints,p=g.id;this._eventManager.objectMap[p]={objectType:"dataSeries",dataSeriesIndex:f};p=C(p);c.strokeStyle=p;c.lineWidth=0<g.lineThickness?Math.max(g.lineThickness,4):0;p=g._colorSet[0];b.strokeStyle=p;var h=!0,l=0,r,m;b.beginPath();if(0<k.length){for(var q=!1,l=0;l<k.length;l++)if(r=k[l].getTime?k[l].x.getTime():k[l].x,!(r<a.axisX.dataInfo.viewPortMin||r>a.axisX.dataInfo.viewPortMax))if("number"!==typeof k[l].y)0<l&&(b.stroke(),t&&c.stroke()),q=!0;else{var n=
-m;r=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(r-a.axisX.conversionParameters.minimum)+0.5<<0;m=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(k[l].y-a.axisY.conversionParameters.minimum)+0.5<<0;var s=g.dataPointIds[l];this._eventManager.objectMap[s]={id:s,objectType:"dataPoint",dataSeriesIndex:f,dataPointIndex:l,x1:r,y1:m};h||q?(b.beginPath(),b.moveTo(r,m),t&&(c.beginPath(),c.moveTo(r,m)),q=h=!1):(b.lineTo(r,n),t&&c.lineTo(r,
-n),b.lineTo(r,m),t&&c.lineTo(r,m),0==l%500&&(b.stroke(),b.beginPath(),b.moveTo(r,m),t&&(c.stroke(),c.beginPath(),c.moveTo(r,m))));if(0<k[l].markerSize||0<g.markerSize)n=g.getMarkerProperties(l,r,m,b),d.push(n),s=C(s),t&&d.push({x:r,y:m,ctx:c,type:n.type,size:n.size,color:s,borderColor:s,borderThickness:n.borderThickness});(k[l].indexLabel||g.indexLabel)&&this._indexLabels.push({chartType:"stepLine",dataPoint:k[l],dataSeries:g,point:{x:r,y:m},direction:0<=k[l].y?1:-1,color:p})}b.stroke();t&&c.stroke()}}J.drawMarkers(d);
-b.restore();b.beginPath();t&&c.beginPath();return{source:b,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderSpline=function(a){function b(a){a=fa(a,2);if(0<a.length){c.beginPath();t&&d.beginPath();c.moveTo(a[0].x,a[0].y);t&&d.moveTo(a[0].x,a[0].y);for(var b=0;b<a.length-3;b+=3)c.bezierCurveTo(a[b+1].x,a[b+1].y,a[b+2].x,a[b+2].y,a[b+3].x,a[b+3].y),t&&d.bezierCurveTo(a[b+1].x,a[b+1].y,a[b+2].x,a[b+2].y,a[b+3].x,a[b+3].y),0<
-b&&0===b%3E3&&(c.stroke(),c.beginPath(),c.moveTo(a[b+3].x,a[b+3].y),t&&(d.stroke(),d.beginPath(),d.moveTo(a[b+3].x,a[b+3].y)));c.stroke();t&&d.stroke()}}var c=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var d=this._eventManager.ghostCtx;c.save();var e=this.plotArea;c.beginPath();c.rect(e.x1,e.y1,e.width,e.height);c.clip();for(var e=[],f=0;f<a.dataSeriesIndexes.length;f++){var g=a.dataSeriesIndexes[f],k=this.data[g];c.lineWidth=k.lineThickness;var p=k.dataPoints,h=k.id;
-this._eventManager.objectMap[h]={objectType:"dataSeries",dataSeriesIndex:g};h=C(h);d.strokeStyle=h;d.lineWidth=0<k.lineThickness?Math.max(k.lineThickness,4):0;h=k._colorSet[0];c.strokeStyle=h;var l=0,r,m,q=[];c.beginPath();if(0<p.length)for(l=0;l<p.length;l++)if(r=p[l].getTime?p[l].x.getTime():p[l].x,!(r<a.axisX.dataInfo.viewPortMin||r>a.axisX.dataInfo.viewPortMax))if("number"!==typeof p[l].y)0<l&&(b(q),q=[]);else{r=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*
-(r-a.axisX.conversionParameters.minimum)+0.5<<0;m=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(p[l].y-a.axisY.conversionParameters.minimum)+0.5<<0;var n=k.dataPointIds[l];this._eventManager.objectMap[n]={id:n,objectType:"dataPoint",dataSeriesIndex:g,dataPointIndex:l,x1:r,y1:m};q[q.length]={x:r,y:m};if(0<p[l].markerSize||0<k.markerSize){var s=k.getMarkerProperties(l,r,m,c);e.push(s);n=C(n);t&&e.push({x:r,y:m,ctx:d,type:s.type,size:s.size,color:n,borderColor:n,borderThickness:s.borderThickness})}(p[l].indexLabel||
-k.indexLabel)&&this._indexLabels.push({chartType:"spline",dataPoint:p[l],dataSeries:k,point:{x:r,y:m},direction:0<=p[l].y?1:-1,color:h})}b(q)}J.drawMarkers(e);c.restore();c.beginPath();t&&d.beginPath();return{source:c,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};var F=function(a,b,c,d,e,f,g,k,p,h,l,r,m){"undefined"===typeof m&&(m=1);g=g||0;k=k||"black";var q=15<d-b&&15<e-c?8:0.35*Math.min(d-b,e-c);a.beginPath();a.moveTo(b,c);a.save();
-a.fillStyle=f;a.globalAlpha=m;a.fillRect(b,c,d-b,e-c);a.globalAlpha=1;0<g&&(m=0===g%2?0:0.5,a.beginPath(),a.lineWidth=g,a.strokeStyle=k,a.moveTo(b,c),a.rect(b-m,c-m,d-b+2*m,e-c+2*m),a.stroke());a.restore();!0===p&&(a.save(),a.beginPath(),a.moveTo(b,c),a.lineTo(b+q,c+q),a.lineTo(d-q,c+q),a.lineTo(d,c),a.closePath(),g=a.createLinearGradient((d+b)/2,c+q,(d+b)/2,c),g.addColorStop(0,f),g.addColorStop(1,"rgba(255, 255, 255, .4)"),a.fillStyle=g,a.fill(),a.restore());!0===h&&(a.save(),a.beginPath(),a.moveTo(b,
-e),a.lineTo(b+q,e-q),a.lineTo(d-q,e-q),a.lineTo(d,e),a.closePath(),g=a.createLinearGradient((d+b)/2,e-q,(d+b)/2,e),g.addColorStop(0,f),g.addColorStop(1,"rgba(255, 255, 255, .4)"),a.fillStyle=g,a.fill(),a.restore());!0===l&&(a.save(),a.beginPath(),a.moveTo(b,c),a.lineTo(b+q,c+q),a.lineTo(b+q,e-q),a.lineTo(b,e),a.closePath(),g=a.createLinearGradient(b+q,(e+c)/2,b,(e+c)/2),g.addColorStop(0,f),g.addColorStop(1,"rgba(255, 255, 255, 0.1)"),a.fillStyle=g,a.fill(),a.restore());!0===r&&(a.save(),a.beginPath(),
-a.moveTo(d,c),a.lineTo(d-q,c+q),a.lineTo(d-q,e-q),a.lineTo(d,e),g=a.createLinearGradient(d-q,(e+c)/2,d,(e+c)/2),g.addColorStop(0,f),g.addColorStop(1,"rgba(255, 255, 255, 0.1)"),a.fillStyle=g,g.addColorStop(0,f),g.addColorStop(1,"rgba(255, 255, 255, 0.1)"),a.fillStyle=g,a.fill(),a.closePath(),a.restore())};v.prototype.renderColumn=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=0,f,g,k,p=a.axisY.conversionParameters.reference+
-a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,e=Math.min(0.15*this.width,0.9*(this.plotArea.width/a.plotType.totalDataSeries))<<0,h=a.axisX.dataInfo.minDiff,l=0.9*(d.width/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(h)/a.plotType.totalDataSeries)<<0;l>e?l=e:Infinity===h?l=e:1>l&&(l=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),
-this._eventManager.ghostCtx.clip());for(d=0;d<a.dataSeriesIndexes.length;d++){var h=a.dataSeriesIndexes[d],r=this.data[h],m=r.dataPoints;if(0<m.length)for(var q=5<l&&r.bevelEnabled?!0:!1,e=0;e<m.length;e++)if(m[e].getTime?k=m[e].x.getTime():k=m[e].x,!(k<a.axisX.dataInfo.viewPortMin||k>a.axisX.dataInfo.viewPortMax)&&"number"===typeof m[e].y){f=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(k-a.axisX.conversionParameters.minimum)+0.5<<0;g=a.axisY.conversionParameters.reference+
-a.axisY.conversionParameters.pixelPerUnit*(m[e].y-a.axisY.conversionParameters.minimum)+0.5<<0;f=f-a.plotType.totalDataSeries*l/2+(a.previousDataSeriesCount+d)*l<<0;var n=f+l<<0,s;0<=m[e].y?s=p:(s=g,g=p);g>s&&(s=g=s);c=m[e].color?m[e].color:r._colorSet[e%r._colorSet.length];F(b,f,g,n,s,c,0,null,q&&0<=m[e].y,0>m[e].y&&q,!1,!1,r.fillOpacity);c=r.dataPointIds[e];this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:h,dataPointIndex:e,x1:f,y1:g,x2:n,y2:s};c=C(c);t&&F(this._eventManager.ghostCtx,
-f,g,n,s,c,0,null,!1,!1,!1,!1);(m[e].indexLabel||r.indexLabel)&&this._indexLabels.push({chartType:"column",dataPoint:m[e],dataSeries:r,point:{x:f+(n-f)/2,y:0<=m[e].y?g:s},direction:0<=m[e].y?1:-1,bounds:{x1:f,y1:Math.min(g,s),x2:n,y2:Math.max(g,s)},color:c})}}b.restore();t&&this._eventManager.ghostCtx.restore();a=Math.min(p,a.axisY.boundingRect.y2);return{source:b,dest:this.plotArea.ctx,animationCallback:y.yScaleAnimation,easingFunction:y.easing.easeOutQuart,animationBase:a}}};v.prototype.renderStackedColumn=
-function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=[],f=[],g=0,k,p=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,g=0.15*this.width<<0,h=a.axisX.dataInfo.minDiff,l=0.9*(d.width/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(h)/a.plotType.plotUnits.length)<<0;l>g?l=g:Infinity===h?l=g:1>l&&(l=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();
-b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(h=0;h<a.dataSeriesIndexes.length;h++){var r=a.dataSeriesIndexes[h],m=this.data[r],q=m.dataPoints;if(0<q.length){var n=5<l&&m.bevelEnabled?!0:!1;b.strokeStyle="#4572A7 ";for(g=0;g<q.length;g++)if(c=q[g].x.getTime?q[g].x.getTime():q[g].x,!(c<a.axisX.dataInfo.viewPortMin||c>a.axisX.dataInfo.viewPortMax)&&"number"===typeof q[g].y){d=a.axisX.conversionParameters.reference+
-a.axisX.conversionParameters.pixelPerUnit*(c-a.axisX.conversionParameters.minimum)+0.5<<0;k=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(q[g].y-a.axisY.conversionParameters.minimum);var s=d-a.plotType.plotUnits.length*l/2+a.index*l<<0,B=s+l<<0,u;if(0<=q[g].y){var x=e[c]?e[c]:0;k-=x;u=p-x;e[c]=x+(u-k)}else x=f[c]?f[c]:0,u=k+x,k=p+x,f[c]=x+(u-k);c=q[g].color?q[g].color:m._colorSet[g%m._colorSet.length];F(b,s,k,B,u,c,0,null,n&&0<=q[g].y,0>q[g].y&&n,!1,!1,m.fillOpacity);
-c=m.dataPointIds[g];this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:r,dataPointIndex:g,x1:s,y1:k,x2:B,y2:u};c=C(c);t&&F(this._eventManager.ghostCtx,s,k,B,u,c,0,null,!1,!1,!1,!1);(q[g].indexLabel||m.indexLabel)&&this._indexLabels.push({chartType:"stackedColumn",dataPoint:q[g],dataSeries:m,point:{x:d,y:0<=q[g].y?k:u},direction:0<=q[g].y?1:-1,bounds:{x1:s,y1:Math.min(k,u),x2:B,y2:Math.max(k,u)},color:c})}}}b.restore();t&&this._eventManager.ghostCtx.restore();a=Math.min(p,
-a.axisY.boundingRect.y2);return{source:b,dest:this.plotArea.ctx,animationCallback:y.yScaleAnimation,easingFunction:y.easing.easeOutQuart,animationBase:a}}};v.prototype.renderStackedColumn100=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=[],f=[],g=0,k,p=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,g=0.15*this.width<<0,h=a.axisX.dataInfo.minDiff,
-l=0.9*(d.width/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(h)/a.plotType.plotUnits.length)<<0;l>g?l=g:Infinity===h?l=g:1>l&&(l=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(h=0;h<a.dataSeriesIndexes.length;h++){var r=a.dataSeriesIndexes[h],m=this.data[r],q=m.dataPoints;if(0<q.length)for(var n=5<l&&m.bevelEnabled?!0:!1,g=0;g<q.length;g++)if(c=
-q[g].x.getTime?q[g].x.getTime():q[g].x,!(c<a.axisX.dataInfo.viewPortMin||c>a.axisX.dataInfo.viewPortMax)&&"number"===typeof q[g].y){d=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(c-a.axisX.conversionParameters.minimum)+0.5<<0;k=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*((0!==a.dataPointYSums[c]?100*(q[g].y/a.dataPointYSums[c]):0)-a.axisY.conversionParameters.minimum);var s=d-a.plotType.plotUnits.length*l/2+a.index*l<<0,B=
-s+l<<0,u;if(0<=q[g].y){var x=e[c]?e[c]:0;k-=x;u=p-x;e[c]=x+(u-k)}else x=f[c]?f[c]:0,u=k+x,k=p+x,f[c]=x+(u-k);c=q[g].color?q[g].color:m._colorSet[g%m._colorSet.length];F(b,s,k,B,u,c,0,null,n&&0<=q[g].y,0>q[g].y&&n,!1,!1,m.fillOpacity);c=m.dataPointIds[g];this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:r,dataPointIndex:g,x1:s,y1:k,x2:B,y2:u};c=C(c);t&&F(this._eventManager.ghostCtx,s,k,B,u,c,0,null,!1,!1,!1,!1);(q[g].indexLabel||m.indexLabel)&&this._indexLabels.push({chartType:"stackedColumn100",
-dataPoint:q[g],dataSeries:m,point:{x:d,y:0<=q[g].y?k:u},direction:0<=q[g].y?1:-1,bounds:{x1:s,y1:Math.min(k,u),x2:B,y2:Math.max(k,u)},color:c})}}b.restore();t&&this._eventManager.ghostCtx.restore();a=Math.min(p,a.axisY.boundingRect.y2);return{source:b,dest:this.plotArea.ctx,animationCallback:y.yScaleAnimation,easingFunction:y.easing.easeOutQuart,animationBase:a}}};v.prototype.renderBar=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,
-e=0,f,g,k,p=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,e=Math.min(0.15*this.height,0.9*(this.plotArea.height/a.plotType.totalDataSeries))<<0,h=a.axisX.dataInfo.minDiff,l=0.9*(d.height/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(h)/a.plotType.totalDataSeries)<<0;l>e?l=e:Infinity===h?l=e:1>l&&(l=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,
-d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(d=0;d<a.dataSeriesIndexes.length;d++){var h=a.dataSeriesIndexes[d],r=this.data[h],m=r.dataPoints;if(0<m.length){var q=5<l&&r.bevelEnabled?!0:!1;b.strokeStyle="#4572A7 ";for(e=0;e<m.length;e++)if(m[e].getTime?k=m[e].x.getTime():k=m[e].x,!(k<a.axisX.dataInfo.viewPortMin||k>a.axisX.dataInfo.viewPortMax)&&"number"===typeof m[e].y){g=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(k-a.axisX.conversionParameters.minimum)+
-0.5<<0;f=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(m[e].y-a.axisY.conversionParameters.minimum)+0.5<<0;g=g-a.plotType.totalDataSeries*l/2+(a.previousDataSeriesCount+d)*l<<0;var n=g+l<<0,s;0<=m[e].y?s=p:(s=f,f=p);c=m[e].color?m[e].color:r._colorSet[e%r._colorSet.length];F(b,s,g,f,n,c,0,null,q,!1,!1,!1,r.fillOpacity);c=r.dataPointIds[e];this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:h,dataPointIndex:e,x1:s,y1:g,x2:f,y2:n};c=C(c);
-t&&F(this._eventManager.ghostCtx,s,g,f,n,c,0,null,!1,!1,!1,!1);this._indexLabels.push({chartType:"bar",dataPoint:m[e],dataSeries:r,point:{x:0<=m[e].y?f:s,y:g+(n-g)/2},direction:0<=m[e].y?1:-1,bounds:{x1:Math.min(s,f),y1:g,x2:Math.max(s,f),y2:n},color:c})}}}b.restore();t&&this._eventManager.ghostCtx.restore();a=Math.max(p,a.axisX.boundingRect.x2);return{source:b,dest:this.plotArea.ctx,animationCallback:y.xScaleAnimation,easingFunction:y.easing.easeOutQuart,animationBase:a}}};v.prototype.renderStackedBar=
-function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=[],f=[],g=0,k,p=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,g=0.15*this.height<<0,h=a.axisX.dataInfo.minDiff,l=0.9*(d.height/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(h)/a.plotType.plotUnits.length)<<0;l>g?l=g:Infinity===h?l=g:1>l&&(l=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();
-b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(h=0;h<a.dataSeriesIndexes.length;h++){var r=a.dataSeriesIndexes[h],m=this.data[r],q=m.dataPoints;if(0<q.length){var n=5<l&&m.bevelEnabled?!0:!1;b.strokeStyle="#4572A7 ";for(g=0;g<q.length;g++)if(c=q[g].x.getTime?q[g].x.getTime():q[g].x,!(c<a.axisX.dataInfo.viewPortMin||c>a.axisX.dataInfo.viewPortMax)&&"number"===typeof q[g].y){d=a.axisX.conversionParameters.reference+
-a.axisX.conversionParameters.pixelPerUnit*(c-a.axisX.conversionParameters.minimum)+0.5<<0;k=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(q[g].y-a.axisY.conversionParameters.minimum);var s=d-a.plotType.plotUnits.length*l/2+a.index*l<<0,B=s+l<<0,u;if(0<=q[g].y){var x=e[c]?e[c]:0;u=p+x;k+=x;e[c]=x+(k-u)}else x=f[c]?f[c]:0,u=k-x,k=p-x,f[c]=x+(k-u);c=q[g].color?q[g].color:m._colorSet[g%m._colorSet.length];F(b,u,s,k,B,c,0,null,n,!1,!1,!1,m.fillOpacity);c=m.dataPointIds[g];
-this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:r,dataPointIndex:g,x1:u,y1:s,x2:k,y2:B};c=C(c);t&&F(this._eventManager.ghostCtx,u,s,k,B,c,0,null,!1,!1,!1,!1);this._indexLabels.push({chartType:"stackedBar",dataPoint:q[g],dataSeries:m,point:{x:0<=q[g].y?k:u,y:d},direction:0<=q[g].y?1:-1,bounds:{x1:Math.min(u,k),y1:s,x2:Math.max(u,k),y2:B},color:c})}}}b.restore();t&&this._eventManager.ghostCtx.restore();a=Math.max(p,a.axisX.boundingRect.x2);return{source:b,dest:this.plotArea.ctx,
-animationCallback:y.xScaleAnimation,easingFunction:y.easing.easeOutQuart,animationBase:a}}};v.prototype.renderStackedBar100=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=[],f=[],g=0,k,p=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,g=0.15*this.height<<0,h=a.axisX.dataInfo.minDiff,l=0.9*(d.height/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(h)/
-a.plotType.plotUnits.length)<<0;l>g?l=g:Infinity===h?l=g:1>l&&(l=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(h=0;h<a.dataSeriesIndexes.length;h++){var r=a.dataSeriesIndexes[h],m=this.data[r],q=m.dataPoints;if(0<q.length){var n=5<l&&m.bevelEnabled?!0:!1;b.strokeStyle="#4572A7 ";for(g=0;g<q.length;g++)if(c=q[g].x.getTime?q[g].x.getTime():
-q[g].x,!(c<a.axisX.dataInfo.viewPortMin||c>a.axisX.dataInfo.viewPortMax)&&"number"===typeof q[g].y){d=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(c-a.axisX.conversionParameters.minimum)+0.5<<0;k=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*((0!==a.dataPointYSums[c]?100*(q[g].y/a.dataPointYSums[c]):0)-a.axisY.conversionParameters.minimum);var s=d-a.plotType.plotUnits.length*l/2+a.index*l<<0,B=s+l<<0,u;if(0<=q[g].y){var x=e[c]?
-e[c]:0;u=p+x;k+=x;e[c]=x+(k-u)}else x=f[c]?f[c]:0,u=k-x,k=p-x,f[c]=x+(k-u);c=q[g].color?q[g].color:m._colorSet[g%m._colorSet.length];F(b,u,s,k,B,c,0,null,n,!1,!1,!1,m.fillOpacity);c=m.dataPointIds[g];this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:r,dataPointIndex:g,x1:u,y1:s,x2:k,y2:B};c=C(c);t&&F(this._eventManager.ghostCtx,u,s,k,B,c,0,null,!1,!1,!1,!1);this._indexLabels.push({chartType:"stackedBar100",dataPoint:q[g],dataSeries:m,point:{x:0<=q[g].y?k:u,y:d},direction:0<=
-q[g].y?1:-1,bounds:{x1:Math.min(u,k),y1:s,x2:Math.max(u,k),y2:B},color:c})}}}b.restore();t&&this._eventManager.ghostCtx.restore();a=Math.max(p,a.axisX.boundingRect.x2);return{source:b,dest:this.plotArea.ctx,animationCallback:y.xScaleAnimation,easingFunction:y.easing.easeOutQuart,animationBase:a}}};v.prototype.renderArea=function(a){function b(){x&&(0<h.lineThickness&&c.stroke(),0>=a.axisY.minimum&&0<=a.axisY.maximum?u=B:0>a.axisY.maximum?u=f.y1:0<a.axisY.minimum&&(u=e.y2),c.lineTo(q,u),c.lineTo(x.x,
-u),c.closePath(),c.globalAlpha=h.fillOpacity,c.fill(),c.globalAlpha=1,t&&(d.lineTo(q,u),d.lineTo(x.x,u),d.closePath(),d.fill()),c.beginPath(),c.moveTo(q,n),d.beginPath(),d.moveTo(q,n),x={x:q,y:n})}var c=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var d=this._eventManager.ghostCtx,e=a.axisX.lineCoordinates,f=a.axisY.lineCoordinates,g=[],k=this.plotArea;c.save();t&&d.save();c.beginPath();c.rect(k.x1,k.y1,k.width,k.height);c.clip();t&&(d.beginPath(),d.rect(k.x1,k.y1,k.width,
-k.height),d.clip());for(k=0;k<a.dataSeriesIndexes.length;k++){var p=a.dataSeriesIndexes[k],h=this.data[p],l=h.dataPoints,g=h.id;this._eventManager.objectMap[g]={objectType:"dataSeries",dataSeriesIndex:p};g=C(g);d.fillStyle=g;var g=[],r=!0,m=0,q,n,s,B=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)+0.5<<0,u,x=null;if(0<l.length){var w=h._colorSet[m%h._colorSet.length];c.fillStyle=w;c.strokeStyle=w;c.lineWidth=h.lineThickness;
-for(var Q=!0;m<l.length;m++)if(s=l[m].x.getTime?l[m].x.getTime():l[m].x,!(s<a.axisX.dataInfo.viewPortMin||s>a.axisX.dataInfo.viewPortMax))if("number"!==typeof l[m].y)b(),Q=!0;else{q=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(s-a.axisX.conversionParameters.minimum)+0.5<<0;n=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(l[m].y-a.axisY.conversionParameters.minimum)+0.5<<0;r||Q?(c.beginPath(),c.moveTo(q,n),x={x:q,y:n},t&&(d.beginPath(),
-d.moveTo(q,n)),Q=r=!1):(c.lineTo(q,n),t&&d.lineTo(q,n),0==m%250&&b());var G=h.dataPointIds[m];this._eventManager.objectMap[G]={id:G,objectType:"dataPoint",dataSeriesIndex:p,dataPointIndex:m,x1:q,y1:n};0!==l[m].markerSize&&(0<l[m].markerSize||0<h.markerSize)&&(s=h.getMarkerProperties(m,q,n,c),g.push(s),G=C(G),t&&g.push({x:q,y:n,ctx:d,type:s.type,size:s.size,color:G,borderColor:G,borderThickness:s.borderThickness}));(l[m].indexLabel||h.indexLabel)&&this._indexLabels.push({chartType:"area",dataPoint:l[m],
-dataSeries:h,point:{x:q,y:n},direction:0<=l[m].y?1:-1,color:w})}b();J.drawMarkers(g)}}c.restore();t&&this._eventManager.ghostCtx.restore();return{source:c,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderSplineArea=function(a){function b(){var b=fa(u,2);if(0<b.length){c.beginPath();c.moveTo(b[0].x,b[0].y);t&&(d.beginPath(),d.moveTo(b[0].x,b[0].y));for(var g=0;g<b.length-3;g+=3)c.bezierCurveTo(b[g+1].x,b[g+1].y,b[g+2].x,b[g+
-2].y,b[g+3].x,b[g+3].y),t&&d.bezierCurveTo(b[g+1].x,b[g+1].y,b[g+2].x,b[g+2].y,b[g+3].x,b[g+3].y);0<h.lineThickness&&c.stroke();0>=a.axisY.minimum&&0<=a.axisY.maximum?s=n:0>a.axisY.maximum?s=f.y1:0<a.axisY.minimum&&(s=e.y2);B={x:b[0].x,y:b[0].y};c.lineTo(b[b.length-1].x,s);c.lineTo(B.x,s);c.closePath();c.globalAlpha=h.fillOpacity;c.fill();c.globalAlpha=1;t&&(d.lineTo(b[b.length-1].x,s),d.lineTo(B.x,s),d.closePath(),d.fill())}}var c=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var d=
-this._eventManager.ghostCtx,e=a.axisX.lineCoordinates,f=a.axisY.lineCoordinates,g=[],k=this.plotArea;c.save();t&&d.save();c.beginPath();c.rect(k.x1,k.y1,k.width,k.height);c.clip();t&&(d.beginPath(),d.rect(k.x1,k.y1,k.width,k.height),d.clip());for(k=0;k<a.dataSeriesIndexes.length;k++){var p=a.dataSeriesIndexes[k],h=this.data[p],l=h.dataPoints,g=h.id;this._eventManager.objectMap[g]={objectType:"dataSeries",dataSeriesIndex:p};g=C(g);d.fillStyle=g;var g=[],r=0,m,q,n=a.axisY.conversionParameters.reference+
-a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)+0.5<<0,s,B=null,u=[];if(0<l.length){color=h._colorSet[r%h._colorSet.length];c.fillStyle=color;c.strokeStyle=color;for(c.lineWidth=h.lineThickness;r<l.length;r++)if(m=l[r].x.getTime?l[r].x.getTime():l[r].x,!(m<a.axisX.dataInfo.viewPortMin||m>a.axisX.dataInfo.viewPortMax))if("number"!==typeof l[r].y)0<r&&(b(),u=[]);else{m=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(m-a.axisX.conversionParameters.minimum)+
-0.5<<0;q=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(l[r].y-a.axisY.conversionParameters.minimum)+0.5<<0;var x=h.dataPointIds[r];this._eventManager.objectMap[x]={id:x,objectType:"dataPoint",dataSeriesIndex:p,dataPointIndex:r,x1:m,y1:q};u[u.length]={x:m,y:q};if(0!==l[r].markerSize&&(0<l[r].markerSize||0<h.markerSize)){var w=h.getMarkerProperties(r,m,q,c);g.push(w);x=C(x);t&&g.push({x:m,y:q,ctx:d,type:w.type,size:w.size,color:x,borderColor:x,borderThickness:w.borderThickness})}(l[r].indexLabel||
-h.indexLabel)&&this._indexLabels.push({chartType:"splineArea",dataPoint:l[r],dataSeries:h,point:{x:m,y:q},direction:0<=l[r].y?1:-1,color:color})}b();J.drawMarkers(g)}}c.restore();t&&this._eventManager.ghostCtx.restore();return{source:c,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderStepArea=function(a){function b(){x&&(0<h.lineThickness&&c.stroke(),0>=a.axisY.minimum&&0<=a.axisY.maximum?u=B:0>a.axisY.maximum?u=f.y1:0<a.axisY.minimum&&
-(u=e.y2),c.lineTo(q,u),c.lineTo(x.x,u),c.closePath(),c.globalAlpha=h.fillOpacity,c.fill(),c.globalAlpha=1,t&&(d.lineTo(q,u),d.lineTo(x.x,u),d.closePath(),d.fill()),c.beginPath(),c.moveTo(q,n),d.beginPath(),d.moveTo(q,n),x={x:q,y:n})}var c=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var d=this._eventManager.ghostCtx,e=a.axisX.lineCoordinates,f=a.axisY.lineCoordinates,g=[],k=this.plotArea;c.save();t&&d.save();c.beginPath();c.rect(k.x1,k.y1,k.width,k.height);c.clip();t&&
-(d.beginPath(),d.rect(k.x1,k.y1,k.width,k.height),d.clip());for(k=0;k<a.dataSeriesIndexes.length;k++){var p=a.dataSeriesIndexes[k],h=this.data[p],l=h.dataPoints,g=h.id;this._eventManager.objectMap[g]={objectType:"dataSeries",dataSeriesIndex:p};g=C(g);d.fillStyle=g;var g=[],r=!0,m=0,q,n,s,B=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)+0.5<<0,u,x=null,w=!1;if(0<l.length){var Q=h._colorSet[m%h._colorSet.length];c.fillStyle=
-Q;c.strokeStyle=Q;for(c.lineWidth=h.lineThickness;m<l.length;m++)if(s=l[m].x.getTime?l[m].x.getTime():l[m].x,!(s<a.axisX.dataInfo.viewPortMin||s>a.axisX.dataInfo.viewPortMax)){var v=n;"number"!==typeof l[m].y?(b(),w=!0):(q=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(s-a.axisX.conversionParameters.minimum)+0.5<<0,n=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(l[m].y-a.axisY.conversionParameters.minimum)+0.5<<0,r||w?(c.beginPath(),
-c.moveTo(q,n),x={x:q,y:n},t&&(d.beginPath(),d.moveTo(q,n)),w=r=!1):(c.lineTo(q,v),t&&d.lineTo(q,v),c.lineTo(q,n),t&&d.lineTo(q,n),0==m%250&&b()),v=h.dataPointIds[m],this._eventManager.objectMap[v]={id:v,objectType:"dataPoint",dataSeriesIndex:p,dataPointIndex:m,x1:q,y1:n},0!==l[m].markerSize&&(0<l[m].markerSize||0<h.markerSize)&&(s=h.getMarkerProperties(m,q,n,c),g.push(s),v=C(v),t&&g.push({x:q,y:n,ctx:d,type:s.type,size:s.size,color:v,borderColor:v,borderThickness:s.borderThickness})),(l[m].indexLabel||
-h.indexLabel)&&this._indexLabels.push({chartType:"stepArea",dataPoint:l[m],dataSeries:h,point:{x:q,y:n},direction:0<=l[m].y?1:-1,color:Q}))}b();J.drawMarkers(g)}}c.restore();t&&this._eventManager.ghostCtx.restore();return{source:c,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderStackedArea=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=[],e=this.plotArea,f=[],g=[],
-k=0,p,h,l,r=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,m=this._eventManager.ghostCtx;t&&m.beginPath();b.save();t&&m.save();b.beginPath();b.rect(e.x1,e.y1,e.width,e.height);b.clip();t&&(m.beginPath(),m.rect(e.x1,e.y1,e.width,e.height),m.clip());xValuePresent=[];for(e=0;e<a.dataSeriesIndexes.length;e++){var q=a.dataSeriesIndexes[e],n=this.data[q],s=n.dataPoints;n.dataPointIndexes=[];for(k=0;k<s.length;k++)q=s[k].x.getTime?
-s[k].x.getTime():s[k].x,n.dataPointIndexes[q]=k,xValuePresent[q]||(g.push(q),xValuePresent[q]=!0);g.sort(ra)}for(e=0;e<a.dataSeriesIndexes.length;e++){var q=a.dataSeriesIndexes[e],n=this.data[q],s=n.dataPoints,B=!0,u=[],k=n.id;this._eventManager.objectMap[k]={objectType:"dataSeries",dataSeriesIndex:q};k=C(k);m.fillStyle=k;if(0<g.length){c=n._colorSet[0];b.fillStyle=c;b.strokeStyle=c;b.lineWidth=n.lineThickness;for(k=0;k<g.length;k++){l=g[k];var x=null,x=0<=n.dataPointIndexes[l]?s[n.dataPointIndexes[l]]:
-{x:l,y:0};if(!(l<a.axisX.dataInfo.viewPortMin||l>a.axisX.dataInfo.viewPortMax)&&"number"===typeof x.y){p=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(l-a.axisX.conversionParameters.minimum)+0.5<<0;h=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(x.y-a.axisY.conversionParameters.minimum);var w=f[l]?f[l]:0;h-=w;u.push({x:p,y:r-w});f[l]=r-h;if(B)b.beginPath(),b.moveTo(p,h),t&&(m.beginPath(),m.moveTo(p,h)),B=!1;else if(b.lineTo(p,
-h),t&&m.lineTo(p,h),0==k%250){for(0<n.lineThickness&&b.stroke();0<u.length;){var v=u.pop();b.lineTo(v.x,v.y);t&&m.lineTo(v.x,v.y)}b.closePath();b.globalAlpha=n.fillOpacity;b.fill();b.globalAlpha=1;b.beginPath();b.moveTo(p,h);t&&(m.closePath(),m.fill(),m.beginPath(),m.moveTo(p,h));u.push({x:p,y:r-w})}if(0<=n.dataPointIndexes[l]){var G=n.dataPointIds[n.dataPointIndexes[l]];this._eventManager.objectMap[G]={id:G,objectType:"dataPoint",dataSeriesIndex:q,dataPointIndex:n.dataPointIndexes[l],x1:p,y1:h}}0<=
-n.dataPointIndexes[l]&&0!==x.markerSize&&(0<x.markerSize||0<n.markerSize)&&(l=n.getMarkerProperties(k,p,h,b),d.push(l),markerColor=C(G),t&&d.push({x:p,y:h,ctx:m,type:l.type,size:l.size,color:markerColor,borderColor:markerColor,borderThickness:l.borderThickness}));(x.indexLabel||n.indexLabel)&&this._indexLabels.push({chartType:"stackedArea",dataPoint:x,dataSeries:n,point:{x:p,y:h},direction:0<=s[k].y?1:-1,color:c})}}for(0<n.lineThickness&&b.stroke();0<u.length;)v=u.pop(),b.lineTo(v.x,v.y),t&&m.lineTo(v.x,
-v.y);b.closePath();b.globalAlpha=n.fillOpacity;b.fill();b.globalAlpha=1;b.beginPath();b.moveTo(p,h);t&&(m.closePath(),m.fill(),m.beginPath(),m.moveTo(p,h))}delete n.dataPointIndexes}J.drawMarkers(d);b.restore();t&&m.restore();return{source:b,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderStackedArea100=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,
-e=[],f=[],g=[],k=0,p,h,l,r=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(0-a.axisY.conversionParameters.minimum)<<0,m=0.15*this.width<<0,q=a.axisX.dataInfo.minDiff,q=0.9*d.width/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(q)<<0,n=this._eventManager.ghostCtx;b.save();t&&n.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(n.beginPath(),n.rect(d.x1,d.y1,d.width,d.height),n.clip());xValuePresent=[];for(d=0;d<a.dataSeriesIndexes.length;d++){var s=
-a.dataSeriesIndexes[d],B=this.data[s],u=B.dataPoints;B.dataPointIndexes=[];for(k=0;k<u.length;k++)s=u[k].x.getTime?u[k].x.getTime():u[k].x,B.dataPointIndexes[s]=k,xValuePresent[s]||(g.push(s),xValuePresent[s]=!0);g.sort(ra)}for(d=0;d<a.dataSeriesIndexes.length;d++){var s=a.dataSeriesIndexes[d],B=this.data[s],u=B.dataPoints,x=!0,c=B.id;this._eventManager.objectMap[c]={objectType:"dataSeries",dataSeriesIndex:s};c=C(c);n.fillStyle=c;1==u.length&&(q=m);1>q?q=1:q>m&&(q=m);var w=[];if(0<g.length){c=B._colorSet[k%
-B._colorSet.length];b.fillStyle=c;b.strokeStyle=c;b.lineWidth=B.lineThickness;for(k=0;k<g.length;k++){l=g[k];var v=null,v=0<=B.dataPointIndexes[l]?u[B.dataPointIndexes[l]]:{x:l,y:0};if(!(l<a.axisX.dataInfo.viewPortMin||l>a.axisX.dataInfo.viewPortMax)&&"number"===typeof v.y){h=0!==a.dataPointYSums[l]?100*(v.y/a.dataPointYSums[l]):0;p=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(l-a.axisX.conversionParameters.minimum)+0.5<<0;h=a.axisY.conversionParameters.reference+
-a.axisY.conversionParameters.pixelPerUnit*(h-a.axisY.conversionParameters.minimum);var G=f[l]?f[l]:0;h-=G;w.push({x:p,y:r-G});f[l]=r-h;if(x)b.beginPath(),b.moveTo(p,h),t&&(n.beginPath(),n.moveTo(p,h)),x=!1;else if(b.lineTo(p,h),t&&n.lineTo(p,h),0==k%250){for(0<B.lineThickness&&b.stroke();0<w.length;){var z=w.pop();b.lineTo(z.x,z.y);t&&n.lineTo(z.x,z.y)}b.closePath();b.globalAlpha=B.fillOpacity;b.fill();b.globalAlpha=1;b.beginPath();b.moveTo(p,h);t&&(n.closePath(),n.fill(),n.beginPath(),n.moveTo(p,
-h));w.push({x:p,y:r-G})}if(0<=B.dataPointIndexes[l]){var A=B.dataPointIds[B.dataPointIndexes[l]];this._eventManager.objectMap[A]={id:A,objectType:"dataPoint",dataSeriesIndex:s,dataPointIndex:B.dataPointIndexes[l],x1:p,y1:h}}0<=B.dataPointIndexes[l]&&0!==v.markerSize&&(0<v.markerSize||0<B.markerSize)&&(l=B.getMarkerProperties(k,p,h,b),e.push(l),markerColor=C(A),t&&e.push({x:p,y:h,ctx:n,type:l.type,size:l.size,color:markerColor,borderColor:markerColor,borderThickness:l.borderThickness}));(v.indexLabel||
-B.indexLabel)&&this._indexLabels.push({chartType:"stackedArea100",dataPoint:v,dataSeries:B,point:{x:p,y:h},direction:0<=u[k].y?1:-1,color:c})}}for(0<B.lineThickness&&b.stroke();0<w.length;)z=w.pop(),b.lineTo(z.x,z.y),t&&n.lineTo(z.x,z.y);b.closePath();b.globalAlpha=B.fillOpacity;b.fill();b.globalAlpha=1;b.beginPath();b.moveTo(p,h);t&&(n.closePath(),n.fill(),n.beginPath(),n.moveTo(p,h))}delete B.dataPointIndexes}J.drawMarkers(e);b.restore();t&&n.restore();return{source:b,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,
-easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderBubble=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx,c=a.dataSeriesIndexes.length;if(!(0>=c)){var d=this.plotArea,e=0,f,g,k=0.15*this.width<<0,e=a.axisX.dataInfo.minDiff,c=0.9*(d.width/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(e)/c)<<0;b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());
-for(var p=-Infinity,h=Infinity,l=0;l<a.dataSeriesIndexes.length;l++)for(var r=a.dataSeriesIndexes[l],m=this.data[r],q=m.dataPoints,n=0,e=0;e<q.length;e++)f=q[e].getTime?f=q[e].x.getTime():f=q[e].x,f<a.axisX.dataInfo.viewPortMin||f>a.axisX.dataInfo.viewPortMax||"undefined"===typeof q[e].z||(n=q[e].z,n>p&&(p=n),n<h&&(h=n));for(var s=25*Math.PI,d=Math.max(Math.pow(0.25*Math.min(d.height,d.width)/2,2)*Math.PI,s),l=0;l<a.dataSeriesIndexes.length;l++)if(r=a.dataSeriesIndexes[l],m=this.data[r],q=m.dataPoints,
-1==q.length&&(c=k),1>c?c=1:c>k&&(c=k),0<q.length)for(b.strokeStyle="#4572A7 ",e=0;e<q.length;e++)if(f=q[e].getTime?f=q[e].x.getTime():f=q[e].x,!(f<a.axisX.dataInfo.viewPortMin||f>a.axisX.dataInfo.viewPortMax)&&"number"===typeof q[e].y){f=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(f-a.axisX.conversionParameters.minimum)+0.5<<0;g=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(q[e].y-a.axisY.conversionParameters.minimum)+0.5<<
-0;var n=q[e].z,B=2*Math.max(Math.sqrt((p===h?d/2:s+(d-s)/(p-h)*(n-h))/Math.PI)<<0,1),n=m.getMarkerProperties(e,b);n.size=B;b.globalAlpha=m.fillOpacity;J.drawMarker(f,g,b,n.type,n.size,n.color,n.borderColor,n.borderThickness);b.globalAlpha=1;var u=m.dataPointIds[e];this._eventManager.objectMap[u]={id:u,objectType:"dataPoint",dataSeriesIndex:r,dataPointIndex:e,x1:f,y1:g,size:B};B=C(u);t&&J.drawMarker(f,g,this._eventManager.ghostCtx,n.type,n.size,B,B,n.borderThickness);(q[e].indexLabel||m.indexLabel)&&
-this._indexLabels.push({chartType:"bubble",dataPoint:q[e],dataSeries:m,point:{x:f,y:g},direction:1,color:null})}b.restore();t&&this._eventManager.ghostCtx.restore();return{source:b,dest:this.plotArea.ctx,animationCallback:y.fadeInAnimation,easingFunction:y.easing.easeInQuad,animationBase:0}}};v.prototype.renderScatter=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx,c=a.dataSeriesIndexes.length;if(!(0>=c)){var d=this.plotArea,e=0,f,g,k=0.15*this.width<<0,e=a.axisX.dataInfo.minDiff,c=0.9*(d.width/
-Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(e)/c)<<0;b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(var p=0;p<a.dataSeriesIndexes.length;p++){var h=a.dataSeriesIndexes[p],l=this.data[h],r=l.dataPoints;1==r.length&&(c=k);1>c?c=1:c>k&&(c=k);if(0<r.length){b.strokeStyle="#4572A7 ";Math.pow(0.3*Math.min(d.height,d.width)/2,2);for(var m=
-0,q=0,e=0;e<r.length;e++)if(f=r[e].getTime?f=r[e].x.getTime():f=r[e].x,!(f<a.axisX.dataInfo.viewPortMin||f>a.axisX.dataInfo.viewPortMax)&&"number"===typeof r[e].y){f=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(f-a.axisX.conversionParameters.minimum)+0.5<<0;g=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(r[e].y-a.axisY.conversionParameters.minimum)+0.5<<0;var n=l.getMarkerProperties(e,f,g,b);b.globalAlpha=l.fillOpacity;J.drawMarker(n.x,
-n.y,n.ctx,n.type,n.size,n.color,n.borderColor,n.borderThickness);b.globalAlpha=1;Math.sqrt((m-f)*(m-f)+(q-g)*(q-g))<Math.min(n.size,5)&&r.length>Math.min(this.plotArea.width,this.plotArea.height)||(m=l.dataPointIds[e],this._eventManager.objectMap[m]={id:m,objectType:"dataPoint",dataSeriesIndex:h,dataPointIndex:e,x1:f,y1:g},m=C(m),t&&J.drawMarker(n.x,n.y,this._eventManager.ghostCtx,n.type,n.size,m,m,n.borderThickness),(r[e].indexLabel||l.indexLabel)&&this._indexLabels.push({chartType:"scatter",dataPoint:r[e],
-dataSeries:l,point:{x:f,y:g},direction:1,color:null}),m=f,q=g)}}}b.restore();t&&this._eventManager.ghostCtx.restore();return{source:b,dest:this.plotArea.ctx,animationCallback:y.fadeInAnimation,easingFunction:y.easing.easeInQuad,animationBase:0}}};v.prototype.renderCandlestick=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx,c=this._eventManager.ghostCtx;if(!(0>=a.dataSeriesIndexes.length)){var d=null,d=this.plotArea,e=0,f,g,k,p,h,l,e=0.015*this.width;f=a.axisX.dataInfo.minDiff;var r=0.7*d.width/
-Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(f)<<0;r>e?r=e:Infinity===f?r=e:1>r&&(r=1);b.save();t&&c.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(c.rect(d.x1,d.y1,d.width,d.height),c.clip());for(var m=0;m<a.dataSeriesIndexes.length;m++){var q=a.dataSeriesIndexes[m],n=this.data[q],s=n.dataPoints;if(0<s.length)for(var B=5<r&&n.bevelEnabled?!0:!1,e=0;e<s.length;e++)if(s[e].getTime?l=s[e].x.getTime():l=s[e].x,!(l<a.axisX.dataInfo.viewPortMin||l>a.axisX.dataInfo.viewPortMax)&&
-null!==s[e].y&&s[e].y.length&&"number"===typeof s[e].y[0]&&"number"===typeof s[e].y[1]&&"number"===typeof s[e].y[2]&&"number"===typeof s[e].y[3]){f=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(l-a.axisX.conversionParameters.minimum)+0.5<<0;g=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(s[e].y[0]-a.axisY.conversionParameters.minimum)+0.5<<0;k=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(s[e].y[1]-
-a.axisY.conversionParameters.minimum)+0.5<<0;p=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(s[e].y[2]-a.axisY.conversionParameters.minimum)+0.5<<0;h=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(s[e].y[3]-a.axisY.conversionParameters.minimum)+0.5<<0;var u=f-r/2<<0,x=u+r<<0,d=s[e].color?s[e].color:n._colorSet[0],w=Math.round(Math.max(1,0.15*r)),v=0===w%2?0:0.5,G=n.dataPointIds[e];this._eventManager.objectMap[G]={id:G,objectType:"dataPoint",
-dataSeriesIndex:q,dataPointIndex:e,x1:u,y1:g,x2:x,y2:k,x3:f,y3:p,x4:f,y4:h,borderThickness:w,color:d};b.strokeStyle=d;b.beginPath();b.lineWidth=w;c.lineWidth=Math.max(w,4);"candlestick"===n.type?(b.moveTo(f-v,k),b.lineTo(f-v,Math.min(g,h)),b.stroke(),b.moveTo(f-v,Math.max(g,h)),b.lineTo(f-v,p),b.stroke(),F(b,u,Math.min(g,h),x,Math.max(g,h),s[e].y[0]<=s[e].y[3]?n.risingColor:d,w,d,B,B,!1,!1,n.fillOpacity),t&&(d=C(G),c.strokeStyle=d,c.moveTo(f-v,k),c.lineTo(f-v,Math.min(g,h)),c.stroke(),c.moveTo(f-
-v,Math.max(g,h)),c.lineTo(f-v,p),c.stroke(),F(c,u,Math.min(g,h),x,Math.max(g,h),d,0,null,!1,!1,!1,!1))):"ohlc"===n.type&&(b.moveTo(f-v,k),b.lineTo(f-v,p),b.stroke(),b.beginPath(),b.moveTo(f,g),b.lineTo(u,g),b.stroke(),b.beginPath(),b.moveTo(f,h),b.lineTo(x,h),b.stroke(),t&&(d=C(G),c.strokeStyle=d,c.moveTo(f-v,k),c.lineTo(f-v,p),c.stroke(),c.beginPath(),c.moveTo(f,g),c.lineTo(u,g),c.stroke(),c.beginPath(),c.moveTo(f,h),c.lineTo(x,h),c.stroke()));(s[e].indexLabel||n.indexLabel)&&this._indexLabels.push({chartType:n.type,
-dataPoint:s[e],dataSeries:n,point:{x:u+(x-u)/2,y:k},direction:1,bounds:{x1:u,y1:Math.min(k,p),x2:x,y2:Math.max(k,p)},color:d})}}b.restore();t&&c.restore();return{source:b,dest:this.plotArea.ctx,animationCallback:y.fadeInAnimation,easingFunction:y.easing.easeInQuad,animationBase:0}}};v.prototype.renderRangeColumn=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=0,f,g,e=0.03*this.width;f=a.axisX.dataInfo.minDiff;var k=0.9*(d.width/
-Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(f)/a.plotType.totalDataSeries)<<0;k>e?k=e:Infinity===f?k=e:1>k&&(k=1);b.save();t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(var p=0;p<a.dataSeriesIndexes.length;p++){var h=a.dataSeriesIndexes[p],l=this.data[h],r=l.dataPoints;if(0<r.length)for(var m=5<k&&l.bevelEnabled?!0:!1,e=0;e<r.length;e++)if(r[e].getTime?
-g=r[e].x.getTime():g=r[e].x,!(g<a.axisX.dataInfo.viewPortMin||g>a.axisX.dataInfo.viewPortMax)&&null!==r[e].y&&r[e].y.length&&"number"===typeof r[e].y[0]&&"number"===typeof r[e].y[1]){c=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(g-a.axisX.conversionParameters.minimum)+0.5<<0;d=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(r[e].y[0]-a.axisY.conversionParameters.minimum)+0.5<<0;f=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*
-(r[e].y[1]-a.axisY.conversionParameters.minimum)+0.5<<0;var q=c-a.plotType.totalDataSeries*k/2+(a.previousDataSeriesCount+p)*k<<0,n=q+k<<0,c=r[e].color?r[e].color:l._colorSet[e%l._colorSet.length];if(d>f){var s=d,d=f;f=s}s=l.dataPointIds[e];this._eventManager.objectMap[s]={id:s,objectType:"dataPoint",dataSeriesIndex:h,dataPointIndex:e,x1:q,y1:d,x2:n,y2:f};F(b,q,d,n,f,c,0,c,m,m,!1,!1,l.fillOpacity);c=C(s);t&&F(this._eventManager.ghostCtx,q,d,n,f,c,0,null,!1,!1,!1,!1);if(r[e].indexLabel||l.indexLabel)this._indexLabels.push({chartType:"rangeColumn",
-dataPoint:r[e],dataSeries:l,indexKeyword:0,point:{x:q+(n-q)/2,y:r[e].y[1]>=r[e].y[0]?f:d},direction:r[e].y[1]>=r[e].y[0]?-1:1,bounds:{x1:q,y1:Math.min(d,f),x2:n,y2:Math.max(d,f)},color:c}),this._indexLabels.push({chartType:"rangeColumn",dataPoint:r[e],dataSeries:l,indexKeyword:1,point:{x:q+(n-q)/2,y:r[e].y[1]>=r[e].y[0]?d:f},direction:r[e].y[1]>=r[e].y[0]?1:-1,bounds:{x1:q,y1:Math.min(d,f),x2:n,y2:Math.max(d,f)},color:c})}}b.restore();t&&this._eventManager.ghostCtx.restore();return{source:b,dest:this.plotArea.ctx,
-animationCallback:y.fadeInAnimation,easingFunction:y.easing.easeInQuad,animationBase:0}}};v.prototype.renderRangeBar=function(a){var b=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var c=null,d=this.plotArea,e=0,f,g,k,e=Math.min(0.15*this.height,0.9*(this.plotArea.height/a.plotType.totalDataSeries))<<0;f=a.axisX.dataInfo.minDiff;var p=0.9*(d.height/Math.abs(a.axisX.maximum-a.axisX.minimum)*Math.abs(f)/a.plotType.totalDataSeries)<<0;p>e?p=e:Infinity===f?p=e:1>p&&(p=1);b.save();
-t&&this._eventManager.ghostCtx.save();b.beginPath();b.rect(d.x1,d.y1,d.width,d.height);b.clip();t&&(this._eventManager.ghostCtx.rect(d.x1,d.y1,d.width,d.height),this._eventManager.ghostCtx.clip());for(var h=0;h<a.dataSeriesIndexes.length;h++){var l=a.dataSeriesIndexes[h],r=this.data[l],m=r.dataPoints;if(0<m.length){var q=5<p&&r.bevelEnabled?!0:!1;b.strokeStyle="#4572A7 ";for(e=0;e<m.length;e++)if(m[e].getTime?k=m[e].x.getTime():k=m[e].x,!(k<a.axisX.dataInfo.viewPortMin||k>a.axisX.dataInfo.viewPortMax)&&
-null!==m[e].y&&m[e].y.length&&"number"===typeof m[e].y[0]&&"number"===typeof m[e].y[1]){d=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(m[e].y[0]-a.axisY.conversionParameters.minimum)+0.5<<0;f=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(m[e].y[1]-a.axisY.conversionParameters.minimum)+0.5<<0;g=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(k-a.axisX.conversionParameters.minimum)+0.5<<0;g=g-
-a.plotType.totalDataSeries*p/2+(a.previousDataSeriesCount+h)*p<<0;var n=g+p<<0;d>f&&(c=d,d=f,f=c);c=m[e].color?m[e].color:r._colorSet[e%r._colorSet.length];F(b,d,g,f,n,c,0,null,q,!1,!1,!1,r.fillOpacity);c=r.dataPointIds[e];this._eventManager.objectMap[c]={id:c,objectType:"dataPoint",dataSeriesIndex:l,dataPointIndex:e,x1:d,y1:g,x2:f,y2:n};c=C(c);t&&F(this._eventManager.ghostCtx,d,g,f,n,c,0,null,!1,!1,!1,!1);if(m[e].indexLabel||r.indexLabel)this._indexLabels.push({chartType:"rangeBar",dataPoint:m[e],
-dataSeries:r,indexKeyword:0,point:{x:m[e].y[1]>=m[e].y[0]?d:f,y:g+(n-g)/2},direction:m[e].y[1]>=m[e].y[0]?-1:1,bounds:{x1:Math.min(d,f),y1:g,x2:Math.max(d,f),y2:n},color:c}),this._indexLabels.push({chartType:"rangeBar",dataPoint:m[e],dataSeries:r,indexKeyword:1,point:{x:m[e].y[1]>=m[e].y[0]?f:d,y:g+(n-g)/2},direction:m[e].y[1]>=m[e].y[0]?1:-1,bounds:{x1:Math.min(d,f),y1:g,x2:Math.max(d,f),y2:n},color:c})}}}b.restore();t&&this._eventManager.ghostCtx.restore();return{source:b,dest:this.plotArea.ctx,
-animationCallback:y.fadeInAnimation,easingFunction:y.easing.easeInQuad,animationBase:0}}};v.prototype.renderRangeArea=function(a){function b(){if(v){var a=null;0<p.lineThickness&&c.stroke();for(var b=g.length-1;0<=b;b--)a=g[b],c.lineTo(a.x,a.y),d.lineTo(a.x,a.y);c.closePath();c.globalAlpha=p.fillOpacity;c.fill();c.globalAlpha=1;d.fill();if(0<p.lineThickness){c.beginPath();c.moveTo(a.x,a.y);for(b=0;b<g.length;b++)a=g[b],c.lineTo(a.x,a.y);c.stroke()}c.beginPath();c.moveTo(m,q);d.beginPath();d.moveTo(m,
-q);v={x:m,y:q};g=[];g.push({x:m,y:n})}}var c=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var d=this._eventManager.ghostCtx,e=[],f=this.plotArea;c.save();t&&d.save();c.beginPath();c.rect(f.x1,f.y1,f.width,f.height);c.clip();t&&(d.beginPath(),d.rect(f.x1,f.y1,f.width,f.height),d.clip());for(f=0;f<a.dataSeriesIndexes.length;f++){var g=[],k=a.dataSeriesIndexes[f],p=this.data[k],h=p.dataPoints,e=p.id;this._eventManager.objectMap[e]={objectType:"dataSeries",dataSeriesIndex:k};
-e=C(e);d.fillStyle=e;var e=[],l=!0,r=0,m,q,n,s,v=null;if(0<h.length){var u=p._colorSet[r%p._colorSet.length];c.fillStyle=u;c.strokeStyle=u;c.lineWidth=p.lineThickness;for(var x=!0;r<h.length;r++)if(s=h[r].x.getTime?h[r].x.getTime():h[r].x,!(s<a.axisX.dataInfo.viewPortMin||s>a.axisX.dataInfo.viewPortMax))if(null!==h[r].y&&h[r].y.length&&"number"===typeof h[r].y[0]&&"number"===typeof h[r].y[1]){m=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(s-a.axisX.conversionParameters.minimum)+
-0.5<<0;q=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(h[r].y[0]-a.axisY.conversionParameters.minimum)+0.5<<0;n=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(h[r].y[1]-a.axisY.conversionParameters.minimum)+0.5<<0;l||x?(c.beginPath(),c.moveTo(m,q),v={x:m,y:q},g=[],g.push({x:m,y:n}),t&&(d.beginPath(),d.moveTo(m,q)),x=l=!1):(c.lineTo(m,q),g.push({x:m,y:n}),t&&d.lineTo(m,q),0==r%250&&b());s=p.dataPointIds[r];this._eventManager.objectMap[s]=
-{id:s,objectType:"dataPoint",dataSeriesIndex:k,dataPointIndex:r,x1:m,y1:q,y2:n};if(0!==h[r].markerSize&&(0<h[r].markerSize||0<p.markerSize)){var w=p.getMarkerProperties(r,m,n,c);e.push(w);var z=C(s);t&&e.push({x:m,y:n,ctx:d,type:w.type,size:w.size,color:z,borderColor:z,borderThickness:w.borderThickness});w=p.getMarkerProperties(r,m,q,c);e.push(w);z=C(s);t&&e.push({x:m,y:q,ctx:d,type:w.type,size:w.size,color:z,borderColor:z,borderThickness:w.borderThickness})}if(h[r].indexLabel||p.indexLabel)this._indexLabels.push({chartType:"rangeArea",
-dataPoint:h[r],dataSeries:p,indexKeyword:0,point:{x:m,y:q},direction:h[r].y[0]<=h[r].y[1]?-1:1,color:u}),this._indexLabels.push({chartType:"rangeArea",dataPoint:h[r],dataSeries:p,indexKeyword:1,point:{x:m,y:n},direction:h[r].y[0]<=h[r].y[1]?1:-1,color:u})}else b(),x=!0;b();J.drawMarkers(e)}}c.restore();t&&this._eventManager.ghostCtx.restore();return{source:c,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};v.prototype.renderRangeSplineArea=
-function(a){function b(){var a=fa(q,2);if(0<a.length){c.beginPath();c.moveTo(a[0].x,a[0].y);t&&(d.beginPath(),d.moveTo(a[0].x,a[0].y));for(var b=0;b<a.length-3;b+=3)c.bezierCurveTo(a[b+1].x,a[b+1].y,a[b+2].x,a[b+2].y,a[b+3].x,a[b+3].y),t&&d.bezierCurveTo(a[b+1].x,a[b+1].y,a[b+2].x,a[b+2].y,a[b+3].x,a[b+3].y);0<k.lineThickness&&c.stroke();a=fa(n,2);c.lineTo(n[n.length-1].x,n[n.length-1].y);for(b=a.length-1;2<b;b-=3)c.bezierCurveTo(a[b-1].x,a[b-1].y,a[b-2].x,a[b-2].y,a[b-3].x,a[b-3].y),t&&d.bezierCurveTo(a[b-
-1].x,a[b-1].y,a[b-2].x,a[b-2].y,a[b-3].x,a[b-3].y);c.closePath();c.globalAlpha=k.fillOpacity;c.fill();c.globalAlpha=1;if(0<k.lineThickness){c.beginPath();c.moveTo(n[n.length-1].x,n[n.length-1].y);for(b=a.length-1;2<b;b-=3)c.bezierCurveTo(a[b-1].x,a[b-1].y,a[b-2].x,a[b-2].y,a[b-3].x,a[b-3].y),t&&d.bezierCurveTo(a[b-1].x,a[b-1].y,a[b-2].x,a[b-2].y,a[b-3].x,a[b-3].y);c.stroke()}c.beginPath();t&&(d.closePath(),d.fill())}}var c=a.targetCanvasCtx||this.plotArea.ctx;if(!(0>=a.dataSeriesIndexes.length)){var d=
-this._eventManager.ghostCtx,e=[],f=this.plotArea;c.save();t&&d.save();c.beginPath();c.rect(f.x1,f.y1,f.width,f.height);c.clip();t&&(d.beginPath(),d.rect(f.x1,f.y1,f.width,f.height),d.clip());for(f=0;f<a.dataSeriesIndexes.length;f++){var g=a.dataSeriesIndexes[f],k=this.data[g],p=k.dataPoints,e=k.id;this._eventManager.objectMap[e]={objectType:"dataSeries",dataSeriesIndex:g};e=C(e);d.fillStyle=e;var e=[],h=0,l,r,m,q=[],n=[];if(0<p.length){color=k._colorSet[h%k._colorSet.length];c.fillStyle=color;c.strokeStyle=
-color;for(c.lineWidth=k.lineThickness;h<p.length;h++)if(l=p[h].x.getTime?p[h].x.getTime():p[h].x,!(l<a.axisX.dataInfo.viewPortMin||l>a.axisX.dataInfo.viewPortMax))if(null!==p[h].y&&p[h].y.length&&"number"===typeof p[h].y[0]&&"number"===typeof p[h].y[1]){l=a.axisX.conversionParameters.reference+a.axisX.conversionParameters.pixelPerUnit*(l-a.axisX.conversionParameters.minimum)+0.5<<0;r=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(p[h].y[0]-a.axisY.conversionParameters.minimum)+
-0.5<<0;m=a.axisY.conversionParameters.reference+a.axisY.conversionParameters.pixelPerUnit*(p[h].y[1]-a.axisY.conversionParameters.minimum)+0.5<<0;var s=k.dataPointIds[h];this._eventManager.objectMap[s]={id:s,objectType:"dataPoint",dataSeriesIndex:g,dataPointIndex:h,x1:l,y1:r,y2:m};q[q.length]={x:l,y:r};n[n.length]={x:l,y:m};if(0!==p[h].markerSize&&(0<p[h].markerSize||0<k.markerSize)){var v=k.getMarkerProperties(h,l,r,c);e.push(v);var u=C(s);t&&e.push({x:l,y:r,ctx:d,type:v.type,size:v.size,color:u,
-borderColor:u,borderThickness:v.borderThickness});v=k.getMarkerProperties(h,l,m,c);e.push(v);u=C(s);t&&e.push({x:l,y:m,ctx:d,type:v.type,size:v.size,color:u,borderColor:u,borderThickness:v.borderThickness})}if(p[h].indexLabel||k.indexLabel)this._indexLabels.push({chartType:"splineArea",dataPoint:p[h],dataSeries:k,indexKeyword:0,point:{x:l,y:r},direction:p[h].y[0]<=p[h].y[1]?-1:1,color:color}),this._indexLabels.push({chartType:"splineArea",dataPoint:p[h],dataSeries:k,indexKeyword:1,point:{x:l,y:m},
-direction:p[h].y[0]<=p[h].y[1]?1:-1,color:color})}else 0<h&&(b(),q=[],n=[]);b();J.drawMarkers(e)}}c.restore();t&&this._eventManager.ghostCtx.restore();return{source:c,dest:this.plotArea.ctx,animationCallback:y.xClipAnimation,easingFunction:y.easing.linear,animationBase:0}}};var pa=function(a,b,c,d,e,f,g,k){"undefined"===typeof k&&(k=1);if(!t){var p=Number((g%(2*Math.PI)).toFixed(8));Number((f%(2*Math.PI)).toFixed(8))===p&&(g-=1E-4)}a.save();a.globalAlpha=k;"pie"===e?(a.beginPath(),a.moveTo(b.x,b.y),
-a.arc(b.x,b.y,c,f,g,!1),a.fillStyle=d,a.strokeStyle="white",a.lineWidth=2,a.closePath(),a.fill()):"doughnut"===e&&(a.beginPath(),a.arc(b.x,b.y,c,f,g,!1),a.arc(b.x,b.y,0.6*c,g,f,!0),a.closePath(),a.fillStyle=d,a.strokeStyle="white",a.lineWidth=2,a.fill());a.globalAlpha=1;a.restore()};v.prototype.renderPie=function(a){function b(){if(h&&l){var a=0,b=0,c=0,d=0;for(A=0;A<l.length;A++){var e=l[A],g=h.dataPointIds[A],f={id:g,objectType:"dataPoint",dataPointIndex:A,dataSeriesIndex:0};n.push(f);var k=e.indexLabel?
-e.indexLabel:h.indexLabel?h.indexLabel:e.label?e.label:h.label?h.label:"";p._eventManager.objectMap[g]=f;f.center={x:w.x,y:w.y};f.y=e.y;f.radius=y;f.indexLabelText=p.replaceKeywordsWithValue(k,e,h,A);f.indexLabelPlacement=h.indexLabelPlacement;f.indexLabelLineColor=e.indexLabelLineColor?e.indexLabelLineColor:h.indexLabelLineColor?h.indexLabelLineColor:e.color?e.color:h._colorSet[A%h._colorSet.length];f.indexLabelLineThickness=e.indexLabelLineThickness?e.indexLabelLineThickness:h.indexLabelLineThickness;
-f.indexLabelFontColor=e.indexLabelFontColor?e.indexLabelFontColor:h.indexLabelFontColor;f.indexLabelFontStyle=e.indexLabelFontStyle?e.indexLabelFontStyle:h.indexLabelFontStyle;f.indexLabelFontWeight=e.indexLabelFontWeight?e.indexLabelFontWeight:h.indexLabelFontWeight;f.indexLabelFontSize=e.indexLabelFontSize?e.indexLabelFontSize:h.indexLabelFontSize;f.indexLabelFontFamily=e.indexLabelFontFamily?e.indexLabelFontFamily:h.indexLabelFontFamily;f.indexLabelBackgroundColor=e.indexLabelBackgroundColor?e.indexLabelBackgroundColor:
-h.indexLabelBackgroundColor?h.indexLabelBackgroundColor:null;f.indexLabelMaxWidth=e.indexLabelMaxWidth?e.indexLabelMaxWidth:h.indexLabelMaxWidth?h.indexLabelMaxWidth:0.33*m.width;f.indexLabelWrap="undefined"!==typeof e.indexLabelWrap?e.indexLabelWrap:h.indexLabelWrap;f.startAngle=0===A?h.startAngle?h.startAngle/180*Math.PI:0:n[A-1].endAngle;f.startAngle=(f.startAngle+2*Math.PI)%(2*Math.PI);f.endAngle=f.startAngle+2*Math.PI/C*Math.abs(e.y);e=(f.endAngle+f.startAngle)/2;e=(e+2*Math.PI)%(2*Math.PI);
-f.midAngle=e;if(f.midAngle>Math.PI/2-u&&f.midAngle<Math.PI/2+u){if(0===a||n[c].midAngle>f.midAngle)c=A;a++}else if(f.midAngle>3*Math.PI/2-u&&f.midAngle<3*Math.PI/2+u){if(0===b||n[d].midAngle>f.midAngle)d=A;b++}f.hemisphere=e>Math.PI/2&&e<=3*Math.PI/2?"left":"right";f.indexLabelTextBlock=new I(p.plotArea.ctx,{fontSize:f.indexLabelFontSize,fontFamily:f.indexLabelFontFamily,fontColor:f.indexLabelFontColor,fontStyle:f.indexLabelFontStyle,fontWeight:f.indexLabelFontWeight,horizontalAlign:"left",backgroundColor:f.indexLabelBackgroundColor,
-maxWidth:f.indexLabelMaxWidth,maxHeight:f.indexLabelWrap?5*f.indexLabelFontSize:1.5*f.indexLabelFontSize,text:f.indexLabelText,padding:0,textBaseline:"top"});f.indexLabelTextBlock.measureText()}g=e=0;k=!1;for(A=0;A<l.length;A++)f=n[(c+A)%l.length],1<a&&(f.midAngle>Math.PI/2-u&&f.midAngle<Math.PI/2+u)&&(e<=a/2&&!k?(f.hemisphere="right",e++):(f.hemisphere="left",k=!0));k=!1;for(A=0;A<l.length;A++)f=n[(d+A)%l.length],1<b&&(f.midAngle>3*Math.PI/2-u&&f.midAngle<3*Math.PI/2+u)&&(g<=b/2&&!k?(f.hemisphere=
-"left",g++):(f.hemisphere="right",k=!0))}}function c(a){var b=p.plotArea.ctx;b.clearRect(m.x1,m.y1,m.width,m.height);b.fillStyle=p.backgroundColor;b.fillRect(m.x1,m.y1,m.width,m.height);for(b=0;b<l.length;b++){var c=n[b].startAngle,d=n[b].endAngle;if(d>c){var e=0.07*y*Math.cos(n[b].midAngle),f=0.07*y*Math.sin(n[b].midAngle),g=!1;if(l[b].exploded){if(1E-9<Math.abs(n[b].center.x-(w.x+e))||1E-9<Math.abs(n[b].center.y-(w.y+f)))n[b].center.x=w.x+e*a,n[b].center.y=w.y+f*a,g=!0}else if(0<Math.abs(n[b].center.x-
-w.x)||0<Math.abs(n[b].center.y-w.y))n[b].center.x=w.x+e*(1-a),n[b].center.y=w.y+f*(1-a),g=!0;g&&(e={},e.dataSeries=h,e.dataPoint=h.dataPoints[b],e.index=b,p._toolTip.highlightObjects([e]));pa(p.plotArea.ctx,n[b].center,n[b].radius,l[b].color?l[b].color:h._colorSet[b%h._colorSet.length],h.type,c,d,h.fillOpacity)}}a=p.plotArea.ctx;a.fillStyle="black";a.strokeStyle="grey";a.textBaseline="middle";a.lineJoin="round";for(b=b=0;b<l.length;b++)c=n[b],c.indexLabelText&&(c.indexLabelTextBlock.y-=c.indexLabelTextBlock.height/
-2,d=0,d="left"===c.hemisphere?"inside"!==h.indexLabelPlacement?-(c.indexLabelTextBlock.width+r):-c.indexLabelTextBlock.width/2:"inside"!==h.indexLabelPlacement?r:-c.indexLabelTextBlock.width/2,c.indexLabelTextBlock.x+=d,c.indexLabelTextBlock.render(!0),c.indexLabelTextBlock.x-=d,c.indexLabelTextBlock.y+=c.indexLabelTextBlock.height/2,"inside"!==c.indexLabelPlacement&&(d=c.center.x+y*Math.cos(c.midAngle),e=c.center.y+y*Math.sin(c.midAngle),a.strokeStyle=c.indexLabelLineColor,a.lineWidth=c.indexLabelLineThickness,
-a.beginPath(),a.moveTo(d,e),a.lineTo(c.indexLabelTextBlock.x,c.indexLabelTextBlock.y),a.lineTo(c.indexLabelTextBlock.x+("left"===c.hemisphere?-r:r),c.indexLabelTextBlock.y),a.stroke()),a.lineJoin="miter")}function d(a,b){var c=a.indexLabelTextBlock.x,d=a.indexLabelTextBlock.y-a.indexLabelTextBlock.height/2,e=a.indexLabelTextBlock.y+a.indexLabelTextBlock.height/2,f=b.indexLabelTextBlock.y-b.indexLabelTextBlock.height/2,g=b.indexLabelTextBlock.x+b.indexLabelTextBlock.width,l=b.indexLabelTextBlock.y+
-b.indexLabelTextBlock.height/2;return a.indexLabelTextBlock.x+a.indexLabelTextBlock.width<b.indexLabelTextBlock.x-r||c>g+r||d>l+r||e<f-r?!1:!0}function e(a,b){var c=0,c=a.indexLabelTextBlock.y-a.indexLabelTextBlock.height/2,d=a.indexLabelTextBlock.y+a.indexLabelTextBlock.height/2,e=b.indexLabelTextBlock.y-b.indexLabelTextBlock.height/2,f=b.indexLabelTextBlock.y+b.indexLabelTextBlock.height/2;return c=b.indexLabelTextBlock.y>a.indexLabelTextBlock.y?e-d:c-f}function f(a){for(var b=null,c=1;c<l.length;c++)if(b=
-(a+c+n.length)%n.length,n[b].hemisphere!==n[a].hemisphere){b=null;break}else if(n[b].indexLabelText&&b!==a&&(0>e(n[b],n[a])||("right"===n[a].hemisphere?n[b].indexLabelTextBlock.y>=n[a].indexLabelTextBlock.y:n[b].indexLabelTextBlock.y<=n[a].indexLabelTextBlock.y)))break;else b=null;return b}function g(a,b){b=b||0;var c=0,d=w.y-1*z,h=w.y+1*z;if(0<=a&&a<l.length){var m=n[a];if(0>b&&m.indexLabelTextBlock.y<d||0<b&&m.indexLabelTextBlock.y>h)return 0;var k=b,p=0,r=0,r=p=p=0;0>k?m.indexLabelTextBlock.y-
-m.indexLabelTextBlock.height/2>d&&m.indexLabelTextBlock.y-m.indexLabelTextBlock.height/2+k<d&&(k=-(d-(m.indexLabelTextBlock.y-m.indexLabelTextBlock.height/2+k))):m.indexLabelTextBlock.y+m.indexLabelTextBlock.height/2<d&&m.indexLabelTextBlock.y+m.indexLabelTextBlock.height/2+k>h&&(k=m.indexLabelTextBlock.y+m.indexLabelTextBlock.height/2+k-h);k=m.indexLabelTextBlock.y+k;d=0;d="right"===m.hemisphere?w.x+Math.sqrt(Math.pow(z,2)-Math.pow(k-w.y,2)):w.x-Math.sqrt(Math.pow(z,2)-Math.pow(k-w.y,2));r=w.x+y*
-Math.cos(m.midAngle);p=w.y+y*Math.sin(m.midAngle);p=Math.sqrt(Math.pow(d-r,2)+Math.pow(k-p,2));r=Math.acos(y/z);p=Math.acos((z*z+y*y-p*p)/(2*y*z));k=p<r?k-m.indexLabelTextBlock.y:0;d=null;for(h=1;h<l.length;h++)if(d=(a-h+n.length)%n.length,n[d].hemisphere!==n[a].hemisphere){d=null;break}else if(n[d].indexLabelText&&n[d].hemisphere===n[a].hemisphere&&d!==a&&(0>e(n[d],n[a])||("right"===n[a].hemisphere?n[d].indexLabelTextBlock.y<=n[a].indexLabelTextBlock.y:n[d].indexLabelTextBlock.y>=n[a].indexLabelTextBlock.y)))break;
-else d=null;r=d;p=f(a);h=d=0;0>k?(h="right"===m.hemisphere?r:p,c=k,null!==h&&(r=-k,k=m.indexLabelTextBlock.y-m.indexLabelTextBlock.height/2-(n[h].indexLabelTextBlock.y+n[h].indexLabelTextBlock.height/2),k-r<s&&(d=-r,q++,h=g(h,d),+h.toFixed(v)>+d.toFixed(v)&&(c=k>s?-(k-s):-(r-(h-d)))))):0<k&&(h="right"===m.hemisphere?p:r,c=k,null!==h&&(r=k,k=n[h].indexLabelTextBlock.y-n[h].indexLabelTextBlock.height/2-(m.indexLabelTextBlock.y+m.indexLabelTextBlock.height/2),k-r<s&&(d=r,q++,h=g(h,d),+h.toFixed(v)<+d.toFixed(v)&&
-(c=k>s?k-s:r-(d-h)))));c&&(k=m.indexLabelTextBlock.y+c,d=0,d="right"===m.hemisphere?w.x+Math.sqrt(Math.pow(z,2)-Math.pow(k-w.y,2)):w.x-Math.sqrt(Math.pow(z,2)-Math.pow(k-w.y,2)),m.midAngle>Math.PI/2-u&&m.midAngle<Math.PI/2+u?(h=(a-1+n.length)%n.length,h=n[h],r=n[(a+1+n.length)%n.length],"left"===m.hemisphere&&"right"===h.hemisphere&&d>h.indexLabelTextBlock.x?d=h.indexLabelTextBlock.x-15:"right"===m.hemisphere&&("left"===r.hemisphere&&d<r.indexLabelTextBlock.x)&&(d=r.indexLabelTextBlock.x+15)):m.midAngle>
-3*Math.PI/2-u&&m.midAngle<3*Math.PI/2+u&&(h=(a-1+n.length)%n.length,h=n[h],r=n[(a+1+n.length)%n.length],"right"===m.hemisphere&&"left"===h.hemisphere&&d<h.indexLabelTextBlock.x?d=h.indexLabelTextBlock.x+15:"left"===m.hemisphere&&("right"===r.hemisphere&&d>r.indexLabelTextBlock.x)&&(d=r.indexLabelTextBlock.x-15)),m.indexLabelTextBlock.y=k,m.indexLabelTextBlock.x=d,m.indexLabelAngle=Math.atan2(m.indexLabelTextBlock.y-w.y,m.indexLabelTextBlock.x-w.x))}return c}function k(){var a=p.plotArea.ctx;a.fillStyle=
-"grey";a.strokeStyle="grey";a.font="16px Arial";a.textBaseline="middle";for(var b=0,c=a=0,a=0;10>a&&(1>a||0<c);a++){y-=c;c=0;if("inside"!==h.indexLabelPlacement){z=y*t;for(b=0;b<l.length;b++){var k=n[b];k.indexLabelTextBlock.x=w.x+z*Math.cos(k.midAngle);k.indexLabelTextBlock.y=w.y+z*Math.sin(k.midAngle);k.indexLabelAngle=k.midAngle;k.radius=y}for(var q,u,b=0;b<l.length;b++){var k=n[b],A=f(b);if(null!==A){q=n[b];u=n[A];var D=0,D=e(q,u)-s;if(0>D){for(var C=u=q=0;C<l.length;C++)C!==b&&n[C].hemisphere===
-k.hemisphere&&(n[C].indexLabelTextBlock.y<k.indexLabelTextBlock.y?q++:u++);C=D/(q+u||1)*u;q=-1*(D-C);var E=u=0;"right"===k.hemisphere?(u=g(b,C),q=-1*(D-u),E=g(A,q),+E.toFixed(v)<+q.toFixed(v)&&+u.toFixed(v)<=+C.toFixed(v)&&g(b,-(q-E))):(u=g(A,C),q=-1*(D-u),E=g(b,q),+E.toFixed(v)<+q.toFixed(v)&&+u.toFixed(v)<=+C.toFixed(v)&&g(A,-(q-E)))}}}}else for(b=0;b<l.length;b++)k=n[b],z="pie"===h.type?0.7*y:0.8*y,D=w.x+z*Math.cos(k.midAngle),C=w.y+z*Math.sin(k.midAngle),k.indexLabelTextBlock.x=D,k.indexLabelTextBlock.y=
-C;for(b=0;b<l.length;b++)k=n[b],D=k.indexLabelTextBlock.measureText(),0!==D.height&&0!==D.width&&(D=D=0,"right"===k.hemisphere?(D=m.x2-(k.indexLabelTextBlock.x+k.indexLabelTextBlock.width+r),D*=-1):D=m.x1-(k.indexLabelTextBlock.x-k.indexLabelTextBlock.width-r),0<D&&(Math.abs(k.indexLabelTextBlock.y-k.indexLabelTextBlock.height/2-w.y)<y||Math.abs(k.indexLabelTextBlock.y+k.indexLabelTextBlock.height/2-w.y)<y)&&(D/=Math.abs(Math.cos(k.indexLabelAngle)),9<D&&(D*=0.3),D>c&&(c=D)),D=D=0,0<k.indexLabelAngle&&
-k.indexLabelAngle<Math.PI?(D=m.y2-(k.indexLabelTextBlock.y+k.indexLabelTextBlock.height/2+5),D*=-1):D=m.y1-(k.indexLabelTextBlock.y-k.indexLabelTextBlock.height/2-5),0<D&&Math.abs(k.indexLabelTextBlock.x-w.x)<y&&(D/=Math.abs(Math.sin(k.indexLabelAngle)),9<D&&(D*=0.3),D>c&&(c=D)));b=function(a,b,c){for(var d=[],e=0;d.push(n[b]),b!==c;b=(b+1+l.length)%l.length);d.sort(function(a,b){return a.y-b.y});for(b=0;b<d.length;b++)if(c=d[b],e<a)e+=c.indexLabelTextBlock.height,c.indexLabelTextBlock.text="",c.indexLabelText=
-"",c.indexLabelTextBlock.measureText();else break};A=k=-1;for(C=E=0;C<l.length;C++)if(q=n[C],q.indexLabelText){var F=f(C);null!==F&&(u=n[F],D=0,D=e(q,u),0>D&&d(q,u)?(0>k&&(k=C),F!==k&&(A=F),E+=-D):0<E&&(b(E,k,A),A=k=-1,E=0))}0<E&&b(E,k,A)}}var p=this;if(!(0>=a.dataSeriesIndexes.length)){for(var h=this.data[a.dataSeriesIndexes[0]],l=h.dataPoints,r=10,m=this.plotArea,q=0,n=[],s=2,t=1.3,u=20/180*Math.PI,v=6,w={x:(m.x2+m.x1)/2,y:(m.y2+m.y1)/2},y="inside"===h.indexLabelPlacement?0.92*Math.min(m.width,
-m.height)/2:0.8*Math.min(m.width,m.height)/2,z=y*t,C=0,A=0;A<l.length;A++)C+=Math.abs(l[A].y);0!==C&&(this.pieDoughnutClickHandler=function(a){p.isAnimating||(a=a.dataPoint,a.exploded=a.exploded?!1:!0,1<this.dataPoints.length&&p._animator.animate(0,500,function(a){c(a)}))},b(),k(),this.disableToolTip=!0,this._animator.animate(0,this.animatedRender?this.animationDuration:0,function(a){var b=p.plotArea.ctx;b.clearRect(m.x1,m.y1,m.width,m.height);b.fillStyle=p.backgroundColor;b.fillRect(m.x1,m.y1,m.width,
-m.height);a=n[0].startAngle+2*Math.PI*a;for(b=0;b<l.length;b++){var c=0===b?n[b].startAngle:d,d=c+(n[b].endAngle-n[b].startAngle),e=!1;d>a&&(d=a,e=!0);var f=l[b].color?l[b].color:h._colorSet[b%h._colorSet.length];d>c&&pa(p.plotArea.ctx,n[b].center,n[b].radius,f,h.type,c,d,h.fillOpacity);if(e)break}},function(){p.disableToolTip=!1;p._animator.animate(0,p.animatedRender?500:0,function(a){c(a)})}))}};v.prototype.animationRequestId=null;v.prototype.requestAnimFrame=function(){return window.requestAnimationFrame||
-window.webkitRequestAnimationFrame||window.mozRequestAnimationFrame||window.oRequestAnimationFrame||window.msRequestAnimationFrame||function(a){window.setTimeout(a,1E3/60)}}();v.prototype.cancelRequestAnimFrame=window.cancelAnimationFrame||window.webkitCancelRequestAnimationFrame||window.mozCancelRequestAnimationFrame||window.oCancelRequestAnimationFrame||window.msCancelRequestAnimationFrame||clearTimeout;aa.prototype.registerSpace=function(a,b){"top"===a?this._topOccupied+=b.height:"bottom"===a?
-this._bottomOccupied+=b.height:"left"===a?this._leftOccupied+=b.width:"right"===a&&(this._rightOccupied+=b.width)};aa.prototype.unRegisterSpace=function(a,b){"top"===a?this._topOccupied-=b.height:"bottom"===a?this._bottomOccupied-=b.height:"left"===a?this._leftOccupied-=b.width:"right"===a&&(this._rightOccupied-=b.width)};aa.prototype.getFreeSpace=function(){return{x1:this._leftOccupied,y1:this._topOccupied,x2:this.chart.width-this._rightOccupied,y2:this.chart.height-this._bottomOccupied,width:this.chart.width-
-this._rightOccupied-this._leftOccupied,height:this.chart.height-this._bottomOccupied-this._topOccupied}};aa.prototype.reset=function(){this._topOccupied=0;this._bottomOccupied=3;this._rightOccupied=this._leftOccupied=0};O(I,L);I.prototype.render=function(a){a&&this.ctx.save();var b=this.ctx.font;this.ctx.textBaseline=this.textBaseline;var c=0;this._isDirty&&this.measureText(this.ctx);this.ctx.translate(this.x,this.y+c);"middle"===this.textBaseline&&(c=-this._lineHeight/2);this.ctx.font=this._getFontString();
-this.ctx.rotate(Math.PI/180*this.angle);var d=0,e=this.padding,f=null;(0<this.borderThickness&&this.borderColor||this.backgroundColor)&&this.ctx.roundRect(0,c,this.width,this.height,this.cornerRadius,this.borderThickness,this.backgroundColor,this.borderColor);this.ctx.fillStyle=this.fontColor;for(c=0;c<this._wrappedText.lines.length;c++)f=this._wrappedText.lines[c],"right"===this.horizontalAlign?d=this.width-f.width-this.padding:"left"===this.horizontalAlign?d=this.padding:"center"===this.horizontalAlign&&
-(d=(this.width-2*this.padding)/2-f.width/2+this.padding),this.ctx.fillText(f.text,d,e),e+=f.height;this.ctx.font=b;a&&this.ctx.restore()};I.prototype.setText=function(a){this.text=a;this._isDirty=!0;this._wrappedText=null};I.prototype.measureText=function(){if(null===this.maxWidth)throw"Please set maxWidth and height for TextBlock";this._wrapText(this.ctx);this._isDirty=!1;return{width:this.width,height:this.height}};I.prototype._getLineWithWidth=function(a,b,c){a=String(a);if(!a)return{text:"",width:0};
-var d=c=0,e=a.length-1,f=Infinity;for(this.ctx.font=this._getFontString();d<=e;){var f=Math.floor((d+e)/2),g=a.substr(0,f+1);c=this.ctx.measureText(g).width;if(c<b)d=f+1;else if(c>b)e=f-1;else break}c>b&&1<g.length&&(g=g.substr(0,g.length-1),c=this.ctx.measureText(g).width);b=!0;if(g.length===a.length||" "===a[g.length])b=!1;b&&(a=g.split(" "),1<a.length&&a.pop(),g=a.join(" "),c=this.ctx.measureText(g).width);return{text:g,width:c}};I.prototype._wrapText=function(){var a=new String(Z(this.text)),
-b=[],c=this.ctx.font,d=0,e=0;for(this.ctx.font=this._getFontString();0<a.length;){var f=this.maxHeight-2*this.padding,g=this._getLineWithWidth(a,this.maxWidth-2*this.padding,!1);g.height=this._lineHeight;b.push(g);e=Math.max(e,g.width);d+=g.height;a=Z(a.slice(g.text.length,a.length));f&&d>f&&(g=b.pop(),d-=g.height)}this._wrappedText={lines:b,width:e,height:d};this.width=e+2*this.padding;this.height=d+2*this.padding;this.ctx.font=c};I.prototype._getFontString=function(){return ua("",this,null)};O(ba,
-L);ba.prototype.render=function(){if(this.text){var a=this.chart.layoutManager.getFreeSpace(),b=0,c=0,d=0,e=0,f=0,g,k;"top"===this.verticalAlign||"bottom"===this.verticalAlign?(e=a.width-2*this.margin,f=0.5*a.height-2*this.margin,d=0):"center"===this.verticalAlign&&("left"===this.horizontalAlign||"right"===this.horizontalAlign?(e=a.height-2*this.margin,f=0.5*a.width-2*this.margin):"center"===this.horizontalAlign&&(e=a.width-2*this.margin,f=0.5*a.height-2*this.margin));var f=new I(this.ctx,{fontSize:this.fontSize,
-fontFamily:this.fontFamily,fontColor:this.fontColor,fontStyle:this.fontStyle,fontWeight:this.fontWeight,horizontalAlign:this.horizontalAlign,verticalAlign:this.verticalAlign,borderColor:this.borderColor,borderThickness:this.borderThickness,backgroundColor:this.backgroundColor,maxWidth:e,maxHeight:f,cornerRadius:this.cornerRadius,text:this.text,padding:this.padding,textBaseline:"top"}),p=f.measureText();"top"===this.verticalAlign||"bottom"===this.verticalAlign?("top"===this.verticalAlign?(c=this.margin,
-k="top"):"bottom"===this.verticalAlign&&(c=a.y2-this.margin-p.height,k="bottom"),"left"===this.horizontalAlign?b=a.x1+this.margin:"center"===this.horizontalAlign?b=a.x1+(e/2-p.width/2)+this.margin:"right"===this.horizontalAlign&&(b=a.x2-this.margin-p.width),g=this.horizontalAlign,this.width=p.width,this.height=p.height):"center"===this.verticalAlign&&("left"===this.horizontalAlign?(b=a.x1+this.margin,c=a.y2-this.margin-(e/2-p.width/2),d=-90,k="left",this.width=p.height,this.height=p.width):"right"===
-this.horizontalAlign?(b=a.x2-this.margin,c=a.y1+this.margin+(e/2-p.width/2),d=90,k="right",this.width=p.height,this.height=p.width):"center"===this.horizontalAlign&&(c=a.y1+(a.height/2-p.height/2),b=a.x1+(a.width/2-p.width/2),k="center",this.width=p.width,this.height=p.height),g="center");f.x=b;f.y=c;f.angle=d;f.horizontalAlign=g;f.render(!0);this.chart.layoutManager.registerSpace(k,{width:this.width+2*this.margin,height:this.height+2*this.margin});this.bounds={x1:b,y1:c,x2:b+this.width,y2:c+this.height};
-this.ctx.textBaseline="top"}};O(ga,L);ga.prototype.render=function(){var a=this.chart.layoutManager.getFreeSpace(),b=null,c=0,d=0,e=0,f=0,g=[],k=[];"top"===this.verticalAlign||"bottom"===this.verticalAlign?(this.orientation="horizontal",b=this.verticalAlign,e=0.9*a.width,f=0.5*a.height):"center"===this.verticalAlign&&(this.orientation="vertical",b=this.horizontalAlign,e=0.5*a.width,f=0.9*a.height);for(var p=0;p<this.dataSeries.length;p++){var h=this.dataSeries[p],l=h.legendMarkerType?h.legendMarkerType:
-"line"!==h.type&&"stepLine"!==h.type&&"spline"!==h.type&&"scatter"!==h.type&&"bubble"!==h.type||!h.markerType?P.getDefaultLegendMarker(h.type):h.markerType,r=h.legendText?h.legendText:h.name,m=h.legendMarkerColor?h.legendMarkerColor:h.markerColor?h.markerColor:h._colorSet[0],q=h.markerSize||"line"!==h.type&&"stepLine"!==h.type&&"spline"!==h.type?0.6*this.lineHeight:0,n=h.legendMarkerBorderColor?h.legendMarkerBorderColor:h.markerBorderColor,s=h.legendMarkerBorderThickness?h.legendMarkerBorderThickness:
-h.markerBorderThickness?Math.max(1,Math.round(0.2*q)):0;if("pie"!==h.type&&"doughnut"!==h.type&&"funnel"!==h.type)l={markerType:l,markerColor:m,text:r,textBlock:null,chartType:h.type,markerSize:q,lineColor:h._colorSet[0],dataSeriesIndex:h.index,dataPointIndex:null,markerBorderColor:n,markerBorderThickness:s},g.push(l);else for(var t=0;t<h.dataPoints.length;t++)s=h.dataPoints[t],l=s.legendMarkerType?s.legendMarkerType:h.legendMarkerType?h.legendMarkerType:P.getDefaultLegendMarker(h.type),r=s.legendText?
-s.legendText:h.legendText?h.legendText:s.name?s.name:"DataPoint: "+(t+1),m=s.legendMarkerColor?s.legendMarkerColor:h.legendMarkerColor?h.legendMarkerColor:s.color?s.color:h.color?h.color:h._colorSet[t%h._colorSet.length],q=0===s.markerSize||0===h.markerSize&&!s.markerSize?0:0.6*this.lineHeight,n=s.legendMarkerBorderColor?s.legendMarkerBorderColor:h.legendMarkerBorderColor?h.legendMarkerBorderColor:s.markerBorderColor?s.markerBorderColor:h.markerBorderColor,s=s.legendMarkerBorderThickness?s.legendMarkerBorderThickness:
-h.legendMarkerBorderThickness?h.legendMarkerBorderThickness:s.markerBorderThickness||h.markerBorderThickness?Math.max(1,Math.round(0.2*q)):0,l={markerType:l,markerColor:m,text:r,textBlock:null,chartType:h.type,markerSize:q,dataSeriesIndex:p,dataPointIndex:t,markerBorderColor:n,markerBorderThickness:s},g.push(l)}if(0<g.length){h=null;for(p=t=0;p<g.length;p++){l=g[p];if("horizontal"===this.orientation){l.textBlock=new I(this.ctx,{x:0,y:0,maxWidth:e,maxHeight:this.lineHeight,angle:0,text:l.text,horizontalAlign:"left",
-fontSize:this.fontSize,fontFamily:this.fontFamily,fontWeight:this.fontWeight,fontColor:this.fontColor,fontStyle:this.fontStyle,textBaseline:"top"});l.textBlock.measureText();if(!h||h.width+l.textBlock.width+(0===h.width?0:this.horizontalSpacing)>e)h={items:[],width:0},k.push(h),this.height=k.length*(l.textBlock.height+5);l.textBlock.x=h.width;l.textBlock.y=0;h.width+=Math.round(l.textBlock.width+l.textBlock._lineHeight+(0===h.width?0:0.5*l.textBlock._lineHeight))}else this.height+this.lineHeight<
-f?(h={items:[],width:0},k.push(h),this.height=k.length*this.lineHeight):(h=k[t],t=(t+1)%k.length),l.textBlock=new I(this.ctx,{x:0,y:0,maxWidth:e,maxHeight:1.5*this.fontSize,angle:0,text:l.text,horizontalAlign:"left",fontSize:this.fontSize,fontFamily:this.fontFamily,fontWeight:this.fontWeight,fontColor:this.fontColor,fontStyle:this.fontStyle,textBaseline:"top"}),l.textBlock.measureText(),l.textBlock.x=h.width,l.textBlock.y=0,h.width+=l.textBlock.width+l.textBlock._lineHeight+(0===h.width?0:0.5*l.textBlock._lineHeight);
-h.items.push(l);this.width=Math.max(h.width,this.width)}this.height=k.length*this.lineHeight}"top"===this.verticalAlign?(d="left"===this.horizontalAlign?a.x1+2:"right"===this.horizontalAlign?a.x2-this.width-2:a.x1+a.width/2-this.width/2,c=a.y1):"center"===this.verticalAlign?(d="left"===this.horizontalAlign?a.x1+2:"right"===this.horizontalAlign?a.x2-this.width-2:a.x1+a.width/2-this.width/2,c=a.y1+a.height/2-this.height/2):"bottom"===this.verticalAlign&&(d="left"===this.horizontalAlign?a.x1+2:"right"===
-this.horizontalAlign?a.x2-this.width-2:a.x1+a.width/2-this.width/2,c=a.y2-this.height-5);this.items=g;for(p=0;p<this.items.length;p++)l=g[p],l.id=++this.chart._eventManager.lastObjectId,this.chart._eventManager.objectMap[l.id]={id:l.id,objectType:"legendItem",legendItemIndex:p,dataSeriesIndex:l.dataSeriesIndex,dataPointIndex:l.dataPointIndex};for(p=0;p<k.length;p++)for(h=k[p],a=0;a<h.items.length;a++){l=h.items[a];f=l.textBlock.x+d+(0===a?0.2*l.markerSize:0.4*this.lineHeight+0.2*l.markerSize);g=c+
-p*this.lineHeight;e=f;this.chart.data[l.dataSeriesIndex].visible||(this.ctx.globalAlpha=0.5);if("line"===l.chartType||"stepLine"===l.chartType||"spline"===l.chartType)this.ctx.strokeStyle=l.lineColor,this.ctx.lineWidth=Math.ceil(this.lineHeight/8),this.ctx.beginPath(),this.ctx.moveTo(f-0.1*this.lineHeight,g+this.lineHeight/2),this.ctx.lineTo(f+0.7*this.lineHeight,g+this.lineHeight/2),this.ctx.stroke(),e-=0.1*this.lineHeight;J.drawMarker(f+l.markerSize/2,g+this.lineHeight/2,this.ctx,l.markerType,l.markerSize,
-l.markerColor,l.markerBorderColor,l.markerBorderThickness);l.textBlock.x=f+Math.round(0.9*this.lineHeight);l.textBlock.y=g;l.textBlock.render(!0);this.chart.data[l.dataSeriesIndex].visible||(this.ctx.globalAlpha=1);f=C(l.id);this.ghostCtx.fillStyle=f;this.ghostCtx.beginPath();this.ghostCtx.fillRect(e,l.textBlock.y,l.textBlock.x+l.textBlock.width-e,l.textBlock.height);l.x1=this.chart._eventManager.objectMap[l.id].x1=e;l.y1=this.chart._eventManager.objectMap[l.id].y1=l.textBlock.y;l.x2=this.chart._eventManager.objectMap[l.id].x2=
-l.textBlock.x+l.textBlock.width;l.y2=this.chart._eventManager.objectMap[l.id].y2=l.textBlock.y+l.textBlock.height}this.chart.layoutManager.registerSpace(b,{width:this.width+2+2,height:this.height+5+5});this.bounds={x1:d,y1:c,x2:d+this.width,y2:c+this.height}};O(la,L);la.prototype.render=function(){var a=this.chart.layoutManager.getFreeSpace();this.ctx.fillStyle="red";this.ctx.fillRect(a.x1,a.y1,a.x2,a.y2)};O(P,L);P.prototype.getDefaultAxisPlacement=function(){var a=this.type;if("column"===a||"line"===
-a||"stepLine"===a||"spline"===a||"area"===a||"stepArea"===a||"splineArea"===a||"stackedColumn"===a||"stackedLine"===a||"bubble"===a||"scatter"===a||"stackedArea"===a||"stackedColumn100"===a||"stackedLine100"===a||"stackedArea100"===a||"candlestick"===a||"ohlc"===a||"rangeColumn"===a||"rangeArea"===a||"rangeSplineArea"===a)return"normal";if("bar"===a||"stackedBar"===a||"stackedBar100"===a||"rangeBar"===a)return"xySwapped";if("pie"===a||"doughnut"===a||"funnel"===a)return"none";window.console.log("Unknown Chart Type: "+
-a);return null};P.getDefaultLegendMarker=function(a){if("column"===a||"stackedColumn"===a||"stackedLine"===a||"bar"===a||"stackedBar"===a||"stackedBar100"===a||"bubble"===a||"scatter"===a||"stackedColumn100"===a||"stackedLine100"===a||"stepArea"===a||"candlestick"===a||"ohlc"===a||"rangeColumn"===a||"rangeBar"===a||"rangeArea"===a||"rangeSplineArea"===a)return"square";if("line"===a||"stepLine"===a||"spline"===a||"pie"===a||"doughnut"===a||"funnel"===a)return"circle";if("area"===a||"splineArea"===
-a||"stackedArea"===a||"stackedArea100"===a)return"triangle";window.console.log("Unknown Chart Type: "+a);return null};P.prototype.getDataPointAtX=function(a,b){if(!this.dataPoints||0===this.dataPoints.length)return null;var c={dataPoint:null,distance:Infinity,index:NaN},d=null,e=0,f=0,g=1,k=Infinity,p=0,h=0,l=0;"none"!==this.chart.plotInfo.axisPlacement&&(l=this.dataPoints[this.dataPoints.length-1].x-this.dataPoints[0].x,l=0<l?Math.min(Math.max((this.dataPoints.length-1)/l*(a-this.dataPoints[0].x)>>
-0,0),this.dataPoints.length):0);for(;;){f=0<g?l+e:l-e;if(0<=f&&f<this.dataPoints.length){var d=this.dataPoints[f],r=Math.abs(d.x-a);r<c.distance&&(c.dataPoint=d,c.distance=r,c.index=f);d=Math.abs(d.x-a);d<=k?k=d:0<g?p++:h++;if(1E3<p&&1E3<h)break}else if(0>l-e&&l+e>=this.dataPoints.length)break;-1===g?(e++,g=1):g=-1}return b||c.dataPoint.x!==a?b&&null!==c.dataPoint?c:null:c};P.prototype.getDataPointAtXY=function(a,b,c){if(!this.dataPoints||0===this.dataPoints.length)return null;c=c||!1;var d=[],e=
-0,f=0,g=1,k=!1,p=Infinity,h=0,l=0,r=0;"none"!==this.chart.plotInfo.axisPlacement&&(r=this.chart.axisX.getXValueAt({x:a,y:b}),f=this.dataPoints[this.dataPoints.length-1].x-this.dataPoints[0].x,r=0<f?Math.min(Math.max((this.dataPoints.length-1)/f*(r-this.dataPoints[0].x)>>0,0),this.dataPoints.length):0);for(;;){f=0<g?r+e:r-e;if(0<=f&&f<this.dataPoints.length){var m=this.chart._eventManager.objectMap[this.dataPointIds[f]],q=this.dataPoints[f],n=null;if(m){switch(this.type){case "column":case "stackedColumn":case "stackedColumn100":case "bar":case "stackedBar":case "stackedBar100":case "rangeColumn":case "rangeBar":a>=
-m.x1&&(a<=m.x2&&b>=m.y1&&b<=m.y2)&&(d.push({dataPoint:q,dataPointIndex:f,dataSeries:this,distance:Math.min(Math.abs(m.x1-a),Math.abs(m.x2-a),Math.abs(m.y1-b),Math.abs(m.y2-b))}),k=!0);break;case "line":case "stepLine":case "spline":case "area":case "stepArea":case "stackedArea":case "stackedArea100":case "splineArea":case "scatter":var s=T("markerSize",q,this)||4,t=c?20:s,n=Math.sqrt(Math.pow(m.x1-a,2)+Math.pow(m.y1-b,2));n<=t&&d.push({dataPoint:q,dataPointIndex:f,dataSeries:this,distance:n});f=Math.abs(m.x1-
-a);f<=p?p=f:0<g?h++:l++;n<=s/2&&(k=!0);break;case "rangeArea":case "rangeSplineArea":s=T("markerSize",q,this)||4;t=c?20:s;n=Math.min(Math.sqrt(Math.pow(m.x1-a,2)+Math.pow(m.y1-b,2)),Math.sqrt(Math.pow(m.x1-a,2)+Math.pow(m.y2-b,2)));n<=t&&d.push({dataPoint:q,dataPointIndex:f,dataSeries:this,distance:n});f=Math.abs(m.x1-a);f<=p?p=f:0<g?h++:l++;n<=s/2&&(k=!0);break;case "bubble":s=m.size;n=Math.sqrt(Math.pow(m.x1-a,2)+Math.pow(m.y1-b,2));n<=s/2&&(d.push({dataPoint:q,dataPointIndex:f,dataSeries:this,
-distance:n}),k=!0);break;case "pie":case "doughnut":s=m.center;t="doughnut"===this.type?0.6*m.radius:0;n=Math.sqrt(Math.pow(s.x-a,2)+Math.pow(s.y-b,2));n<m.radius&&n>t&&(n=Math.atan2(b-s.y,a-s.x),0>n&&(n+=2*Math.PI),n=Number(((180*(n/Math.PI)%360+360)%360).toFixed(12)),s=Number(((180*(m.startAngle/Math.PI)%360+360)%360).toFixed(12)),t=Number(((180*(m.endAngle/Math.PI)%360+360)%360).toFixed(12)),0===t&&1<m.endAngle&&(t=360),s>=t&&0!==q.y&&(t+=360,n<s&&(n+=360)),n>s&&n<t&&(d.push({dataPoint:q,dataPointIndex:f,
-dataSeries:this,distance:0}),k=!0));break;case "candlestick":if(a>=m.x1-m.borderThickness/2&&a<=m.x2+m.borderThickness/2&&b>=m.y2-m.borderThickness/2&&b<=m.y3+m.borderThickness/2||Math.abs(m.x2-a+m.x1-a)<m.borderThickness&&b>=m.y1&&b<=m.y4)d.push({dataPoint:q,dataPointIndex:f,dataSeries:this,distance:Math.min(Math.abs(m.x1-a),Math.abs(m.x2-a),Math.abs(m.y2-b),Math.abs(m.y3-b))}),k=!0;break;case "ohlc":if(Math.abs(m.x2-a+m.x1-a)<m.borderThickness&&b>=m.y2&&b<=m.y3||a>=m.x1&&a<=(m.x2+m.x1)/2&&b>=m.y1-
-m.borderThickness/2&&b<=m.y1+m.borderThickness/2||a>=(m.x1+m.x2)/2&&a<=m.x2&&b>=m.y4-m.borderThickness/2&&b<=m.y4+m.borderThickness/2)d.push({dataPoint:q,dataPointIndex:f,dataSeries:this,distance:Math.min(Math.abs(m.x1-a),Math.abs(m.x2-a),Math.abs(m.y2-b),Math.abs(m.y3-b))}),k=!0}if(k||1E3<h&&1E3<l)break}}else if(0>r-e&&r+e>=this.dataPoints.length)break;-1===g?(e++,g=1):g=-1}a=null;for(b=0;b<d.length;b++)a?d[b].distance<=a.distance&&(a=d[b]):a=d[b];return a};P.prototype.getMarkerProperties=function(a,
-b,c,d){var e=this.dataPoints;return{x:b,y:c,ctx:d,type:e[a].markerType?e[a].markerType:this.markerType,size:e[a].markerSize?e[a].markerSize:this.markerSize,color:e[a].markerColor?e[a].markerColor:this.markerColor?this.markerColor:e[a].color?e[a].color:this.color?this.color:this._colorSet[a%this._colorSet.length],borderColor:e[a].markerBorderColor?e[a].markerBorderColor:this.markerBorderColor?this.markerBorderColor:null,borderThickness:e[a].markerBorderThickness?e[a].markerBorderThickness:this.markerBorderThickness?
-this.markerBorderThickness:null}};O(A,L);A.prototype.createLabels=function(){var a,b=0,c,d=0,e=0,b=0;if("bottom"===this._position||"top"===this._position)b=this.lineCoordinates.width/Math.abs(this.maximum-this.minimum)*this.interval,d=this.labelAutoFit?"undefined"===typeof this._options.labelMaxWidth?0.9*b>>0:this.labelMaxWidth:"undefined"===typeof this._options.labelMaxWidth?0.7*this.chart.width>>0:this.labelMaxWidth,e="undefined"===typeof this._options.labelWrap||this.labelWrap?0.5*this.chart.height>>
-0:1.5*this.labelFontSize;else if("left"===this._position||"right"===this._position)b=this.lineCoordinates.height/Math.abs(this.maximum-this.minimum)*this.interval,d=this.labelAutoFit?"undefined"===typeof this._options.labelMaxWidth?0.3*this.chart.width>>0:this.labelMaxWidth:"undefined"===typeof this._options.labelMaxWidth?0.5*this.chart.width>>0:this.labelMaxWidth,e="undefined"===typeof this._options.labelWrap||this.labelWrap?2*b>>0:1.5*this.labelFontSize;if("axisX"===this.type&&"dateTime"===this.chart.plotInfo.axisXValueType)for(c=
-qa(new Date(this.maximum),this.interval,this.intervalType),b=this.intervalstartTimePercent;b<c;qa(b,this.interval,this.intervalType))a=b.getTime(),a="axisX"===this.type&&this.labels[a]?this.labels[a]:ya(b,this.valueFormatString,this.chart._cultureInfo),a=new I(this.ctx,{x:0,y:0,maxWidth:d,maxHeight:e,angle:this.labelAngle,text:this.prefix+a+this.suffix,horizontalAlign:"left",fontSize:this.labelFontSize,fontFamily:this.labelFontFamily,fontWeight:this.labelFontWeight,fontColor:this.labelFontColor,fontStyle:this.labelFontStyle,
-textBaseline:"middle"}),this._labels.push({position:b.getTime(),textBlock:a,effectiveHeight:null});else{c=this.maximum;if(this.labels&&this.labels.length){a=Math.ceil(this.interval);for(var f=Math.ceil(this.intervalstartTimePercent),g=!1,b=f;b<this.maximum;b+=a)if(this.labels[b])g=!0;else{g=!1;break}g&&(this.interval=a,this.intervalstartTimePercent=f)}for(b=this.intervalstartTimePercent;b<=c;b=parseFloat((b+this.interval).toFixed(14)))a="axisX"===this.type&&this.labels[b]?this.labels[b]:X(b,this.valueFormatString,
-this.chart._cultureInfo),a=new I(this.ctx,{x:0,y:0,maxWidth:d,maxHeight:e,angle:this.labelAngle,text:this.prefix+a+this.suffix,horizontalAlign:"left",fontSize:this.labelFontSize,fontFamily:this.labelFontFamily,fontWeight:this.labelFontWeight,fontColor:this.labelFontColor,fontStyle:this.labelFontStyle,textBaseline:"middle",borderThickness:0}),this._labels.push({position:b,textBlock:a,effectiveHeight:null})}for(b=0;b<this.stripLines.length;b++)c=this.stripLines[b],a=new I(this.ctx,{x:0,y:0,backgroundColor:c.labelBackgroundColor,
-maxWidth:d,maxHeight:e,angle:this.labelAngle,text:c.label,horizontalAlign:"left",fontSize:c.labelFontSize,fontFamily:c.labelFontFamily,fontWeight:c.labelFontWeight,fontColor:c.labelFontColor,fontStyle:c.labelFontStyle,textBaseline:"middle",borderThickness:0}),this._labels.push({position:c.value,textBlock:a,effectiveHeight:null,stripLine:c})};A.prototype.createLabelsAndCalculateWidth=function(){var a=0;this._labels=[];if("left"===this._position||"right"===this._position)for(this.createLabels(),i=0;i<
-this._labels.length;i++){var b=this._labels[i].textBlock.measureText(),c=0,c=0===this.labelAngle?b.width:b.width*Math.cos(Math.PI/180*Math.abs(this.labelAngle))+b.height/2*Math.sin(Math.PI/180*Math.abs(this.labelAngle));a<c&&(a=c);this._labels[i].effectiveWidth=c}return(this.title?ca(this.titleFontFamily,this.titleFontSize,this.titleFontWeight)+2:0)+a+this.tickLength+5};A.prototype.createLabelsAndCalculateHeight=function(){var a=0;this._labels=[];var b,c=0;this.createLabels();if("bottom"===this._position||
-"top"===this._position)for(c=0;c<this._labels.length;c++){b=this._labels[c].textBlock;b=b.measureText();var d=0,d=0===this.labelAngle?b.height:b.width*Math.sin(Math.PI/180*Math.abs(this.labelAngle))+b.height/2*Math.cos(Math.PI/180*Math.abs(this.labelAngle));a<d&&(a=d);this._labels[c].effectiveHeight=d}return(this.title?ca(this.titleFontFamily,this.titleFontSize,this.titleFontWeight)+2:0)+a+this.tickLength+5};A.setLayoutAndRender=function(a,b,c,d,e){var f,g,k,p=a.chart,h=p.ctx;a.calculateAxisParameters();
-b&&b.calculateAxisParameters();c&&c.calculateAxisParameters();if(b&&c&&"undefined"===typeof b._options.maximum&&"undefined"===typeof b._options.minimum&&"undefined"===typeof b._options.interval&&"undefined"===typeof c._options.maximum&&"undefined"===typeof c._options.minimum&&"undefined"===typeof c._options.interval){k=(b.maximum-b.minimum)/b.interval;var l=(c.maximum-c.minimum)/c.interval;k>l?c.maximum=c.interval*k+c.minimum:l>k&&(b.maximum=b.interval*l+b.minimum)}l=b?b.margin:0;if("normal"===d){a.lineCoordinates=
-{};var r=Math.ceil(b?b.createLabelsAndCalculateWidth():0);f=Math.round(e.x1+r+l);a.lineCoordinates.x1=f;l=Math.ceil(c?c.createLabelsAndCalculateWidth():0);g=Math.round(e.x2-l>a.chart.width-10?a.chart.width-10:e.x2-l);a.lineCoordinates.x2=g;a.lineCoordinates.width=Math.abs(g-f);var m=Math.ceil(a.createLabelsAndCalculateHeight());d=Math.round(e.y2-m-a.margin);k=Math.round(e.y2-a.margin);a.lineCoordinates.y1=d;a.lineCoordinates.y2=d;a.boundingRect={x1:f,y1:d,x2:g,y2:k,width:g-f,height:k-d};b&&(f=Math.round(e.x1+
-b.margin),d=Math.round(10>e.y1?10:e.y1),g=Math.round(e.x1+r+b.margin),k=Math.round(e.y2-m-a.margin),b.lineCoordinates={x1:g,y1:d,x2:g,y2:k,height:Math.abs(k-d)},b.boundingRect={x1:f,y1:d,x2:g,y2:k,width:g-f,height:k-d});c&&(f=Math.round(a.lineCoordinates.x2),d=Math.round(10>e.y1?10:e.y1),g=Math.round(f+l+c.margin),k=Math.round(e.y2-m-a.margin),c.lineCoordinates={x1:f,y1:d,x2:f,y2:k,height:Math.abs(k-d)},c.boundingRect={x1:f,y1:d,x2:g,y2:k,width:g-f,height:k-d});a.calculateValueToPixelconversionParameters();
-b&&b.calculateValueToPixelconversionParameters();c&&c.calculateValueToPixelconversionParameters();h.save();h.rect(5,a.boundingRect.y1,a.chart.width-10,a.boundingRect.height);h.clip();a.renderLabelsTicksAndTitle();h.restore();b&&b.renderLabelsTicksAndTitle();c&&c.renderLabelsTicksAndTitle()}else{r=Math.ceil(a.createLabelsAndCalculateWidth());b&&(b.lineCoordinates={},f=Math.round(e.x1+r+a.margin),g=Math.round(e.x2>b.chart.width-10?b.chart.width-10:e.x2),b.lineCoordinates.x1=f,b.lineCoordinates.x2=g,
-b.lineCoordinates.width=Math.abs(g-f));c&&(c.lineCoordinates={},f=Math.round(e.x1+r+a.margin),g=Math.round(e.x2>c.chart.width-10?c.chart.width-10:e.x2),c.lineCoordinates.x1=f,c.lineCoordinates.x2=g,c.lineCoordinates.width=Math.abs(g-f));var m=Math.ceil(b?b.createLabelsAndCalculateHeight():0),q=Math.ceil(c?c.createLabelsAndCalculateHeight():0);b&&(d=Math.round(e.y2-m-b.margin),k=Math.round(e.y2-l>b.chart.height-10?b.chart.height-10:e.y2-l),b.lineCoordinates.y1=d,b.lineCoordinates.y2=d,b.boundingRect=
-{x1:f,y1:d,x2:g,y2:k,width:g-f,height:m});c&&(d=Math.round(e.y1+c.margin),k=e.y1+c.margin+q,c.lineCoordinates.y1=k,c.lineCoordinates.y2=k,c.boundingRect={x1:f,y1:d,x2:g,y2:k,width:g-f,height:q});f=Math.round(e.x1+a.margin);d=Math.round(c?c.lineCoordinates.y2:10>e.y1?10:e.y1);g=Math.round(e.x1+r+a.margin);k=Math.round(b?b.lineCoordinates.y1:e.y2-l>a.chart.height-10?a.chart.height-10:e.y2-l);a.lineCoordinates={x1:g,y1:d,x2:g,y2:k,height:Math.abs(k-d)};a.boundingRect={x1:f,y1:d,x2:g,y2:k,width:g-f,height:k-
-d};a.calculateValueToPixelconversionParameters();b&&b.calculateValueToPixelconversionParameters();c&&c.calculateValueToPixelconversionParameters();b&&b.renderLabelsTicksAndTitle();c&&c.renderLabelsTicksAndTitle();a.renderLabelsTicksAndTitle()}p.preparePlotArea();e=a.chart.plotArea;h.save();h.rect(e.x1,e.y1,Math.abs(e.x2-e.x1),Math.abs(e.y2-e.y1));h.clip();a.renderStripLinesOfThicknessType("value");b&&b.renderStripLinesOfThicknessType("value");c&&c.renderStripLinesOfThicknessType("value");a.renderInterlacedColors();
-b&&b.renderInterlacedColors();c&&c.renderInterlacedColors();h.restore();a.renderGrid();b&&b.renderGrid();c&&c.renderGrid();a.renderAxisLine();b&&b.renderAxisLine();c&&c.renderAxisLine();a.renderStripLinesOfThicknessType("pixel");b&&b.renderStripLinesOfThicknessType("pixel");c&&c.renderStripLinesOfThicknessType("pixel")};A.prototype.renderLabelsTicksAndTitle=function(){var a=!1,b=0,c=1,d=0;0!==this.labelAngle&&360!==this.labelAngle&&(c=1.2);if("undefined"===typeof this._options.interval){if("bottom"===
-this._position||"top"===this._position){for(e=0;e<this._labels.length;e++)f=this._labels[e],f.position<this.minimum||f.stripLine||(f=f.textBlock.width*Math.cos(Math.PI/180*this.labelAngle)+f.textBlock.height*Math.sin(Math.PI/180*this.labelAngle),b+=f);b>this.lineCoordinates.width*c&&(a=!0)}if("left"===this._position||"right"===this._position){for(e=0;e<this._labels.length;e++)f=this._labels[e],f.position<this.minimum||f.stripLine||(f=f.textBlock.height*Math.cos(Math.PI/180*this.labelAngle)+f.textBlock.width*
-Math.sin(Math.PI/180*this.labelAngle),b+=f);b>this.lineCoordinates.height*c&&(a=!0)}}if("bottom"===this._position){for(var e=0,f,e=0;e<this._labels.length;e++)if(f=this._labels[e],!(f.position<this.minimum||f.position>this.maximum)){b=this.getPixelCoordinatesOnAxis(f.position);if(this.tickThickness&&!this._labels[e].stripLine||this._labels[e].stripLine&&"pixel"===this._labels[e].stripLine._thicknessType)this._labels[e].stripLine?(c=this._labels[e].stripLine,this.ctx.lineWidth=c.thickness,this.ctx.strokeStyle=
-c.color):(this.ctx.lineWidth=this.tickThickness,this.ctx.strokeStyle=this.tickColor),c=1===this.ctx.lineWidth%2?(b.x<<0)+0.5:b.x<<0,this.ctx.beginPath(),this.ctx.moveTo(c,b.y<<0),this.ctx.lineTo(c,b.y+this.tickLength<<0),this.ctx.stroke();if(!a||0===d++%2||this._labels[e].stripLine)0===f.textBlock.angle?(b.x-=f.textBlock.width/2,b.y+=this.tickLength+f.textBlock.fontSize/2):(b.x-=0>this.labelAngle?f.textBlock.width*Math.cos(Math.PI/180*this.labelAngle):0,b.y+=this.tickLength+Math.abs(0>this.labelAngle?
-f.textBlock.width*Math.sin(Math.PI/180*this.labelAngle)-5:5)),f.textBlock.x=b.x,f.textBlock.y=b.y,f.textBlock.render(!0)}this.title&&(this._titleTextBlock=new I(this.ctx,{x:this.lineCoordinates.x1,y:this.boundingRect.y2-this.titleFontSize-5,maxWidth:this.lineCoordinates.width,maxHeight:1.5*this.titleFontSize,angle:0,text:this.title,horizontalAlign:"center",fontSize:this.titleFontSize,fontFamily:this.titleFontFamily,fontWeight:this.titleFontWeight,fontColor:this.titleFontColor,fontStyle:this.titleFontStyle,
-textBaseline:"top"}),this._titleTextBlock.measureText(),this._titleTextBlock.x=this.lineCoordinates.x1+this.lineCoordinates.width/2-this._titleTextBlock.width/2,this._titleTextBlock.y=this.boundingRect.y2-this._titleTextBlock.height-3,this._titleTextBlock.render(!0))}else if("top"===this._position){for(e=0;e<this._labels.length;e++)if(f=this._labels[e],!(f.position<this.minimum||f.position>this.maximum)){b=this.getPixelCoordinatesOnAxis(f.position);if(this.tickThickness&&!this._labels[e].stripLine||
-this._labels[e].stripLine&&"pixel"===this._labels[e].stripLine._thicknessType)this._labels[e].stripLine?(c=this._labels[e].stripLine,this.ctx.lineWidth=c.thickness,this.ctx.strokeStyle=c.color):(this.ctx.lineWidth=this.tickThickness,this.ctx.strokeStyle=this.tickColor),c=1===this.ctx.lineWidth%2?(b.x<<0)+0.5:b.x<<0,this.ctx.beginPath(),this.ctx.moveTo(c,b.y<<0),this.ctx.lineTo(c,b.y-this.tickLength<<0),this.ctx.stroke();if(!a||0===d++%2||this._labels[e].stripLine)0===f.textBlock.angle?(b.x-=f.textBlock.width/
-2,b.y-=this.tickLength+f.textBlock.height/2):(b.x-=0<this.labelAngle?f.textBlock.width*Math.cos(Math.PI/180*this.labelAngle):0,b.y-=this.tickLength+Math.abs(0<this.labelAngle?f.textBlock.width*Math.sin(Math.PI/180*this.labelAngle)+5:5)),f.textBlock.x=b.x,f.textBlock.y=b.y,f.textBlock.render(!0)}this.title&&(this._titleTextBlock=new I(this.ctx,{x:this.lineCoordinates.x1,y:this.boundingRect.y1+1,maxWidth:this.lineCoordinates.width,maxHeight:1.5*this.titleFontSize,angle:0,text:this.title,horizontalAlign:"center",
-fontSize:this.titleFontSize,fontFamily:this.titleFontFamily,fontWeight:this.titleFontWeight,fontColor:this.titleFontColor,fontStyle:this.titleFontStyle,textBaseline:"top"}),this._titleTextBlock.measureText(),this._titleTextBlock.x=this.lineCoordinates.x1+this.lineCoordinates.width/2-this._titleTextBlock.width/2,this._titleTextBlock.render(!0))}else if("left"===this._position){for(e=0;e<this._labels.length;e++)if(f=this._labels[e],!(f.position<this.minimum||f.position>this.maximum)){b=this.getPixelCoordinatesOnAxis(f.position);
-if(this.tickThickness&&!this._labels[e].stripLine||this._labels[e].stripLine&&"pixel"===this._labels[e].stripLine._thicknessType)this._labels[e].stripLine?(c=this._labels[e].stripLine,this.ctx.lineWidth=c.thickness,this.ctx.strokeStyle=c.color):(this.ctx.lineWidth=this.tickThickness,this.ctx.strokeStyle=this.tickColor),c=1===this.ctx.lineWidth%2?(b.y<<0)+0.5:b.y<<0,this.ctx.beginPath(),this.ctx.moveTo(b.x<<0,c),this.ctx.lineTo(b.x-this.tickLength<<0,c),this.ctx.stroke();if(!a||0===d++%2||this._labels[e].stripLine)f.textBlock.x=
-b.x-f.textBlock.width*Math.cos(Math.PI/180*this.labelAngle)-this.tickLength-5,f.textBlock.y=0===this.labelAngle?b.y-f.textBlock.height/2+this.labelFontSize/2:b.y-f.textBlock.width*Math.sin(Math.PI/180*this.labelAngle),f.textBlock.render(!0)}this.title&&(this._titleTextBlock=new I(this.ctx,{x:this.boundingRect.x1+1,y:this.lineCoordinates.y2,maxWidth:this.lineCoordinates.height,maxHeight:1.5*this.titleFontSize,angle:-90,text:this.title,horizontalAlign:"center",fontSize:this.titleFontSize,fontFamily:this.titleFontFamily,
-fontWeight:this.titleFontWeight,fontColor:this.titleFontColor,fontStyle:this.titleFontStyle,textBaseline:"top"}),this._titleTextBlock.measureText(),this._titleTextBlock.y=this.lineCoordinates.height/2+this._titleTextBlock.width/2+this.lineCoordinates.y1,this._titleTextBlock.render(!0))}else if("right"===this._position){for(e=0;e<this._labels.length;e++)if(f=this._labels[e],!(f.position<this.minimum||f.position>this.maximum)){b=this.getPixelCoordinatesOnAxis(f.position);if(this.tickThickness&&!this._labels[e].stripLine||
-this._labels[e].stripLine&&"pixel"===this._labels[e].stripLine._thicknessType)this._labels[e].stripLine?(c=this._labels[e].stripLine,this.ctx.lineWidth=c.thickness,this.ctx.strokeStyle=c.color):(this.ctx.lineWidth=this.tickThickness,this.ctx.strokeStyle=this.tickColor),c=1===this.ctx.lineWidth%2?(b.y<<0)+0.5:b.y<<0,this.ctx.beginPath(),this.ctx.moveTo(b.x<<0,c),this.ctx.lineTo(b.x+this.tickLength<<0,c),this.ctx.stroke();if(!a||0===d++%2||this._labels[e].stripLine)f.textBlock.x=b.x+this.tickLength+
-5,f.textBlock.y=0===this.labelAngle?b.y-f.textBlock.height/2+this.labelFontSize/2:b.y,f.textBlock.render(!0)}this.title&&(this._titleTextBlock=new I(this.ctx,{x:this.boundingRect.x2-1,y:this.lineCoordinates.y2,maxWidth:this.lineCoordinates.height,maxHeight:1.5*this.titleFontSize,angle:90,text:this.title,horizontalAlign:"center",fontSize:this.titleFontSize,fontFamily:this.titleFontFamily,fontWeight:this.titleFontWeight,fontColor:this.titleFontColor,fontStyle:this.titleFontStyle,textBaseline:"top"}),
-this._titleTextBlock.measureText(),this._titleTextBlock.y=this.lineCoordinates.height/2-this._titleTextBlock.width/2+this.lineCoordinates.y1,this._titleTextBlock.render(!0))}};A.prototype.renderInterlacedColors=function(){var a=this.chart.plotArea.ctx,b,c,d=this.chart.plotArea,e=0;b=!0;if(("bottom"===this._position||"top"===this._position)&&this.interlacedColor)for(a.fillStyle=this.interlacedColor,e=0;e<this._labels.length;e++)this._labels[e].stripLine||(b?(b=this.getPixelCoordinatesOnAxis(this._labels[e].position),
-c=e+1>=this._labels.length?this.getPixelCoordinatesOnAxis(this.maximum):this.getPixelCoordinatesOnAxis(this._labels[e+1].position),a.fillRect(b.x,d.y1,Math.abs(c.x-b.x),Math.abs(d.y1-d.y2)),b=!1):b=!0);else if(("left"===this._position||"right"===this._position)&&this.interlacedColor)for(a.fillStyle=this.interlacedColor,e=0;e<this._labels.length;e++)this._labels[e].stripLine||(b?(c=this.getPixelCoordinatesOnAxis(this._labels[e].position),b=e+1>=this._labels.length?this.getPixelCoordinatesOnAxis(this.maximum):
-this.getPixelCoordinatesOnAxis(this._labels[e+1].position),a.fillRect(d.x1,b.y,Math.abs(d.x1-d.x2),Math.abs(b.y-c.y)),b=!1):b=!0);a.beginPath()};A.prototype.renderStripLinesOfThicknessType=function(a){if(this.stripLines&&0<this.stripLines.length&&a)for(var b=this.chart.plotArea.ctx,c=0,c=0;c<this.stripLines.length;c++){var d=this.stripLines[c];if(d._thicknessType===a&&("pixel"!==a||!(d.value<this.minimum||d.value>this.maximum))){var e=this.getPixelCoordinatesOnAxis(d.value),f=Math.abs("pixel"===a?
-d.thickness:this.conversionParameters.pixelPerUnit*d.thickness);if(!(0>=f)){b.strokeStyle=d.color;b.beginPath();C(d.id);var g,k,p,h;b.lineWidth=f;if("bottom"===this._position||"top"===this._position)g=k=1===b.lineWidth%2?(e.x<<0)+0.5:e.x<<0,p=this.chart.plotArea.y1,h=this.chart.plotArea.y2;else if("left"===this._position||"right"===this._position)p=h=1===b.lineWidth%2?(e.y<<0)+0.5:e.y<<0,g=this.chart.plotArea.x1,k=this.chart.plotArea.x2;b.moveTo(g,p);b.lineTo(k,h);b.stroke()}}}};A.prototype.renderGrid=
-function(){if(this.gridThickness&&0<this.gridThickness){var a=this.chart.ctx,b,c=this.chart.plotArea;a.lineWidth=this.gridThickness;a.strokeStyle=this.gridColor;if("bottom"===this._position||"top"===this._position)for(d=0;d<this._labels.length&&!this._labels[d].stripLine;d++)this._labels[d].position<this.minimum||this._labels[d].position>this.maximum||(a.beginPath(),b=this.getPixelCoordinatesOnAxis(this._labels[d].position),b=1===a.lineWidth%2?(b.x<<0)+0.5:b.x<<0,a.moveTo(b,c.y1<<0),a.lineTo(b,c.y2<<
-0),a.stroke());else if("left"===this._position||"right"===this._position)for(var d=0;d<this._labels.length&&!this._labels[d].stripLine;d++)this._labels[d].position<this.minimum||this._labels[d].position>this.maximum||(a.beginPath(),b=this.getPixelCoordinatesOnAxis(this._labels[d].position),b=1===a.lineWidth%2?(b.y<<0)+0.5:b.y<<0,a.moveTo(c.x1<<0,b),a.lineTo(c.x2<<0,b),a.stroke())}};A.prototype.renderAxisLine=function(){var a=this.chart.ctx;if("bottom"===this._position||"top"===this._position){if(this.lineThickness){a.lineWidth=
-this.lineThickness;a.strokeStyle=this.lineColor?this.lineColor:"black";var b=1===this.lineThickness%2?(this.lineCoordinates.y1<<0)+0.5:this.lineCoordinates.y1<<0;a.beginPath();a.moveTo(this.lineCoordinates.x1,b);a.lineTo(this.lineCoordinates.x2,b);a.stroke()}}else"left"!==this._position&&"right"!==this._position||!this.lineThickness||(a.lineWidth=this.lineThickness,a.strokeStyle=this.lineColor,b=1===this.lineThickness%2?(this.lineCoordinates.x1<<0)+0.5:this.lineCoordinates.x1<<0,a.beginPath(),a.moveTo(b,
-this.lineCoordinates.y1),a.lineTo(b,this.lineCoordinates.y2),a.stroke())};A.prototype.getPixelCoordinatesOnAxis=function(a){var b={},c=this.lineCoordinates.width,d=this.lineCoordinates.height;if("bottom"===this._position||"top"===this._position)c/=Math.abs(this.maximum-this.minimum),b.x=this.lineCoordinates.x1+c*(a-this.minimum),b.y=this.lineCoordinates.y1;if("left"===this._position||"right"===this._position)c=d/Math.abs(this.maximum-this.minimum),b.y=this.lineCoordinates.y2-c*(a-this.minimum),b.x=
-this.lineCoordinates.x2;return b};A.prototype.getXValueAt=function(a){if(!a)return null;var b=null;"left"===this._position?b=(this.chart.axisX.maximum-this.chart.axisX.minimum)/this.chart.axisX.lineCoordinates.height*(this.chart.axisX.lineCoordinates.y2-a.y)+this.chart.axisX.minimum:"bottom"===this._position&&(b=(this.chart.axisX.maximum-this.chart.axisX.minimum)/this.chart.axisX.lineCoordinates.width*(a.x-this.chart.axisX.lineCoordinates.x1)+this.chart.axisX.minimum);return b};A.prototype.calculateValueToPixelconversionParameters=
-function(a){a={pixelPerUnit:null,minimum:null,reference:null};var b=this.lineCoordinates.width,c=this.lineCoordinates.height;a.minimum=this.minimum;if("bottom"===this._position||"top"===this._position)a.pixelPerUnit=b/Math.abs(this.maximum-this.minimum),a.reference=this.lineCoordinates.x1;if("left"===this._position||"right"===this._position)a.pixelPerUnit=-1*c/Math.abs(this.maximum-this.minimum),a.reference=this.lineCoordinates.y2;this.conversionParameters=a};A.prototype.calculateAxisParameters=function(){var a=
-this.chart.layoutManager.getFreeSpace();"bottom"===this._position||"top"===this._position?(this.maxWidth=a.width,this.maxHeight=a.height):(this.maxWidth=a.height,this.maxHeight=a.width);var a="axisX"===this.type?500>this.maxWidth?8:Math.max(6,Math.floor(this.maxWidth/62)):Math.max(Math.floor(this.maxWidth/40),2),b,c,d,e;e=0;"axisX"===this.type?(b=null!==this.sessionVariables.internalMinimum?this.sessionVariables.internalMinimum:this.dataInfo.viewPortMin,c=null!==this.sessionVariables.internalMaximum?
-this.sessionVariables.internalMaximum:this.dataInfo.viewPortMax,0===c-b&&(c+=0.4,b-=0.4),d=Infinity!==this.dataInfo.minDiff?this.dataInfo.minDiff:1<c-b?0.5*Math.abs(c-b):1):"axisY"===this.type&&(b="undefined"===typeof this._options.minimum?this.dataInfo.viewPortMin:this._options.minimum,c="undefined"===typeof this._options.maximum?this.dataInfo.viewPortMax:this._options.maximum,0===b&&0===c?(c+=9,b=0):0===c-b?(e=Math.min(Math.abs(0.01*Math.abs(c)),5),c+=e,b-=e):(e=Math.min(Math.abs(0.01*Math.abs(c-
-b)),0.05),0!==c&&(c+=e),0!==b&&(b-=e)),this.includeZero&&"undefined"===typeof this._options.minimum&&0<b&&(b=0),this.includeZero&&"undefined"===typeof this._options.maximum&&0>c&&(c=0));"axisX"===this.type&&"dateTime"===this.chart.plotInfo.axisXValueType?(e=c-b,this.intervalType||(e/1<=a?(this.interval=1,this.intervalType="millisecond"):e/2<=a?(this.interval=2,this.intervalType="millisecond"):e/5<=a?(this.interval=5,this.intervalType="millisecond"):e/10<=a?(this.interval=10,this.intervalType="millisecond"):
-e/20<=a?(this.interval=20,this.intervalType="millisecond"):e/50<=a?(this.interval=50,this.intervalType="millisecond"):e/100<=a?(this.interval=100,this.intervalType="millisecond"):e/200<=a?(this.interval=200,this.intervalType="millisecond"):e/250<=a?(this.interval=250,this.intervalType="millisecond"):e/300<=a?(this.interval=300,this.intervalType="millisecond"):e/400<=a?(this.interval=400,this.intervalType="millisecond"):e/500<=a?(this.interval=500,this.intervalType="millisecond"):e/(1*z.secondDuration)<=
-a?(this.interval=1,this.intervalType="second"):e/(2*z.secondDuration)<=a?(this.interval=2,this.intervalType="second"):e/(5*z.secondDuration)<=a?(this.interval=5,this.intervalType="second"):e/(10*z.secondDuration)<=a?(this.interval=10,this.intervalType="second"):e/(15*z.secondDuration)<=a?(this.interval=15,this.intervalType="second"):e/(20*z.secondDuration)<=a?(this.interval=20,this.intervalType="second"):e/(30*z.secondDuration)<=a?(this.interval=30,this.intervalType="second"):e/(1*z.minuteDuration)<=
-a?(this.interval=1,this.intervalType="minute"):e/(2*z.minuteDuration)<=a?(this.interval=2,this.intervalType="minute"):e/(5*z.minuteDuration)<=a?(this.interval=5,this.intervalType="minute"):e/(10*z.minuteDuration)<=a?(this.interval=10,this.intervalType="minute"):e/(15*z.minuteDuration)<=a?(this.interval=15,this.intervalType="minute"):e/(20*z.minuteDuration)<=a?(this.interval=20,this.intervalType="minute"):e/(30*z.minuteDuration)<=a?(this.interval=30,this.intervalType="minute"):e/(1*z.hourDuration)<=
-a?(this.interval=1,this.intervalType="hour"):e/(2*z.hourDuration)<=a?(this.interval=2,this.intervalType="hour"):e/(3*z.hourDuration)<=a?(this.interval=3,this.intervalType="hour"):e/(6*z.hourDuration)<=a?(this.interval=6,this.intervalType="hour"):e/(1*z.dayDuration)<=a?(this.interval=1,this.intervalType="day"):e/(2*z.dayDuration)<=a?(this.interval=2,this.intervalType="day"):e/(4*z.dayDuration)<=a?(this.interval=4,this.intervalType="day"):e/(1*z.weekDuration)<=a?(this.interval=1,this.intervalType="week"):
-e/(2*z.weekDuration)<=a?(this.interval=2,this.intervalType="week"):e/(3*z.weekDuration)<=a?(this.interval=3,this.intervalType="week"):e/(1*z.monthDuration)<=a?(this.interval=1,this.intervalType="month"):e/(2*z.monthDuration)<=a?(this.interval=2,this.intervalType="month"):e/(3*z.monthDuration)<=a?(this.interval=3,this.intervalType="month"):e/(6*z.monthDuration)<=a?(this.interval=6,this.intervalType="month"):(this.interval=e/(1*z.yearDuration)<=a?1:e/(2*z.yearDuration)<=a?2:e/(4*z.yearDuration)<=a?
-4:Math.floor(A.getNiceNumber(e/(a-1),!0)/z.yearDuration),this.intervalType="year")),this.minimum=null!==this.sessionVariables.internalMinimum?this.sessionVariables.internalMinimum:b-d/2,this.maximum=this.sessionVariables.internalMaximum?this.sessionVariables.internalMaximum:c+d/2,this.valueFormatString||("year"===this.intervalType?this.valueFormatString="YYYY":"month"===this.intervalType?this.valueFormatString="MMM YYYY":"week"===this.intervalType?this.valueFormatString="MMM DD YYYY":"day"===this.intervalType?
-this.valueFormatString="MMM DD YYYY":"hour"===this.intervalType?this.valueFormatString="hh:mm TT":"minute"===this.intervalType?this.valueFormatString="hh:mm TT":"second"===this.intervalType?this.valueFormatString="hh:mm:ss TT":"millisecond"===this.intervalType&&(this.valueFormatString="fff'ms'")),this.intervalstartTimePercent=this.getLabelStartPoint(new Date(this.minimum),this.intervalType,this.interval)):(this.intervalType="number",e=A.getNiceNumber(c-b,!1),this.interval=this._options&&this._options.interval?
-this._options.interval:A.getNiceNumber(e/(a-1),!0),this.minimum=null!==this.sessionVariables.internalMinimum?this.sessionVariables.internalMinimum:Math.floor(b/this.interval)*this.interval,this.maximum=null!==this.sessionVariables.internalMaximum?this.sessionVariables.internalMaximum:Math.ceil(c/this.interval)*this.interval,"axisX"===this.type?(null===this.sessionVariables.internalMinimum&&(this.minimum=b-d/2),this.sessionVariables.internalMaximum||(this.maximum=c+d/2),this.intervalstartTimePercent=
-Math.floor((this.minimum+0.2*this.interval)/this.interval)*this.interval):"axisY"===this.type&&(this.intervalstartTimePercent=this.minimum));"axisX"===this.type&&(this._absoluteMinimum=this._options&&"undefined"!==typeof this._options.minimum?this._options.minimum:this.dataInfo.min-d/2,this._absoluteMaximum=this._options&&"undefined"!==typeof this._options.maximum?this._options.maximum:this.dataInfo.max+d/2);if(!this.valueFormatString&&(this.valueFormatString="#,##0.##",e=Math.abs(this.maximum-this.minimum),
-1>e&&(b=Math.floor(Math.abs(Math.log(e)/Math.LN10))+2,2<b)))for(c=0;c<b-2;c++)this.valueFormatString+="#"};A.getNiceNumber=function(a,b){var c=Math.floor(Math.log(a)/Math.LN10),d=a/Math.pow(10,c);return Number(((b?1.5>d?1:3>d?2:7>d?5:10:1>=d?1:2>=d?2:5>=d?5:10)*Math.pow(10,c)).toFixed(20))};A.prototype.getLabelStartPoint=function(){var a=Y(this.interval,this.intervalType),a=new Date(Math.floor(this.minimum/a)*a);if("millisecond"!==this.intervalType)if("second"===this.intervalType)0<a.getMilliseconds()&&
-(a.setSeconds(a.getSeconds()+1),a.setMilliseconds(0));else if("minute"===this.intervalType){if(0<a.getSeconds()||0<a.getMilliseconds())a.setMinutes(a.getMinutes()+1),a.setSeconds(0),a.setMilliseconds(0)}else if("hour"===this.intervalType){if(0<a.getMinutes()||0<a.getSeconds()||0<a.getMilliseconds())a.setHours(a.getHours()+1),a.setMinutes(0),a.setSeconds(0),a.setMilliseconds(0)}else if("day"===this.intervalType){if(0<a.getHours()||0<a.getMinutes()||0<a.getSeconds()||0<a.getMilliseconds())a.setDate(a.getDate()+
-1),a.setHours(0),a.setMinutes(0),a.setSeconds(0),a.setMilliseconds(0)}else if("week"===this.intervalType){if(0<a.getDay()||0<a.getHours()||0<a.getMinutes()||0<a.getSeconds()||0<a.getMilliseconds())a.setDate(a.getDate()+(7-a.getDay())),a.setHours(0),a.setMinutes(0),a.setSeconds(0),a.setMilliseconds(0)}else if("month"===this.intervalType){if(1<a.getDate()||0<a.getHours()||0<a.getMinutes()||0<a.getSeconds()||0<a.getMilliseconds())a.setMonth(a.getMonth()+1),a.setDate(1),a.setHours(0),a.setMinutes(0),
-a.setSeconds(0),a.setMilliseconds(0)}else"year"===this.intervalType&&(0<a.getMonth()||1<a.getDate()||0<a.getHours()||0<a.getMinutes()||0<a.getSeconds()||0<a.getMilliseconds())&&(a.setFullYear(a.getFullYear()+1),a.setMonth(0),a.setDate(1),a.setHours(0),a.setMinutes(0),a.setSeconds(0),a.setMilliseconds(0));return a};O(ma,L);O(N,L);N.prototype._initialize=function(){if(this.enabled){this.container=document.createElement("div");this.container.setAttribute("class","canvasjs-chart-tooltip");this.container.style.position=
-"absolute";this.container.style.height="auto";this.container.style.boxShadow="1px 1px 2px 2px rgba(0,0,0,0.1)";this.container.style.zIndex="1000";this.container.style.display="none";var a;a='<div style=" width: auto;height: auto;min-width: 50px;';a+="line-height: 20px;";a+="margin: 0px 0px 0px 0px;";a+="padding: 5px;";a+="font-family: Calibri, Arial, Georgia, serif;";a+="font-weight: 400;";a+="font-style: "+(t?"italic;":"normal;");a+="font-size: 14px;";a+="color: #000000;";a+="text-shadow: 1px 1px 1px rgba(0, 0, 0, 0.1);";
-a+="text-align: left;";a+="border: 2px solid gray;";a+=t?"background: rgba(255,255,255,.9);":"background: rgb(255,255,255);";a+="text-indent: 0px;";a+="white-space: nowrap;";a+="border-radius: 5px;";a+="-moz-user-select:none;";a+="-khtml-user-select: none;";a+="-webkit-user-select: none;";a+="-ms-user-select: none;";a+="user-select: none;";t||(a+="filter: alpha(opacity = 90);",a+="filter: progid:DXImageTransform.Microsoft.Shadow(Strength=3, Direction=135, Color='#666666');");a+='} "> Sample Tooltip</div>';
-this.container.innerHTML=a;this.contentDiv=this.container.firstChild;this.container.style.borderRadius=this.contentDiv.style.borderRadius;this.chart._canvasJSContainer.appendChild(this.container)}};N.prototype.mouseMoveHandler=function(a,b){this._lastUpdated&&40>(new Date).getTime()-this._lastUpdated||(this._lastUpdated=(new Date).getTime(),this._updateToolTip(a,b))};N.prototype._updateToolTip=function(a,b){if(this.enabled&&!this.chart.disableToolTip){if("undefined"===typeof a||"undefined"===typeof b){if(isNaN(this._prevX)||
-isNaN(this._prevY))return;a=this._prevX;b=this._prevY}else this._prevX=a,this._prevY=b;var c=null,d=null,e=[],f=0;if(this.shared&&"none"!==this.chart.plotInfo.axisPlacement){f="xySwapped"===this.chart.plotInfo.axisPlacement?(this.chart.axisX.maximum-this.chart.axisX.minimum)/this.chart.axisX.lineCoordinates.height*(this.chart.axisX.lineCoordinates.y2-b)+this.chart.axisX.minimum:(this.chart.axisX.maximum-this.chart.axisX.minimum)/this.chart.axisX.lineCoordinates.width*(a-this.chart.axisX.lineCoordinates.x1)+
-this.chart.axisX.minimum;c=[];for(d=0;d<this.chart.data.length;d++){var g=this.chart.data[d].getDataPointAtX(f,!0);g&&0<=g.index&&(g.dataSeries=this.chart.data[d],null!==g.dataPoint.y&&c.push(g))}if(0===c.length)return;c.sort(function(a,b){return a.distance-b.distance});f=c[0];for(d=0;d<c.length;d++)c[d].dataPoint.x.valueOf()===f.dataPoint.x.valueOf()&&e.push(c[d]);c=null}else if((g=this.chart.getDataPointAtXY(a,b,!0))?(this.currentDataPointIndex=g.dataPointIndex,this.currentSeriesIndex=g.dataSeries.index):
-t?(g=ta(a,b,this.chart._eventManager.ghostCtx),0<g&&"undefined"!==typeof this.chart._eventManager.objectMap[g]?(eventObject=this.chart._eventManager.objectMap[g],this.currentSeriesIndex=eventObject.dataSeriesIndex,this.currentDataPointIndex=0<=eventObject.dataPointIndex?eventObject.dataPointIndex:-1):this.currentDataPointIndex=-1):this.currentDataPointIndex=-1,0<=this.currentSeriesIndex){d=this.chart.data[this.currentSeriesIndex];g={};if(0<=this.currentDataPointIndex)c=d.dataPoints[this.currentDataPointIndex],
-g.dataSeries=d,g.dataPoint=c,g.index=this.currentDataPointIndex,g.distance=Math.abs(c.x-f);else if("line"===d.type||"stepLine"===d.type||"spline"===d.type||"area"===d.type||"stepArea"===d.type||"splineArea"===d.type||"stackedArea"===d.type||"stackedArea100"===d.type||"rangeArea"===d.type||"rangeSplineArea"===d.type||"candlestick"===d.type||"ohlc"===d.type)f=(this.chart.axisX.maximum-this.chart.axisX.minimum)/this.chart.axisX.lineCoordinates.width*(a-this.chart.axisX.lineCoordinates.x1)+this.chart.axisX.minimum.valueOf(),
-g=d.getDataPointAtX(f,!0),g.dataSeries=d,this.currentDataPointIndex=g.index,c=g.dataPoint;else return;null!==g.dataPoint.y&&e.push(g)}if(0<e.length)if(this.highlightObjects(e),f="",f=this.getToolTipInnerHTML({entries:e}),null!==f){this.contentDiv.innerHTML=f;this.contentDiv.innerHTML=f;f=!1;"none"===this.container.style.display&&(f=!0,this.container.style.display="block");try{this.contentDiv.style.borderRightColor=this.contentDiv.style.borderLeftColor=this.contentDiv.style.borderColor=this.borderColor?
-this.borderColor:e[0].dataPoint.color?e[0].dataPoint.color:e[0].dataSeries.color?e[0].dataSeries.color:e[0].dataSeries._colorSet[e[0].index%e[0].dataSeries._colorSet.length]}catch(k){}"pie"===e[0].dataSeries.type||"doughnut"===e[0].dataSeries.type||"funnel"===e[0].dataSeries.type||"bar"===e[0].dataSeries.type||"rangeBar"===e[0].dataSeries.type||"stackedBar"===e[0].dataSeries.type||"stackedBar100"===e[0].dataSeries.type?toolTipLeft=a-10-this.container.clientWidth:(toolTipLeft=this.chart.axisX.lineCoordinates.width/
-Math.abs(this.chart.axisX.maximum-this.chart.axisX.minimum)*Math.abs(e[0].dataPoint.x-this.chart.axisX.minimum)+this.chart.axisX.lineCoordinates.x1+0.5-this.container.clientWidth<<0,toolTipLeft-=10);0>toolTipLeft&&(toolTipLeft+=this.container.clientWidth+20);toolTipLeft+this.container.clientWidth>this.chart._container.clientWidth&&(toolTipLeft=Math.max(0,this.chart._container.clientWidth-this.container.clientWidth));toolTipLeft+="px";e=1!==e.length||this.shared||"line"!==e[0].dataSeries.type&&"stepLine"!==
-e[0].dataSeries.type&&"spline"!==e[0].dataSeries.type&&"area"!==e[0].dataSeries.type&&"stepArea"!==e[0].dataSeries.type&&"splineArea"!==e[0].dataSeries.type&&"stackedArea"!==e[0].dataSeries.type&&"stackedArea100"!==e[0].dataSeries.type?"bar"===e[0].dataSeries.type||"rangeBar"===e[0].dataSeries.type||"stackedBar"===e[0].dataSeries.type||"stackedBar100"===e[0].dataSeries.type?e[0].dataSeries.axisX.lineCoordinates.y2-e[0].dataSeries.axisX.lineCoordinates.height/Math.abs(e[0].dataSeries.axisX.maximum-
-e[0].dataSeries.axisX.minimum)*Math.abs(e[0].dataPoint.x-e[0].dataSeries.axisX.minimum)+0.5<<0:b:e[0].dataSeries.axisY.lineCoordinates.y2-e[0].dataSeries.axisY.lineCoordinates.height/Math.abs(e[0].dataSeries.axisY.maximum-e[0].dataSeries.axisY.minimum)*Math.abs(e[0].dataPoint.y-e[0].dataSeries.axisY.minimum)+0.5<<0;e=-e+10;0<e+this.container.clientHeight+5&&(e-=e+this.container.clientHeight+5-0);this.container.style.left=toolTipLeft;this.container.style.bottom=e+"px";!this.animationEnabled||f?this.disableAnimation():
-this.enableAnimation()}else this.hide(!1)}};N.prototype.highlightObjects=function(a){if(this.enabled){var b=this.chart.overlaidCanvasCtx;this.chart.resetOverlayedCanvas();b.save();for(var c=0,d=0;d<a.length;d++){var e=a[d];if((e=this.chart._eventManager.objectMap[e.dataSeries.dataPointIds[e.index]])&&e.objectType&&"dataPoint"===e.objectType){var c=this.chart.data[e.dataSeriesIndex],f=e.dataPointIndex;if("line"===c.type||"stepLine"===c.type||"spline"===c.type||"scatter"===c.type||"area"===c.type||
-"stepArea"===c.type||"splineArea"===c.type||"stackedArea"===c.type||"stackedArea100"===c.type||"rangeArea"===c.type||"rangeSplineArea"===c.type){var g=c.getMarkerProperties(f,e.x1,e.y1,this.chart.overlaidCanvasCtx);g.size=Math.max(1.5*g.size<<0,10);g.borderColor=g.borderColor||"#FFFFFF";g.borderThickness=g.borderThickness||Math.ceil(0.1*g.size);J.drawMarkers([g]);"undefined"!==typeof e.y2&&(g=c.getMarkerProperties(f,e.x1,e.y2,this.chart.overlaidCanvasCtx),g.size=Math.max(1.5*g.size<<0,10),g.borderColor=
-g.borderColor||"#FFFFFF",g.borderThickness=g.borderThickness||Math.ceil(0.1*g.size),J.drawMarkers([g]))}else"bubble"===c.type?(g=c.getMarkerProperties(f,e.x1,e.y1,this.chart.overlaidCanvasCtx),g.size=e.size,g.color="white",g.borderColor="white",b.globalAlpha=0.3,J.drawMarkers([g]),b.globalAlpha=1):"column"===c.type||"stackedColumn"===c.type||"stackedColumn100"===c.type||"bar"===c.type||"rangeBar"===c.type||"stackedBar"===c.type||"stackedBar100"===c.type||"rangeColumn"===c.type?F(b,e.x1,e.y1,e.x2,
-e.y2,"white",0,null,!1,!1,!1,!1,0.3):"pie"===c.type||"doughnut"===c.type?pa(b,e.center,e.radius,"white",c.type,e.startAngle,e.endAngle,0.3):"candlestick"===c.type?(b.globalAlpha=1,b.strokeStyle=e.color,b.lineWidth=2*e.borderThickness,c=0===b.lineWidth%2?0:0.5,b.beginPath(),b.moveTo(e.x3-c,e.y2),b.lineTo(e.x3-c,Math.min(e.y1,e.y4)),b.stroke(),b.beginPath(),b.moveTo(e.x3-c,Math.max(e.y1,e.y4)),b.lineTo(e.x3-c,e.y3),b.stroke(),F(b,e.x1,Math.min(e.y1,e.y4),e.x2,Math.max(e.y1,e.y4),"transparent",2*e.borderThickness,
-e.color,!1,!1,!1,!1),b.globalAlpha=1):"ohlc"===c.type&&(b.globalAlpha=1,b.strokeStyle=e.color,b.lineWidth=2*e.borderThickness,c=0===b.lineWidth%2?0:0.5,b.beginPath(),b.moveTo(e.x3-c,e.y2),b.lineTo(e.x3-c,e.y3),b.stroke(),b.beginPath(),b.moveTo(e.x3,e.y1),b.lineTo(e.x1,e.y1),b.stroke(),b.beginPath(),b.moveTo(e.x3,e.y4),b.lineTo(e.x2,e.y4),b.stroke(),b.globalAlpha=1)}}b.globalAlpha=1;b.beginPath()}};N.prototype.getToolTipInnerHTML=function(a){a=a.entries;for(var b=null,c=null,d=null,e=0,f="",g=!0,k=
-0;k<a.length;k++)if(a[k].dataSeries.toolTipContent||a[k].dataPoint.toolTipContent){g=!1;break}if(g&&this.content&&"function"===typeof this.content)b=this.content({entries:a});else if(this.shared){for(var p="",k=0;k<a.length;k++)if(c=a[k].dataSeries,d=a[k].dataPoint,e=a[k].index,f="",0===k&&(g&&!this.content)&&(p+="undefined"!==typeof this.chart.axisX.labels[d.x]?this.chart.axisX.labels[d.x]:"{x}",p+="</br>",p=this.chart.replaceKeywordsWithValue(p,d,c,e)),null!==d.toolTipContent&&("undefined"!==typeof d.toolTipContent||
-null!==c._options.toolTipContent)){if("line"===c.type||"stepLine"===c.type||"spline"===c.type||"area"===c.type||"stepArea"===c.type||"splineArea"===c.type||"column"===c.type||"bar"===c.type||"scatter"===c.type||"stackedColumn"===c.type||"stackedColumn100"===c.type||"stackedBar"===c.type||"stackedBar100"===c.type||"stackedArea"===c.type||"stackedArea100"===c.type)f+=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>{name}:</span> {y}";
-else if("bubble"===c.type)f+=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>{name}:</span> {y}, {z}";else if("pie"===c.type||"doughnut"===c.type||"funnel"===c.type)f+=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:" {y}";else if("rangeColumn"===c.type||"rangeBar"===c.type||
-"rangeArea"===c.type||"rangeSplineArea"===c.type)f+=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>{name}:</span> {y[0]}, {y[1]}";else if("candlestick"===c.type||"ohlc"===c.type)f+=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>{name}:</span><br/>Open: {y[0]}<br/>High: {y[1]}<br/>Low: {y[2]}<br/>Close: {y[3]}";
-null===b&&(b="");b+=this.chart.replaceKeywordsWithValue(f,d,c,e);k<a.length-1&&(b+="</br>")}null!==b&&(b=p+b)}else{c=a[0].dataSeries;d=a[0].dataPoint;e=a[0].index;if(null===d.toolTipContent||"undefined"===typeof d.toolTipContent&&null===c._options.toolTipContent)return null;if("line"===c.type||"stepLine"===c.type||"spline"===c.type||"area"===c.type||"stepArea"===c.type||"splineArea"===c.type||"column"===c.type||"bar"===c.type||"scatter"===c.type||"stackedColumn"===c.type||"stackedColumn100"===c.type||
-"stackedBar"===c.type||"stackedBar100"===c.type||"stackedArea"===c.type||"stackedArea100"===c.type)f=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>"+(d.label?"{label}":"{x}")+" :</span> {y}";else if("bubble"===c.type)f=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>"+
-(d.label?"{label}":"{x}")+":</span> {y}, {z}";else if("pie"===c.type||"doughnut"===c.type||"funnel"===c.type)f=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:(d.name?"{name}: ":d.label?"{label}: ":"")+"{y}";else if("rangeColumn"===c.type||"rangeBar"===c.type||"rangeArea"===c.type||"rangeSplineArea"===c.type)f=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:
-this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>"+(d.label?"{label}":"{x}")+" :</span> {y[0]}, {y[1]}";else if("candlestick"===c.type||"ohlc"===c.type)f=d.toolTipContent?d.toolTipContent:c.toolTipContent?c.toolTipContent:this.content&&"function"!==typeof this.content?this.content:"<span style='\"'color:{color};'\"'>"+(d.label?"{label}":"{x}")+"</span><br/>Open: {y[0]}<br/>High: {y[1]}<br/>Low: {y[2]}<br/>Close: {y[3]}";
-null===b&&(b="");b+=this.chart.replaceKeywordsWithValue(f,d,c,e)}return b};N.prototype.enableAnimation=function(){this.container.style.WebkitTransition||(this.container.style.WebkitTransition="left .2s ease-out, bottom .2s ease-out",this.container.style.MozTransition="left .2s ease-out, bottom .2s ease-out",this.container.style.MsTransition="left .2s ease-out, bottom .2s ease-out",this.container.style.transition="left .2s ease-out, bottom .2s ease-out")};N.prototype.disableAnimation=function(){this.container.style.WebkitTransition&&
-(this.container.style.WebkitTransition="",this.container.style.MozTransition="",this.container.style.MsTransition="",this.container.style.transition="")};N.prototype.hide=function(a){this.enabled&&(this.container.style.display="none",this.currentSeriesIndex=-1,this._prevY=this._prevX=NaN,("undefined"===typeof a||a)&&this.chart.resetOverlayedCanvas())};v.prototype.replaceKeywordsWithValue=function(a,b,c,d,e){var f=this;e="undefined"===typeof e?0:e;if((0<=c.type.indexOf("stacked")||"pie"===c.type||
-"doughnut"===c.type)&&(0<=a.indexOf("#percent")||0<=a.indexOf("#total"))){var g="#percent",k="#total",p=null;if(0<=c.type.indexOf("stacked"))k=0,p=b.x.getTime?b.x.getTime():b.x,p in c.plotUnit.yTotals&&(k=c.plotUnit.yTotals[p],g=isNaN(b.y)?0:100*(b.y/k));else if("pie"===c.type||"doughnut"===c.type){for(i=k=0;i<c.dataPoints.length;i++)isNaN(c.dataPoints[i].y)||(k+=c.dataPoints[i].y);g=isNaN(b.y)?0:100*(b.y/k)}do{p="";if(c.percentFormatString)p=c.percentFormatString;else{var p="#,##0.",h=Math.max(Math.ceil(Math.log(1/
-Math.abs(g))/Math.LN10),2);if(isNaN(h)||!isFinite(h))h=2;for(var l=0;l<h;l++)p+="#"}a=a.replace("#percent",X(g,p,f._cultureInfo));a=a.replace("#total",X(k,c.yValueFormatString?c.yValueFormatString:"#,##0.########"))}while(0<=a.indexOf("#percent")||0<=a.indexOf("#total"))}return a.replace(/\{.*?\}|"[^"]*"|'[^']*'/g,function(a){if('"'===a[0]&&'"'===a[a.length-1]||"'"===a[0]&&"'"===a[a.length-1])return a.slice(1,a.length-1);a=Z(a.slice(1,a.length-1));a=a.replace("#index",e);var g=null;try{var h=a.match(/(.*?)\s*\[\s*(.*?)\s*\]/);
-h&&0<h.length&&(g=Z(h[2]),a=Z(h[1]))}catch(k){}h=null;if("color"===a)return b.color?b.color:c.color?c.color:c._colorSet[d%c._colorSet.length];if(b.hasOwnProperty(a))h=b;else if(c.hasOwnProperty(a))h=c;else return"";h=h[a];null!==g&&(h=h[g]);return"x"===a?f.axisX&&"dateTime"===f.plotInfo.axisXValueType?ya(h,b.xValueFormatString?b.xValueFormatString:c.xValueFormatString?c.xValueFormatString:f.axisX&&f.axisX.valueFormatString?f.axisX.valueFormatString:"DD MMM YY",f._cultureInfo):X(h,b.xValueFormatString?
-b.xValueFormatString:c.xValueFormatString?c.xValueFormatString:"#,##0.########",f._cultureInfo):"y"===a?X(h,b.yValueFormatString?b.yValueFormatString:c.yValueFormatString?c.yValueFormatString:"#,##0.########",f._cultureInfo):"z"===a?X(h,b.zValueFormatString?b.zValueFormatString:c.zValueFormatString?c.zValueFormatString:"#,##0.########",f._cultureInfo):h})};$.prototype.reset=function(){this.lastObjectId=0;this.objectMap=[];this.rectangularRegionEventSubscriptions=[];this.previousDataPointEventObject=
-null;this.eventObjects=[];t&&(this.ghostCtx.clearRect(0,0,this.chart.width,this.chart.height),this.ghostCtx.beginPath())};$.prototype.getNewObjectTrackingId=function(){return++this.lastObjectId};$.prototype.mouseEventHandler=function(a){if("mousemove"===a.type||"click"===a.type){var b=[],c=ia(a),d=null;if((d=this.chart.getObjectAtXY(c.x,c.y,!1))&&"undefined"!==typeof this.objectMap[d])if(d=this.objectMap[d],"dataPoint"===d.objectType){var e=this.chart.data[d.dataSeriesIndex],f=e.dataPoints[d.dataPointIndex],
-g=d.dataPointIndex;d.eventParameter={x:c.x,y:c.y,dataPoint:f,dataSeries:e._options,dataPointIndex:g,dataSeriesIndex:e.index,chart:this.chart._publicChartReference};d.eventContext={context:f,userContext:f,mouseover:"mouseover",mousemove:"mousemove",mouseout:"mouseout",click:"click"};b.push(d);d=this.objectMap[e.id];d.eventParameter={x:c.x,y:c.y,dataPoint:f,dataSeries:e._options,dataPointIndex:g,dataSeriesIndex:e.index,chart:this.chart._publicChartReference};d.eventContext={context:e,userContext:e._options,
-mouseover:"mouseover",mousemove:"mousemove",mouseout:"mouseout",click:"click"};b.push(this.objectMap[e.id])}else"legendItem"===d.objectType&&(e=this.chart.data[d.dataSeriesIndex],f=null!==d.dataPointIndex?e.dataPoints[d.dataPointIndex]:null,d.eventParameter={x:c.x,y:c.y,dataSeries:e._options,dataPoint:f,dataPointIndex:d.dataPointIndex,dataSeriesIndex:d.dataSeriesIndex,chart:this.chart._publicChartReference},d.eventContext={context:this.chart.legend,userContext:this.chart.legend._options,mouseover:"itemmouseover",
-mousemove:"itemmousemove",mouseout:"itemmouseout",click:"itemclick"},b.push(d));e=[];for(c=0;c<this.mouseoveredObjectMaps.length;c++){f=!0;for(d=0;d<b.length;d++)if(b[d].id===this.mouseoveredObjectMaps[c].id){f=!1;break}f?this.fireEvent(this.mouseoveredObjectMaps[c],"mouseout",a):e.push(this.mouseoveredObjectMaps[c])}this.mouseoveredObjectMaps=e;for(c=0;c<b.length;c++){e=!1;for(d=0;d<this.mouseoveredObjectMaps.length;d++)if(b[c].id===this.mouseoveredObjectMaps[d].id){e=!0;break}e||(this.fireEvent(b[c],
-"mouseover",a),this.mouseoveredObjectMaps.push(b[c]));"click"===a.type?this.fireEvent(b[c],"click",a):"mousemove"===a.type&&this.fireEvent(b[c],"mousemove",a)}}};$.prototype.fireEvent=function(a,b,c){if(a&&b){var d=a.eventParameter,e=a.eventContext,f=a.eventContext.userContext;f&&(e&&f[e[b]])&&f[e[b]].call(f,d);"mouseout"!==b?f.cursor&&f.cursor!==c.target.style.cursor&&(c.target.style.cursor=f.cursor):(c.target.style.cursor=this.chart._defaultCursor,delete a.eventParameter,delete a.eventContext);
-"click"===b&&("dataPoint"===a.objectType&&this.chart.pieDoughnutClickHandler)&&this.chart.pieDoughnutClickHandler.call(this.chart.data[a.dataSeriesIndex],d)}};O(xa,L);oa.prototype.animate=function(a,b,c,d,e){var f=this;this.chart.isAnimating=!0;e=e||y.easing.linear;c&&this.animations.push({startTime:(new Date).getTime()+(a?a:0),duration:b,animationCallback:c,onComplete:d});for(a=[];0<this.animations.length;)if(b=this.animations.shift(),c=(new Date).getTime(),d=0,b.startTime<=c&&(d=e(Math.min(c-b.startTime,
-b.duration),0,1,b.duration),d=Math.min(d,1),isNaN(d)||!isFinite(d))&&(d=1),1>d&&a.push(b),b.animationCallback(d),1<=d&&b.onComplete)b.onComplete();this.animations=a;0<this.animations.length?this.animationRequestId=this.chart.requestAnimFrame.call(window,function(){f.animate.call(f)}):this.chart.isAnimating=!1};oa.prototype.cancelAllAnimations=function(){this.animations=[];this.animationRequestId&&this.chart.cancelRequestAnimFrame.call(window,this.animationRequestId);this.animationRequestId=null;this.chart.isAnimating=
-!1};var y={yScaleAnimation:function(a,b){if(0!==a){var c=b.dest,d=b.source.canvas,e=b.animationBase;c.drawImage(d,0,0,d.width,d.height,0,e-e*a,c.canvas.width/H,a*c.canvas.height/H)}},xScaleAnimation:function(a,b){if(0!==a){var c=b.dest,d=b.source.canvas,e=b.animationBase;c.drawImage(d,0,0,d.width,d.height,e-e*a,0,a*c.canvas.width/H,c.canvas.height/H)}},xClipAnimation:function(a,b){if(0!==a){var c=b.dest,d=b.source.canvas;c.save();0<a&&c.drawImage(d,0,0,d.width*a,d.height,0,0,d.width*a/H,d.height/
-H);c.restore()}},fadeInAnimation:function(a,b){if(0!==a){var c=b.dest,d=b.source.canvas;c.save();c.globalAlpha=a;c.drawImage(d,0,0,d.width,d.height,0,0,c.canvas.width/H,c.canvas.height/H);c.restore()}},easing:{linear:function(a,b,c,d){return c*a/d+b},easeOutQuad:function(a,b,c,d){return-c*(a/=d)*(a-2)+b},easeOutQuart:function(a,b,c,d){return-c*((a=a/d-1)*a*a*a-1)+b},easeInQuad:function(a,b,c,d){return c*(a/=d)*a+b},easeInQuart:function(a,b,c,d){return c*(a/=d)*a*a*a+b}}},J={drawMarker:function(a,
-b,c,d,e,f,g,k){if(c){var p=1;c.fillStyle=f?f:"#000000";c.strokeStyle=g?g:"#000000";c.lineWidth=k?k:0;"circle"===d?(c.moveTo(a,b),c.beginPath(),c.arc(a,b,e/2,0,2*Math.PI,!1),f&&c.fill(),k&&(g?c.stroke():(p=c.globalAlpha,c.globalAlpha=0.15,c.strokeStyle="black",c.stroke(),c.globalAlpha=p))):"square"===d?(c.beginPath(),c.rect(a-e/2,b-e/2,e,e),f&&c.fill(),k&&(g?c.stroke():(p=c.globalAlpha,c.globalAlpha=0.15,c.strokeStyle="black",c.stroke(),c.globalAlpha=p))):"triangle"===d?(c.beginPath(),c.moveTo(a-e/
-2,b+e/2),c.lineTo(a+e/2,b+e/2),c.lineTo(a,b-e/2),c.closePath(),f&&c.fill(),k&&(g?c.stroke():(p=c.globalAlpha,c.globalAlpha=0.15,c.strokeStyle="black",c.stroke(),c.globalAlpha=p)),c.beginPath()):"cross"===d&&(c.strokeStyle=f,c.lineWidth=e/4,c.beginPath(),c.moveTo(a-e/2,b-e/2),c.lineTo(a+e/2,b+e/2),c.stroke(),c.moveTo(a+e/2,b-e/2),c.lineTo(a-e/2,b+e/2),c.stroke())}},drawMarkers:function(a){for(var b=0;b<a.length;b++){var c=a[b];J.drawMarker(c.x,c.y,c.ctx,c.type,c.size,c.color,c.borderColor,c.borderThickness)}}},
-za={Chart:function(a,b){var c=new v(a,b,this);this.render=function(){c.render(this.options)};this.options=c._options},addColorSet:function(a,b){V[a]=b},addCultureInfo:function(a,b){na[a]=b}};za.Chart.version="v1.6.1 GA";window.CanvasJS=za})();
-/*
- excanvas is used to support IE678 which do not implement HTML5 Canvas Element. You can safely remove the following excanvas code if you don't need to support older browsers.
-
- Copyright 2006 Google Inc. https://code.google.com/p/explorercanvas/
- Licensed under the Apache License, Version 2.0
-*/
-document.createElement("canvas").getContext||function(){function V(){return this.context_||(this.context_=new C(this))}function W(a,b,c){var g=M.call(arguments,2);return function(){return a.apply(b,g.concat(M.call(arguments)))}}function N(a){return String(a).replace(/&/g,"&").replace(/"/g,""")}function O(a){a.namespaces.g_vml_||a.namespaces.add("g_vml_","urn:schemas-microsoft-com:vml","#default#VML");a.namespaces.g_o_||a.namespaces.add("g_o_","urn:schemas-microsoft-com:office:office","#default#VML");
-a.styleSheets.ex_canvas_||(a=a.createStyleSheet(),a.owningElement.id="ex_canvas_",a.cssText="canvas{display:inline-block;overflow:hidden;text-align:left;width:300px;height:150px}")}function X(a){var b=a.srcElement;switch(a.propertyName){case "width":b.getContext().clearRect();b.style.width=b.attributes.width.nodeValue+"px";b.firstChild.style.width=b.clientWidth+"px";break;case "height":b.getContext().clearRect(),b.style.height=b.attributes.height.nodeValue+"px",b.firstChild.style.height=b.clientHeight+
-"px"}}function Y(a){a=a.srcElement;a.firstChild&&(a.firstChild.style.width=a.clientWidth+"px",a.firstChild.style.height=a.clientHeight+"px")}function D(){return[[1,0,0],[0,1,0],[0,0,1]]}function t(a,b){for(var c=D(),g=0;3>g;g++)for(var e=0;3>e;e++){for(var f=0,d=0;3>d;d++)f+=a[g][d]*b[d][e];c[g][e]=f}return c}function P(a,b){b.fillStyle=a.fillStyle;b.lineCap=a.lineCap;b.lineJoin=a.lineJoin;b.lineWidth=a.lineWidth;b.miterLimit=a.miterLimit;b.shadowBlur=a.shadowBlur;b.shadowColor=a.shadowColor;b.shadowOffsetX=
-a.shadowOffsetX;b.shadowOffsetY=a.shadowOffsetY;b.strokeStyle=a.strokeStyle;b.globalAlpha=a.globalAlpha;b.font=a.font;b.textAlign=a.textAlign;b.textBaseline=a.textBaseline;b.arcScaleX_=a.arcScaleX_;b.arcScaleY_=a.arcScaleY_;b.lineScale_=a.lineScale_}function Q(a){var b=a.indexOf("(",3),c=a.indexOf(")",b+1),b=a.substring(b+1,c).split(",");if(4!=b.length||"a"!=a.charAt(3))b[3]=1;return b}function E(a,b,c){return Math.min(c,Math.max(b,a))}function F(a,b,c){0>c&&c++;1<c&&c--;return 1>6*c?a+6*(b-a)*c:
-1>2*c?b:2>3*c?a+6*(b-a)*(2/3-c):a}function G(a){if(a in H)return H[a];var b,c=1;a=String(a);if("#"==a.charAt(0))b=a;else if(/^rgb/.test(a)){c=Q(a);b="#";for(var g,e=0;3>e;e++)g=-1!=c[e].indexOf("%")?Math.floor(255*(parseFloat(c[e])/100)):+c[e],b+=v[E(g,0,255)];c=+c[3]}else if(/^hsl/.test(a)){e=c=Q(a);b=parseFloat(e[0])/360%360;0>b&&b++;g=E(parseFloat(e[1])/100,0,1);e=E(parseFloat(e[2])/100,0,1);if(0==g)g=e=b=e;else{var f=0.5>e?e*(1+g):e+g-e*g,d=2*e-f;g=F(d,f,b+1/3);e=F(d,f,b);b=F(d,f,b-1/3)}b="#"+
-v[Math.floor(255*g)]+v[Math.floor(255*e)]+v[Math.floor(255*b)];c=c[3]}else b=Z[a]||a;return H[a]={color:b,alpha:c}}function C(a){this.m_=D();this.mStack_=[];this.aStack_=[];this.currentPath_=[];this.fillStyle=this.strokeStyle="#000";this.lineWidth=1;this.lineJoin="miter";this.lineCap="butt";this.miterLimit=1*q;this.globalAlpha=1;this.font="10px sans-serif";this.textAlign="left";this.textBaseline="alphabetic";this.canvas=a;var b="width:"+a.clientWidth+"px;height:"+a.clientHeight+"px;overflow:hidden;position:absolute",
-c=a.ownerDocument.createElement("div");c.style.cssText=b;a.appendChild(c);b=c.cloneNode(!1);b.style.backgroundColor="red";b.style.filter="alpha(opacity=0)";a.appendChild(b);this.element_=c;this.lineScale_=this.arcScaleY_=this.arcScaleX_=1}function R(a,b,c,g){a.currentPath_.push({type:"bezierCurveTo",cp1x:b.x,cp1y:b.y,cp2x:c.x,cp2y:c.y,x:g.x,y:g.y});a.currentX_=g.x;a.currentY_=g.y}function S(a,b){var c=G(a.strokeStyle),g=c.color,c=c.alpha*a.globalAlpha,e=a.lineScale_*a.lineWidth;1>e&&(c*=e);b.push("<g_vml_:stroke",
-' opacity="',c,'"',' joinstyle="',a.lineJoin,'"',' miterlimit="',a.miterLimit,'"',' endcap="',$[a.lineCap]||"square",'"',' weight="',e,'px"',' color="',g,'" />')}function T(a,b,c,g){var e=a.fillStyle,f=a.arcScaleX_,d=a.arcScaleY_,k=g.x-c.x,n=g.y-c.y;if(e instanceof w){var h=0,l=g=0,u=0,m=1;if("gradient"==e.type_){h=e.x1_/f;c=e.y1_/d;var p=s(a,e.x0_/f,e.y0_/d),h=s(a,h,c),h=180*Math.atan2(h.x-p.x,h.y-p.y)/Math.PI;0>h&&(h+=360);1E-6>h&&(h=0)}else p=s(a,e.x0_,e.y0_),g=(p.x-c.x)/k,l=(p.y-c.y)/n,k/=f*q,
-n/=d*q,m=x.max(k,n),u=2*e.r0_/m,m=2*e.r1_/m-u;f=e.colors_;f.sort(function(a,b){return a.offset-b.offset});d=f.length;p=f[0].color;c=f[d-1].color;k=f[0].alpha*a.globalAlpha;a=f[d-1].alpha*a.globalAlpha;for(var n=[],r=0;r<d;r++){var t=f[r];n.push(t.offset*m+u+" "+t.color)}b.push('<g_vml_:fill type="',e.type_,'"',' method="none" focus="100%"',' color="',p,'"',' color2="',c,'"',' colors="',n.join(","),'"',' opacity="',a,'"',' g_o_:opacity2="',k,'"',' angle="',h,'"',' focusposition="',g,",",l,'" />')}else e instanceof
-I?k&&n&&b.push("<g_vml_:fill",' position="',-c.x/k*f*f,",",-c.y/n*d*d,'"',' type="tile"',' src="',e.src_,'" />'):(e=G(a.fillStyle),b.push('<g_vml_:fill color="',e.color,'" opacity="',e.alpha*a.globalAlpha,'" />'))}function s(a,b,c){a=a.m_;return{x:q*(b*a[0][0]+c*a[1][0]+a[2][0])-r,y:q*(b*a[0][1]+c*a[1][1]+a[2][1])-r}}function z(a,b,c){isFinite(b[0][0])&&(isFinite(b[0][1])&&isFinite(b[1][0])&&isFinite(b[1][1])&&isFinite(b[2][0])&&isFinite(b[2][1]))&&(a.m_=b,c&&(a.lineScale_=aa(ba(b[0][0]*b[1][1]-b[0][1]*
-b[1][0]))))}function w(a){this.type_=a;this.r1_=this.y1_=this.x1_=this.r0_=this.y0_=this.x0_=0;this.colors_=[]}function I(a,b){if(!a||1!=a.nodeType||"IMG"!=a.tagName)throw new A("TYPE_MISMATCH_ERR");if("complete"!=a.readyState)throw new A("INVALID_STATE_ERR");switch(b){case "repeat":case null:case "":this.repetition_="repeat";break;case "repeat-x":case "repeat-y":case "no-repeat":this.repetition_=b;break;default:throw new A("SYNTAX_ERR");}this.src_=a.src;this.width_=a.width;this.height_=a.height}
-function A(a){this.code=this[a];this.message=a+": DOM Exception "+this.code}var x=Math,k=x.round,J=x.sin,K=x.cos,ba=x.abs,aa=x.sqrt,q=10,r=q/2;navigator.userAgent.match(/MSIE ([\d.]+)?/);var M=Array.prototype.slice;O(document);var U={init:function(a){a=a||document;a.createElement("canvas");a.attachEvent("onreadystatechange",W(this.init_,this,a))},init_:function(a){a=a.getElementsByTagName("canvas");for(var b=0;b<a.length;b++)this.initElement(a[b])},initElement:function(a){if(!a.getContext){a.getContext=
-V;O(a.ownerDocument);a.innerHTML="";a.attachEvent("onpropertychange",X);a.attachEvent("onresize",Y);var b=a.attributes;b.width&&b.width.specified?a.style.width=b.width.nodeValue+"px":a.width=a.clientWidth;b.height&&b.height.specified?a.style.height=b.height.nodeValue+"px":a.height=a.clientHeight}return a}};U.init();for(var v=[],d=0;16>d;d++)for(var B=0;16>B;B++)v[16*d+B]=d.toString(16)+B.toString(16);var Z={aliceblue:"#F0F8FF",antiquewhite:"#FAEBD7",aquamarine:"#7FFFD4",azure:"#F0FFFF",beige:"#F5F5DC",
-bisque:"#FFE4C4",black:"#000000",blanchedalmond:"#FFEBCD",blueviolet:"#8A2BE2",brown:"#A52A2A",burlywood:"#DEB887",cadetblue:"#5F9EA0",chartreuse:"#7FFF00",chocolate:"#D2691E",coral:"#FF7F50",cornflowerblue:"#6495ED",cornsilk:"#FFF8DC",crimson:"#DC143C",cyan:"#00FFFF",darkblue:"#00008B",darkcyan:"#008B8B",darkgoldenrod:"#B8860B",darkgray:"#A9A9A9",darkgreen:"#006400",darkgrey:"#A9A9A9",darkkhaki:"#BDB76B",darkmagenta:"#8B008B",darkolivegreen:"#556B2F",darkorange:"#FF8C00",darkorchid:"#9932CC",darkred:"#8B0000",
-darksalmon:"#E9967A",darkseagreen:"#8FBC8F",darkslateblue:"#483D8B",darkslategray:"#2F4F4F",darkslategrey:"#2F4F4F",darkturquoise:"#00CED1",darkviolet:"#9400D3",deeppink:"#FF1493",deepskyblue:"#00BFFF",dimgray:"#696969",dimgrey:"#696969",dodgerblue:"#1E90FF",firebrick:"#B22222",floralwhite:"#FFFAF0",forestgreen:"#228B22",gainsboro:"#DCDCDC",ghostwhite:"#F8F8FF",gold:"#FFD700",goldenrod:"#DAA520",grey:"#808080",greenyellow:"#ADFF2F",honeydew:"#F0FFF0",hotpink:"#FF69B4",indianred:"#CD5C5C",indigo:"#4B0082",
-ivory:"#FFFFF0",khaki:"#F0E68C",lavender:"#E6E6FA",lavenderblush:"#FFF0F5",lawngreen:"#7CFC00",lemonchiffon:"#FFFACD",lightblue:"#ADD8E6",lightcoral:"#F08080",lightcyan:"#E0FFFF",lightgoldenrodyellow:"#FAFAD2",lightgreen:"#90EE90",lightgrey:"#D3D3D3",lightpink:"#FFB6C1",lightsalmon:"#FFA07A",lightseagreen:"#20B2AA",lightskyblue:"#87CEFA",lightslategray:"#778899",lightslategrey:"#778899",lightsteelblue:"#B0C4DE",lightyellow:"#FFFFE0",limegreen:"#32CD32",linen:"#FAF0E6",magenta:"#FF00FF",mediumaquamarine:"#66CDAA",
-mediumblue:"#0000CD",mediumorchid:"#BA55D3",mediumpurple:"#9370DB",mediumseagreen:"#3CB371",mediumslateblue:"#7B68EE",mediumspringgreen:"#00FA9A",mediumturquoise:"#48D1CC",mediumvioletred:"#C71585",midnightblue:"#191970",mintcream:"#F5FFFA",mistyrose:"#FFE4E1",moccasin:"#FFE4B5",navajowhite:"#FFDEAD",oldlace:"#FDF5E6",olivedrab:"#6B8E23",orange:"#FFA500",orangered:"#FF4500",orchid:"#DA70D6",palegoldenrod:"#EEE8AA",palegreen:"#98FB98",paleturquoise:"#AFEEEE",palevioletred:"#DB7093",papayawhip:"#FFEFD5",
-peachpuff:"#FFDAB9",peru:"#CD853F",pink:"#FFC0CB",plum:"#DDA0DD",powderblue:"#B0E0E6",rosybrown:"#BC8F8F",royalblue:"#4169E1",saddlebrown:"#8B4513",salmon:"#FA8072",sandybrown:"#F4A460",seagreen:"#2E8B57",seashell:"#FFF5EE",sienna:"#A0522D",skyblue:"#87CEEB",slateblue:"#6A5ACD",slategray:"#708090",slategrey:"#708090",snow:"#FFFAFA",springgreen:"#00FF7F",steelblue:"#4682B4",tan:"#D2B48C",thistle:"#D8BFD8",tomato:"#FF6347",turquoise:"#40E0D0",violet:"#EE82EE",wheat:"#F5DEB3",whitesmoke:"#F5F5F5",yellowgreen:"#9ACD32"},
-H={},L={},$={butt:"flat",round:"round"},d=C.prototype;d.clearRect=function(){this.textMeasureEl_&&(this.textMeasureEl_.removeNode(!0),this.textMeasureEl_=null);this.element_.innerHTML=""};d.beginPath=function(){this.currentPath_=[]};d.moveTo=function(a,b){var c=s(this,a,b);this.currentPath_.push({type:"moveTo",x:c.x,y:c.y});this.currentX_=c.x;this.currentY_=c.y};d.lineTo=function(a,b){var c=s(this,a,b);this.currentPath_.push({type:"lineTo",x:c.x,y:c.y});this.currentX_=c.x;this.currentY_=c.y};d.bezierCurveTo=
-function(a,b,c,g,e,f){e=s(this,e,f);a=s(this,a,b);c=s(this,c,g);R(this,a,c,e)};d.quadraticCurveTo=function(a,b,c,g){a=s(this,a,b);c=s(this,c,g);g={x:this.currentX_+2/3*(a.x-this.currentX_),y:this.currentY_+2/3*(a.y-this.currentY_)};R(this,g,{x:g.x+(c.x-this.currentX_)/3,y:g.y+(c.y-this.currentY_)/3},c)};d.arc=function(a,b,c,g,e,f){c*=q;var d=f?"at":"wa",k=a+K(g)*c-r,n=b+J(g)*c-r;g=a+K(e)*c-r;e=b+J(e)*c-r;k!=g||f||(k+=0.125);a=s(this,a,b);k=s(this,k,n);g=s(this,g,e);this.currentPath_.push({type:d,
-x:a.x,y:a.y,radius:c,xStart:k.x,yStart:k.y,xEnd:g.x,yEnd:g.y})};d.rect=function(a,b,c,g){this.moveTo(a,b);this.lineTo(a+c,b);this.lineTo(a+c,b+g);this.lineTo(a,b+g);this.closePath()};d.strokeRect=function(a,b,c,g){var e=this.currentPath_;this.beginPath();this.moveTo(a,b);this.lineTo(a+c,b);this.lineTo(a+c,b+g);this.lineTo(a,b+g);this.closePath();this.stroke();this.currentPath_=e};d.fillRect=function(a,b,c,g){var e=this.currentPath_;this.beginPath();this.moveTo(a,b);this.lineTo(a+c,b);this.lineTo(a+
-c,b+g);this.lineTo(a,b+g);this.closePath();this.fill();this.currentPath_=e};d.createLinearGradient=function(a,b,c,g){var e=new w("gradient");e.x0_=a;e.y0_=b;e.x1_=c;e.y1_=g;return e};d.createRadialGradient=function(a,b,c,g,e,f){var d=new w("gradientradial");d.x0_=a;d.y0_=b;d.r0_=c;d.x1_=g;d.y1_=e;d.r1_=f;return d};d.drawImage=function(a,b){var c,g,e,d,r,y,n,h;e=a.runtimeStyle.width;d=a.runtimeStyle.height;a.runtimeStyle.width="auto";a.runtimeStyle.height="auto";var l=a.width,u=a.height;a.runtimeStyle.width=
-e;a.runtimeStyle.height=d;if(3==arguments.length)c=arguments[1],g=arguments[2],r=y=0,n=e=l,h=d=u;else if(5==arguments.length)c=arguments[1],g=arguments[2],e=arguments[3],d=arguments[4],r=y=0,n=l,h=u;else if(9==arguments.length)r=arguments[1],y=arguments[2],n=arguments[3],h=arguments[4],c=arguments[5],g=arguments[6],e=arguments[7],d=arguments[8];else throw Error("Invalid number of arguments");var m=s(this,c,g),p=[];p.push(" <g_vml_:group",' coordsize="',10*q,",",10*q,'"',' coordorigin="0,0"',' style="width:',
-10,"px;height:",10,"px;position:absolute;");if(1!=this.m_[0][0]||this.m_[0][1]||1!=this.m_[1][1]||this.m_[1][0]){var t=[];t.push("M11=",this.m_[0][0],",","M12=",this.m_[1][0],",","M21=",this.m_[0][1],",","M22=",this.m_[1][1],",","Dx=",k(m.x/q),",","Dy=",k(m.y/q),"");var v=s(this,c+e,g),w=s(this,c,g+d);c=s(this,c+e,g+d);m.x=x.max(m.x,v.x,w.x,c.x);m.y=x.max(m.y,v.y,w.y,c.y);p.push("padding:0 ",k(m.x/q),"px ",k(m.y/q),"px 0;filter:progid:DXImageTransform.Microsoft.Matrix(",t.join(""),", sizingmethod='clip');")}else p.push("top:",
-k(m.y/q),"px;left:",k(m.x/q),"px;");p.push(' ">','<g_vml_:image src="',a.src,'"',' style="width:',q*e,"px;"," height:",q*d,'px"',' cropleft="',r/l,'"',' croptop="',y/u,'"',' cropright="',(l-r-n)/l,'"',' cropbottom="',(u-y-h)/u,'"'," />","</g_vml_:group>");this.element_.insertAdjacentHTML("BeforeEnd",p.join(""))};d.stroke=function(a){var b=[];b.push("<g_vml_:shape",' filled="',!!a,'"',' style="position:absolute;width:',10,"px;height:",10,'px;"',' coordorigin="0,0"',' coordsize="',10*q,",",10*q,'"',
-' stroked="',!a,'"',' path="');for(var c={x:null,y:null},d={x:null,y:null},e=0;e<this.currentPath_.length;e++){var f=this.currentPath_[e];switch(f.type){case "moveTo":b.push(" m ",k(f.x),",",k(f.y));break;case "lineTo":b.push(" l ",k(f.x),",",k(f.y));break;case "close":b.push(" x ");f=null;break;case "bezierCurveTo":b.push(" c ",k(f.cp1x),",",k(f.cp1y),",",k(f.cp2x),",",k(f.cp2y),",",k(f.x),",",k(f.y));break;case "at":case "wa":b.push(" ",f.type," ",k(f.x-this.arcScaleX_*f.radius),",",k(f.y-this.arcScaleY_*
-f.radius)," ",k(f.x+this.arcScaleX_*f.radius),",",k(f.y+this.arcScaleY_*f.radius)," ",k(f.xStart),",",k(f.yStart)," ",k(f.xEnd),",",k(f.yEnd))}if(f){if(null==c.x||f.x<c.x)c.x=f.x;if(null==d.x||f.x>d.x)d.x=f.x;if(null==c.y||f.y<c.y)c.y=f.y;if(null==d.y||f.y>d.y)d.y=f.y}}b.push(' ">');a?T(this,b,c,d):S(this,b);b.push("</g_vml_:shape>");this.element_.insertAdjacentHTML("beforeEnd",b.join(""))};d.fill=function(){this.stroke(!0)};d.closePath=function(){this.currentPath_.push({type:"close"})};d.save=function(){var a=
-{};P(this,a);this.aStack_.push(a);this.mStack_.push(this.m_);this.m_=t(D(),this.m_)};d.restore=function(){this.aStack_.length&&(P(this.aStack_.pop(),this),this.m_=this.mStack_.pop())};d.translate=function(a,b){z(this,t([[1,0,0],[0,1,0],[a,b,1]],this.m_),!1)};d.rotate=function(a){var b=K(a);a=J(a);z(this,t([[b,a,0],[-a,b,0],[0,0,1]],this.m_),!1)};d.scale=function(a,b){this.arcScaleX_*=a;this.arcScaleY_*=b;z(this,t([[a,0,0],[0,b,0],[0,0,1]],this.m_),!0)};d.transform=function(a,b,c,d,e,f){z(this,t([[a,
-b,0],[c,d,0],[e,f,1]],this.m_),!0)};d.setTransform=function(a,b,c,d,e,f){z(this,[[a,b,0],[c,d,0],[e,f,1]],!0)};d.drawText_=function(a,b,c,d,e){var f=this.m_;d=0;var r=1E3,t=0,n=[],h;h=this.font;if(L[h])h=L[h];else{var l=document.createElement("div").style;try{l.font=h}catch(u){}h=L[h]={style:l.fontStyle||"normal",variant:l.fontVariant||"normal",weight:l.fontWeight||"normal",size:l.fontSize||10,family:l.fontFamily||"sans-serif"}}var l=h,m=this.element_;h={};for(var p in l)h[p]=l[p];p=parseFloat(m.currentStyle.fontSize);
-m=parseFloat(l.size);"number"==typeof l.size?h.size=l.size:-1!=l.size.indexOf("px")?h.size=m:-1!=l.size.indexOf("em")?h.size=p*m:-1!=l.size.indexOf("%")?h.size=p/100*m:-1!=l.size.indexOf("pt")?h.size=m/0.75:h.size=p;h.size*=0.981;p=h.style+" "+h.variant+" "+h.weight+" "+h.size+"px "+h.family;m=this.element_.currentStyle;l=this.textAlign.toLowerCase();switch(l){case "left":case "center":case "right":break;case "end":l="ltr"==m.direction?"right":"left";break;case "start":l="rtl"==m.direction?"right":
-"left";break;default:l="left"}switch(this.textBaseline){case "hanging":case "top":t=h.size/1.75;break;case "middle":break;default:case null:case "alphabetic":case "ideographic":case "bottom":t=-h.size/2.25}switch(l){case "right":d=1E3;r=0.05;break;case "center":d=r=500}b=s(this,b+0,c+t);n.push('<g_vml_:line from="',-d,' 0" to="',r,' 0.05" ',' coordsize="100 100" coordorigin="0 0"',' filled="',!e,'" stroked="',!!e,'" style="position:absolute;width:1px;height:1px;">');e?S(this,n):T(this,n,{x:-d,y:0},
-{x:r,y:h.size});e=f[0][0].toFixed(3)+","+f[1][0].toFixed(3)+","+f[0][1].toFixed(3)+","+f[1][1].toFixed(3)+",0,0";b=k(b.x/q)+","+k(b.y/q);n.push('<g_vml_:skew on="t" matrix="',e,'" ',' offset="',b,'" origin="',d,' 0" />','<g_vml_:path textpathok="true" />','<g_vml_:textpath on="true" string="',N(a),'" style="v-text-align:',l,";font:",N(p),'" /></g_vml_:line>');this.element_.insertAdjacentHTML("beforeEnd",n.join(""))};d.fillText=function(a,b,c,d){this.drawText_(a,b,c,d,!1)};d.strokeText=function(a,
-b,c,d){this.drawText_(a,b,c,d,!0)};d.measureText=function(a){this.textMeasureEl_||(this.element_.insertAdjacentHTML("beforeEnd",'<span style="position:absolute;top:-20000px;left:0;padding:0;margin:0;border:none;white-space:pre;"></span>'),this.textMeasureEl_=this.element_.lastChild);var b=this.element_.ownerDocument;this.textMeasureEl_.innerHTML="";this.textMeasureEl_.style.font=this.font;this.textMeasureEl_.appendChild(b.createTextNode(a));return{width:this.textMeasureEl_.offsetWidth}};d.clip=function(){};
-d.arcTo=function(){};d.createPattern=function(a,b){return new I(a,b)};w.prototype.addColorStop=function(a,b){b=G(b);this.colors_.push({offset:a,color:b.color,alpha:b.alpha})};d=A.prototype=Error();d.INDEX_SIZE_ERR=1;d.DOMSTRING_SIZE_ERR=2;d.HIERARCHY_REQUEST_ERR=3;d.WRONG_DOCUMENT_ERR=4;d.INVALID_CHARACTER_ERR=5;d.NO_DATA_ALLOWED_ERR=6;d.NO_MODIFICATION_ALLOWED_ERR=7;d.NOT_FOUND_ERR=8;d.NOT_SUPPORTED_ERR=9;d.INUSE_ATTRIBUTE_ERR=10;d.INVALID_STATE_ERR=11;d.SYNTAX_ERR=12;d.INVALID_MODIFICATION_ERR=
-13;d.NAMESPACE_ERR=14;d.INVALID_ACCESS_ERR=15;d.VALIDATION_ERR=16;d.TYPE_MISMATCH_ERR=17;G_vmlCanvasManager=U;CanvasRenderingContext2D=C;CanvasGradient=w;CanvasPattern=I;DOMException=A}();
diff --git a/frc971/http_status/www/lib/jquery-1.4.4.js b/frc971/http_status/www/lib/jquery-1.4.4.js
deleted file mode 100644
index a4f1145..0000000
--- a/frc971/http_status/www/lib/jquery-1.4.4.js
+++ /dev/null
@@ -1,7179 +0,0 @@
-/*!
- * jQuery JavaScript Library v1.4.4
- * http://jquery.com/
- *
- * Copyright 2010, John Resig
- * Dual licensed under the MIT or GPL Version 2 licenses.
- * http://jquery.org/license
- *
- * Includes Sizzle.js
- * http://sizzlejs.com/
- * Copyright 2010, The Dojo Foundation
- * Released under the MIT, BSD, and GPL Licenses.
- *
- * Date: Thu Nov 11 19:04:53 2010 -0500
- */
-(function( window, undefined ) {
-
-// Use the correct document accordingly with window argument (sandbox)
-var document = window.document;
-var jQuery = (function() {
-
-// Define a local copy of jQuery
-var jQuery = function( selector, context ) {
- // The jQuery object is actually just the init constructor 'enhanced'
- return new jQuery.fn.init( selector, context );
- },
-
- // Map over jQuery in case of overwrite
- _jQuery = window.jQuery,
-
- // Map over the $ in case of overwrite
- _$ = window.$,
-
- // A central reference to the root jQuery(document)
- rootjQuery,
-
- // A simple way to check for HTML strings or ID strings
- // (both of which we optimize for)
- quickExpr = /^(?:[^<]*(<[\w\W]+>)[^>]*$|#([\w\-]+)$)/,
-
- // Is it a simple selector
- isSimple = /^.[^:#\[\.,]*$/,
-
- // Check if a string has a non-whitespace character in it
- rnotwhite = /\S/,
- rwhite = /\s/,
-
- // Used for trimming whitespace
- trimLeft = /^\s+/,
- trimRight = /\s+$/,
-
- // Check for non-word characters
- rnonword = /\W/,
-
- // Check for digits
- rdigit = /\d/,
-
- // Match a standalone tag
- rsingleTag = /^<(\w+)\s*\/?>(?:<\/\1>)?$/,
-
- // JSON RegExp
- rvalidchars = /^[\],:{}\s]*$/,
- rvalidescape = /\\(?:["\\\/bfnrt]|u[0-9a-fA-F]{4})/g,
- rvalidtokens = /"[^"\\\n\r]*"|true|false|null|-?\d+(?:\.\d*)?(?:[eE][+\-]?\d+)?/g,
- rvalidbraces = /(?:^|:|,)(?:\s*\[)+/g,
-
- // Useragent RegExp
- rwebkit = /(webkit)[ \/]([\w.]+)/,
- ropera = /(opera)(?:.*version)?[ \/]([\w.]+)/,
- rmsie = /(msie) ([\w.]+)/,
- rmozilla = /(mozilla)(?:.*? rv:([\w.]+))?/,
-
- // Keep a UserAgent string for use with jQuery.browser
- userAgent = navigator.userAgent,
-
- // For matching the engine and version of the browser
- browserMatch,
-
- // Has the ready events already been bound?
- readyBound = false,
-
- // The functions to execute on DOM ready
- readyList = [],
-
- // The ready event handler
- DOMContentLoaded,
-
- // Save a reference to some core methods
- toString = Object.prototype.toString,
- hasOwn = Object.prototype.hasOwnProperty,
- push = Array.prototype.push,
- slice = Array.prototype.slice,
- trim = String.prototype.trim,
- indexOf = Array.prototype.indexOf,
-
- // [[Class]] -> type pairs
- class2type = {};
-
-jQuery.fn = jQuery.prototype = {
- init: function( selector, context ) {
- var match, elem, ret, doc;
-
- // Handle $(""), $(null), or $(undefined)
- if ( !selector ) {
- return this;
- }
-
- // Handle $(DOMElement)
- if ( selector.nodeType ) {
- this.context = this[0] = selector;
- this.length = 1;
- return this;
- }
-
- // The body element only exists once, optimize finding it
- if ( selector === "body" && !context && document.body ) {
- this.context = document;
- this[0] = document.body;
- this.selector = "body";
- this.length = 1;
- return this;
- }
-
- // Handle HTML strings
- if ( typeof selector === "string" ) {
- // Are we dealing with HTML string or an ID?
- match = quickExpr.exec( selector );
-
- // Verify a match, and that no context was specified for #id
- if ( match && (match[1] || !context) ) {
-
- // HANDLE: $(html) -> $(array)
- if ( match[1] ) {
- doc = (context ? context.ownerDocument || context : document);
-
- // If a single string is passed in and it's a single tag
- // just do a createElement and skip the rest
- ret = rsingleTag.exec( selector );
-
- if ( ret ) {
- if ( jQuery.isPlainObject( context ) ) {
- selector = [ document.createElement( ret[1] ) ];
- jQuery.fn.attr.call( selector, context, true );
-
- } else {
- selector = [ doc.createElement( ret[1] ) ];
- }
-
- } else {
- ret = jQuery.buildFragment( [ match[1] ], [ doc ] );
- selector = (ret.cacheable ? ret.fragment.cloneNode(true) : ret.fragment).childNodes;
- }
-
- return jQuery.merge( this, selector );
-
- // HANDLE: $("#id")
- } else {
- elem = document.getElementById( match[2] );
-
- // Check parentNode to catch when Blackberry 4.6 returns
- // nodes that are no longer in the document #6963
- if ( elem && elem.parentNode ) {
- // Handle the case where IE and Opera return items
- // by name instead of ID
- if ( elem.id !== match[2] ) {
- return rootjQuery.find( selector );
- }
-
- // Otherwise, we inject the element directly into the jQuery object
- this.length = 1;
- this[0] = elem;
- }
-
- this.context = document;
- this.selector = selector;
- return this;
- }
-
- // HANDLE: $("TAG")
- } else if ( !context && !rnonword.test( selector ) ) {
- this.selector = selector;
- this.context = document;
- selector = document.getElementsByTagName( selector );
- return jQuery.merge( this, selector );
-
- // HANDLE: $(expr, $(...))
- } else if ( !context || context.jquery ) {
- return (context || rootjQuery).find( selector );
-
- // HANDLE: $(expr, context)
- // (which is just equivalent to: $(context).find(expr)
- } else {
- return jQuery( context ).find( selector );
- }
-
- // HANDLE: $(function)
- // Shortcut for document ready
- } else if ( jQuery.isFunction( selector ) ) {
- return rootjQuery.ready( selector );
- }
-
- if (selector.selector !== undefined) {
- this.selector = selector.selector;
- this.context = selector.context;
- }
-
- return jQuery.makeArray( selector, this );
- },
-
- // Start with an empty selector
- selector: "",
-
- // The current version of jQuery being used
- jquery: "1.4.4",
-
- // The default length of a jQuery object is 0
- length: 0,
-
- // The number of elements contained in the matched element set
- size: function() {
- return this.length;
- },
-
- toArray: function() {
- return slice.call( this, 0 );
- },
-
- // Get the Nth element in the matched element set OR
- // Get the whole matched element set as a clean array
- get: function( num ) {
- return num == null ?
-
- // Return a 'clean' array
- this.toArray() :
-
- // Return just the object
- ( num < 0 ? this.slice(num)[ 0 ] : this[ num ] );
- },
-
- // Take an array of elements and push it onto the stack
- // (returning the new matched element set)
- pushStack: function( elems, name, selector ) {
- // Build a new jQuery matched element set
- var ret = jQuery();
-
- if ( jQuery.isArray( elems ) ) {
- push.apply( ret, elems );
-
- } else {
- jQuery.merge( ret, elems );
- }
-
- // Add the old object onto the stack (as a reference)
- ret.prevObject = this;
-
- ret.context = this.context;
-
- if ( name === "find" ) {
- ret.selector = this.selector + (this.selector ? " " : "") + selector;
- } else if ( name ) {
- ret.selector = this.selector + "." + name + "(" + selector + ")";
- }
-
- // Return the newly-formed element set
- return ret;
- },
-
- // Execute a callback for every element in the matched set.
- // (You can seed the arguments with an array of args, but this is
- // only used internally.)
- each: function( callback, args ) {
- return jQuery.each( this, callback, args );
- },
-
- ready: function( fn ) {
- // Attach the listeners
- jQuery.bindReady();
-
- // If the DOM is already ready
- if ( jQuery.isReady ) {
- // Execute the function immediately
- fn.call( document, jQuery );
-
- // Otherwise, remember the function for later
- } else if ( readyList ) {
- // Add the function to the wait list
- readyList.push( fn );
- }
-
- return this;
- },
-
- eq: function( i ) {
- return i === -1 ?
- this.slice( i ) :
- this.slice( i, +i + 1 );
- },
-
- first: function() {
- return this.eq( 0 );
- },
-
- last: function() {
- return this.eq( -1 );
- },
-
- slice: function() {
- return this.pushStack( slice.apply( this, arguments ),
- "slice", slice.call(arguments).join(",") );
- },
-
- map: function( callback ) {
- return this.pushStack( jQuery.map(this, function( elem, i ) {
- return callback.call( elem, i, elem );
- }));
- },
-
- end: function() {
- return this.prevObject || jQuery(null);
- },
-
- // For internal use only.
- // Behaves like an Array's method, not like a jQuery method.
- push: push,
- sort: [].sort,
- splice: [].splice
-};
-
-// Give the init function the jQuery prototype for later instantiation
-jQuery.fn.init.prototype = jQuery.fn;
-
-jQuery.extend = jQuery.fn.extend = function() {
- var options, name, src, copy, copyIsArray, clone,
- target = arguments[0] || {},
- i = 1,
- length = arguments.length,
- deep = false;
-
- // Handle a deep copy situation
- if ( typeof target === "boolean" ) {
- deep = target;
- target = arguments[1] || {};
- // skip the boolean and the target
- i = 2;
- }
-
- // Handle case when target is a string or something (possible in deep copy)
- if ( typeof target !== "object" && !jQuery.isFunction(target) ) {
- target = {};
- }
-
- // extend jQuery itself if only one argument is passed
- if ( length === i ) {
- target = this;
- --i;
- }
-
- for ( ; i < length; i++ ) {
- // Only deal with non-null/undefined values
- if ( (options = arguments[ i ]) != null ) {
- // Extend the base object
- for ( name in options ) {
- src = target[ name ];
- copy = options[ name ];
-
- // Prevent never-ending loop
- if ( target === copy ) {
- continue;
- }
-
- // Recurse if we're merging plain objects or arrays
- if ( deep && copy && ( jQuery.isPlainObject(copy) || (copyIsArray = jQuery.isArray(copy)) ) ) {
- if ( copyIsArray ) {
- copyIsArray = false;
- clone = src && jQuery.isArray(src) ? src : [];
-
- } else {
- clone = src && jQuery.isPlainObject(src) ? src : {};
- }
-
- // Never move original objects, clone them
- target[ name ] = jQuery.extend( deep, clone, copy );
-
- // Don't bring in undefined values
- } else if ( copy !== undefined ) {
- target[ name ] = copy;
- }
- }
- }
- }
-
- // Return the modified object
- return target;
-};
-
-jQuery.extend({
- noConflict: function( deep ) {
- window.$ = _$;
-
- if ( deep ) {
- window.jQuery = _jQuery;
- }
-
- return jQuery;
- },
-
- // Is the DOM ready to be used? Set to true once it occurs.
- isReady: false,
-
- // A counter to track how many items to wait for before
- // the ready event fires. See #6781
- readyWait: 1,
-
- // Handle when the DOM is ready
- ready: function( wait ) {
- // A third-party is pushing the ready event forwards
- if ( wait === true ) {
- jQuery.readyWait--;
- }
-
- // Make sure that the DOM is not already loaded
- if ( !jQuery.readyWait || (wait !== true && !jQuery.isReady) ) {
- // Make sure body exists, at least, in case IE gets a little overzealous (ticket #5443).
- if ( !document.body ) {
- return setTimeout( jQuery.ready, 1 );
- }
-
- // Remember that the DOM is ready
- jQuery.isReady = true;
-
- // If a normal DOM Ready event fired, decrement, and wait if need be
- if ( wait !== true && --jQuery.readyWait > 0 ) {
- return;
- }
-
- // If there are functions bound, to execute
- if ( readyList ) {
- // Execute all of them
- var fn,
- i = 0,
- ready = readyList;
-
- // Reset the list of functions
- readyList = null;
-
- while ( (fn = ready[ i++ ]) ) {
- fn.call( document, jQuery );
- }
-
- // Trigger any bound ready events
- if ( jQuery.fn.trigger ) {
- jQuery( document ).trigger( "ready" ).unbind( "ready" );
- }
- }
- }
- },
-
- bindReady: function() {
- if ( readyBound ) {
- return;
- }
-
- readyBound = true;
-
- // Catch cases where $(document).ready() is called after the
- // browser event has already occurred.
- if ( document.readyState === "complete" ) {
- // Handle it asynchronously to allow scripts the opportunity to delay ready
- return setTimeout( jQuery.ready, 1 );
- }
-
- // Mozilla, Opera and webkit nightlies currently support this event
- if ( document.addEventListener ) {
- // Use the handy event callback
- document.addEventListener( "DOMContentLoaded", DOMContentLoaded, false );
-
- // A fallback to window.onload, that will always work
- window.addEventListener( "load", jQuery.ready, false );
-
- // If IE event model is used
- } else if ( document.attachEvent ) {
- // ensure firing before onload,
- // maybe late but safe also for iframes
- document.attachEvent("onreadystatechange", DOMContentLoaded);
-
- // A fallback to window.onload, that will always work
- window.attachEvent( "onload", jQuery.ready );
-
- // If IE and not a frame
- // continually check to see if the document is ready
- var toplevel = false;
-
- try {
- toplevel = window.frameElement == null;
- } catch(e) {}
-
- if ( document.documentElement.doScroll && toplevel ) {
- doScrollCheck();
- }
- }
- },
-
- // See test/unit/core.js for details concerning isFunction.
- // Since version 1.3, DOM methods and functions like alert
- // aren't supported. They return false on IE (#2968).
- isFunction: function( obj ) {
- return jQuery.type(obj) === "function";
- },
-
- isArray: Array.isArray || function( obj ) {
- return jQuery.type(obj) === "array";
- },
-
- // A crude way of determining if an object is a window
- isWindow: function( obj ) {
- return obj && typeof obj === "object" && "setInterval" in obj;
- },
-
- isNaN: function( obj ) {
- return obj == null || !rdigit.test( obj ) || isNaN( obj );
- },
-
- type: function( obj ) {
- return obj == null ?
- String( obj ) :
- class2type[ toString.call(obj) ] || "object";
- },
-
- isPlainObject: function( obj ) {
- // Must be an Object.
- // Because of IE, we also have to check the presence of the constructor property.
- // Make sure that DOM nodes and window objects don't pass through, as well
- if ( !obj || jQuery.type(obj) !== "object" || obj.nodeType || jQuery.isWindow( obj ) ) {
- return false;
- }
-
- // Not own constructor property must be Object
- if ( obj.constructor &&
- !hasOwn.call(obj, "constructor") &&
- !hasOwn.call(obj.constructor.prototype, "isPrototypeOf") ) {
- return false;
- }
-
- // Own properties are enumerated firstly, so to speed up,
- // if last one is own, then all properties are own.
-
- var key;
- for ( key in obj ) {}
-
- return key === undefined || hasOwn.call( obj, key );
- },
-
- isEmptyObject: function( obj ) {
- for ( var name in obj ) {
- return false;
- }
- return true;
- },
-
- error: function( msg ) {
- throw msg;
- },
-
- parseJSON: function( data ) {
- if ( typeof data !== "string" || !data ) {
- return null;
- }
-
- // Make sure leading/trailing whitespace is removed (IE can't handle it)
- data = jQuery.trim( data );
-
- // Make sure the incoming data is actual JSON
- // Logic borrowed from http://json.org/json2.js
- if ( rvalidchars.test(data.replace(rvalidescape, "@")
- .replace(rvalidtokens, "]")
- .replace(rvalidbraces, "")) ) {
-
- // Try to use the native JSON parser first
- return window.JSON && window.JSON.parse ?
- window.JSON.parse( data ) :
- (new Function("return " + data))();
-
- } else {
- jQuery.error( "Invalid JSON: " + data );
- }
- },
-
- noop: function() {},
-
- // Evalulates a script in a global context
- globalEval: function( data ) {
- if ( data && rnotwhite.test(data) ) {
- // Inspired by code by Andrea Giammarchi
- // http://webreflection.blogspot.com/2007/08/global-scope-evaluation-and-dom.html
- var head = document.getElementsByTagName("head")[0] || document.documentElement,
- script = document.createElement("script");
-
- script.type = "text/javascript";
-
- if ( jQuery.support.scriptEval ) {
- script.appendChild( document.createTextNode( data ) );
- } else {
- script.text = data;
- }
-
- // Use insertBefore instead of appendChild to circumvent an IE6 bug.
- // This arises when a base node is used (#2709).
- head.insertBefore( script, head.firstChild );
- head.removeChild( script );
- }
- },
-
- nodeName: function( elem, name ) {
- return elem.nodeName && elem.nodeName.toUpperCase() === name.toUpperCase();
- },
-
- // args is for internal usage only
- each: function( object, callback, args ) {
- var name, i = 0,
- length = object.length,
- isObj = length === undefined || jQuery.isFunction(object);
-
- if ( args ) {
- if ( isObj ) {
- for ( name in object ) {
- if ( callback.apply( object[ name ], args ) === false ) {
- break;
- }
- }
- } else {
- for ( ; i < length; ) {
- if ( callback.apply( object[ i++ ], args ) === false ) {
- break;
- }
- }
- }
-
- // A special, fast, case for the most common use of each
- } else {
- if ( isObj ) {
- for ( name in object ) {
- if ( callback.call( object[ name ], name, object[ name ] ) === false ) {
- break;
- }
- }
- } else {
- for ( var value = object[0];
- i < length && callback.call( value, i, value ) !== false; value = object[++i] ) {}
- }
- }
-
- return object;
- },
-
- // Use native String.trim function wherever possible
- trim: trim ?
- function( text ) {
- return text == null ?
- "" :
- trim.call( text );
- } :
-
- // Otherwise use our own trimming functionality
- function( text ) {
- return text == null ?
- "" :
- text.toString().replace( trimLeft, "" ).replace( trimRight, "" );
- },
-
- // results is for internal usage only
- makeArray: function( array, results ) {
- var ret = results || [];
-
- if ( array != null ) {
- // The window, strings (and functions) also have 'length'
- // The extra typeof function check is to prevent crashes
- // in Safari 2 (See: #3039)
- // Tweaked logic slightly to handle Blackberry 4.7 RegExp issues #6930
- var type = jQuery.type(array);
-
- if ( array.length == null || type === "string" || type === "function" || type === "regexp" || jQuery.isWindow( array ) ) {
- push.call( ret, array );
- } else {
- jQuery.merge( ret, array );
- }
- }
-
- return ret;
- },
-
- inArray: function( elem, array ) {
- if ( array.indexOf ) {
- return array.indexOf( elem );
- }
-
- for ( var i = 0, length = array.length; i < length; i++ ) {
- if ( array[ i ] === elem ) {
- return i;
- }
- }
-
- return -1;
- },
-
- merge: function( first, second ) {
- var i = first.length,
- j = 0;
-
- if ( typeof second.length === "number" ) {
- for ( var l = second.length; j < l; j++ ) {
- first[ i++ ] = second[ j ];
- }
-
- } else {
- while ( second[j] !== undefined ) {
- first[ i++ ] = second[ j++ ];
- }
- }
-
- first.length = i;
-
- return first;
- },
-
- grep: function( elems, callback, inv ) {
- var ret = [], retVal;
- inv = !!inv;
-
- // Go through the array, only saving the items
- // that pass the validator function
- for ( var i = 0, length = elems.length; i < length; i++ ) {
- retVal = !!callback( elems[ i ], i );
- if ( inv !== retVal ) {
- ret.push( elems[ i ] );
- }
- }
-
- return ret;
- },
-
- // arg is for internal usage only
- map: function( elems, callback, arg ) {
- var ret = [], value;
-
- // Go through the array, translating each of the items to their
- // new value (or values).
- for ( var i = 0, length = elems.length; i < length; i++ ) {
- value = callback( elems[ i ], i, arg );
-
- if ( value != null ) {
- ret[ ret.length ] = value;
- }
- }
-
- return ret.concat.apply( [], ret );
- },
-
- // A global GUID counter for objects
- guid: 1,
-
- proxy: function( fn, proxy, thisObject ) {
- if ( arguments.length === 2 ) {
- if ( typeof proxy === "string" ) {
- thisObject = fn;
- fn = thisObject[ proxy ];
- proxy = undefined;
-
- } else if ( proxy && !jQuery.isFunction( proxy ) ) {
- thisObject = proxy;
- proxy = undefined;
- }
- }
-
- if ( !proxy && fn ) {
- proxy = function() {
- return fn.apply( thisObject || this, arguments );
- };
- }
-
- // Set the guid of unique handler to the same of original handler, so it can be removed
- if ( fn ) {
- proxy.guid = fn.guid = fn.guid || proxy.guid || jQuery.guid++;
- }
-
- // So proxy can be declared as an argument
- return proxy;
- },
-
- // Mutifunctional method to get and set values to a collection
- // The value/s can be optionally by executed if its a function
- access: function( elems, key, value, exec, fn, pass ) {
- var length = elems.length;
-
- // Setting many attributes
- if ( typeof key === "object" ) {
- for ( var k in key ) {
- jQuery.access( elems, k, key[k], exec, fn, value );
- }
- return elems;
- }
-
- // Setting one attribute
- if ( value !== undefined ) {
- // Optionally, function values get executed if exec is true
- exec = !pass && exec && jQuery.isFunction(value);
-
- for ( var i = 0; i < length; i++ ) {
- fn( elems[i], key, exec ? value.call( elems[i], i, fn( elems[i], key ) ) : value, pass );
- }
-
- return elems;
- }
-
- // Getting an attribute
- return length ? fn( elems[0], key ) : undefined;
- },
-
- now: function() {
- return (new Date()).getTime();
- },
-
- // Use of jQuery.browser is frowned upon.
- // More details: http://docs.jquery.com/Utilities/jQuery.browser
- uaMatch: function( ua ) {
- ua = ua.toLowerCase();
-
- var match = rwebkit.exec( ua ) ||
- ropera.exec( ua ) ||
- rmsie.exec( ua ) ||
- ua.indexOf("compatible") < 0 && rmozilla.exec( ua ) ||
- [];
-
- return { browser: match[1] || "", version: match[2] || "0" };
- },
-
- browser: {}
-});
-
-// Populate the class2type map
-jQuery.each("Boolean Number String Function Array Date RegExp Object".split(" "), function(i, name) {
- class2type[ "[object " + name + "]" ] = name.toLowerCase();
-});
-
-browserMatch = jQuery.uaMatch( userAgent );
-if ( browserMatch.browser ) {
- jQuery.browser[ browserMatch.browser ] = true;
- jQuery.browser.version = browserMatch.version;
-}
-
-// Deprecated, use jQuery.browser.webkit instead
-if ( jQuery.browser.webkit ) {
- jQuery.browser.safari = true;
-}
-
-if ( indexOf ) {
- jQuery.inArray = function( elem, array ) {
- return indexOf.call( array, elem );
- };
-}
-
-// Verify that \s matches non-breaking spaces
-// (IE fails on this test)
-if ( !rwhite.test( "\xA0" ) ) {
- trimLeft = /^[\s\xA0]+/;
- trimRight = /[\s\xA0]+$/;
-}
-
-// All jQuery objects should point back to these
-rootjQuery = jQuery(document);
-
-// Cleanup functions for the document ready method
-if ( document.addEventListener ) {
- DOMContentLoaded = function() {
- document.removeEventListener( "DOMContentLoaded", DOMContentLoaded, false );
- jQuery.ready();
- };
-
-} else if ( document.attachEvent ) {
- DOMContentLoaded = function() {
- // Make sure body exists, at least, in case IE gets a little overzealous (ticket #5443).
- if ( document.readyState === "complete" ) {
- document.detachEvent( "onreadystatechange", DOMContentLoaded );
- jQuery.ready();
- }
- };
-}
-
-// The DOM ready check for Internet Explorer
-function doScrollCheck() {
- if ( jQuery.isReady ) {
- return;
- }
-
- try {
- // If IE is used, use the trick by Diego Perini
- // http://javascript.nwbox.com/IEContentLoaded/
- document.documentElement.doScroll("left");
- } catch(e) {
- setTimeout( doScrollCheck, 1 );
- return;
- }
-
- // and execute any waiting functions
- jQuery.ready();
-}
-
-// Expose jQuery to the global object
-return (window.jQuery = window.$ = jQuery);
-
-})();
-
-
-(function() {
-
- jQuery.support = {};
-
- var root = document.documentElement,
- script = document.createElement("script"),
- div = document.createElement("div"),
- id = "script" + jQuery.now();
-
- div.style.display = "none";
- div.innerHTML = " <link/><table></table><a href='/a' style='color:red;float:left;opacity:.55;'>a</a><input type='checkbox'/>";
-
- var all = div.getElementsByTagName("*"),
- a = div.getElementsByTagName("a")[0],
- select = document.createElement("select"),
- opt = select.appendChild( document.createElement("option") );
-
- // Can't get basic test support
- if ( !all || !all.length || !a ) {
- return;
- }
-
- jQuery.support = {
- // IE strips leading whitespace when .innerHTML is used
- leadingWhitespace: div.firstChild.nodeType === 3,
-
- // Make sure that tbody elements aren't automatically inserted
- // IE will insert them into empty tables
- tbody: !div.getElementsByTagName("tbody").length,
-
- // Make sure that link elements get serialized correctly by innerHTML
- // This requires a wrapper element in IE
- htmlSerialize: !!div.getElementsByTagName("link").length,
-
- // Get the style information from getAttribute
- // (IE uses .cssText insted)
- style: /red/.test( a.getAttribute("style") ),
-
- // Make sure that URLs aren't manipulated
- // (IE normalizes it by default)
- hrefNormalized: a.getAttribute("href") === "/a",
-
- // Make sure that element opacity exists
- // (IE uses filter instead)
- // Use a regex to work around a WebKit issue. See #5145
- opacity: /^0.55$/.test( a.style.opacity ),
-
- // Verify style float existence
- // (IE uses styleFloat instead of cssFloat)
- cssFloat: !!a.style.cssFloat,
-
- // Make sure that if no value is specified for a checkbox
- // that it defaults to "on".
- // (WebKit defaults to "" instead)
- checkOn: div.getElementsByTagName("input")[0].value === "on",
-
- // Make sure that a selected-by-default option has a working selected property.
- // (WebKit defaults to false instead of true, IE too, if it's in an optgroup)
- optSelected: opt.selected,
-
- // Will be defined later
- deleteExpando: true,
- optDisabled: false,
- checkClone: false,
- scriptEval: false,
- noCloneEvent: true,
- boxModel: null,
- inlineBlockNeedsLayout: false,
- shrinkWrapBlocks: false,
- reliableHiddenOffsets: true
- };
-
- // Make sure that the options inside disabled selects aren't marked as disabled
- // (WebKit marks them as diabled)
- select.disabled = true;
- jQuery.support.optDisabled = !opt.disabled;
-
- script.type = "text/javascript";
- try {
- script.appendChild( document.createTextNode( "window." + id + "=1;" ) );
- } catch(e) {}
-
- root.insertBefore( script, root.firstChild );
-
- // Make sure that the execution of code works by injecting a script
- // tag with appendChild/createTextNode
- // (IE doesn't support this, fails, and uses .text instead)
- if ( window[ id ] ) {
- jQuery.support.scriptEval = true;
- delete window[ id ];
- }
-
- // Test to see if it's possible to delete an expando from an element
- // Fails in Internet Explorer
- try {
- delete script.test;
-
- } catch(e) {
- jQuery.support.deleteExpando = false;
- }
-
- root.removeChild( script );
-
- if ( div.attachEvent && div.fireEvent ) {
- div.attachEvent("onclick", function click() {
- // Cloning a node shouldn't copy over any
- // bound event handlers (IE does this)
- jQuery.support.noCloneEvent = false;
- div.detachEvent("onclick", click);
- });
- div.cloneNode(true).fireEvent("onclick");
- }
-
- div = document.createElement("div");
- div.innerHTML = "<input type='radio' name='radiotest' checked='checked'/>";
-
- var fragment = document.createDocumentFragment();
- fragment.appendChild( div.firstChild );
-
- // WebKit doesn't clone checked state correctly in fragments
- jQuery.support.checkClone = fragment.cloneNode(true).cloneNode(true).lastChild.checked;
-
- // Figure out if the W3C box model works as expected
- // document.body must exist before we can do this
- jQuery(function() {
- var div = document.createElement("div");
- div.style.width = div.style.paddingLeft = "1px";
-
- document.body.appendChild( div );
- jQuery.boxModel = jQuery.support.boxModel = div.offsetWidth === 2;
-
- if ( "zoom" in div.style ) {
- // Check if natively block-level elements act like inline-block
- // elements when setting their display to 'inline' and giving
- // them layout
- // (IE < 8 does this)
- div.style.display = "inline";
- div.style.zoom = 1;
- jQuery.support.inlineBlockNeedsLayout = div.offsetWidth === 2;
-
- // Check if elements with layout shrink-wrap their children
- // (IE 6 does this)
- div.style.display = "";
- div.innerHTML = "<div style='width:4px;'></div>";
- jQuery.support.shrinkWrapBlocks = div.offsetWidth !== 2;
- }
-
- div.innerHTML = "<table><tr><td style='padding:0;display:none'></td><td>t</td></tr></table>";
- var tds = div.getElementsByTagName("td");
-
- // Check if table cells still have offsetWidth/Height when they are set
- // to display:none and there are still other visible table cells in a
- // table row; if so, offsetWidth/Height are not reliable for use when
- // determining if an element has been hidden directly using
- // display:none (it is still safe to use offsets if a parent element is
- // hidden; don safety goggles and see bug #4512 for more information).
- // (only IE 8 fails this test)
- jQuery.support.reliableHiddenOffsets = tds[0].offsetHeight === 0;
-
- tds[0].style.display = "";
- tds[1].style.display = "none";
-
- // Check if empty table cells still have offsetWidth/Height
- // (IE < 8 fail this test)
- jQuery.support.reliableHiddenOffsets = jQuery.support.reliableHiddenOffsets && tds[0].offsetHeight === 0;
- div.innerHTML = "";
-
- document.body.removeChild( div ).style.display = "none";
- div = tds = null;
- });
-
- // Technique from Juriy Zaytsev
- // http://thinkweb2.com/projects/prototype/detecting-event-support-without-browser-sniffing/
- var eventSupported = function( eventName ) {
- var el = document.createElement("div");
- eventName = "on" + eventName;
-
- var isSupported = (eventName in el);
- if ( !isSupported ) {
- el.setAttribute(eventName, "return;");
- isSupported = typeof el[eventName] === "function";
- }
- el = null;
-
- return isSupported;
- };
-
- jQuery.support.submitBubbles = eventSupported("submit");
- jQuery.support.changeBubbles = eventSupported("change");
-
- // release memory in IE
- root = script = div = all = a = null;
-})();
-
-
-
-var windowData = {},
- rbrace = /^(?:\{.*\}|\[.*\])$/;
-
-jQuery.extend({
- cache: {},
-
- // Please use with caution
- uuid: 0,
-
- // Unique for each copy of jQuery on the page
- expando: "jQuery" + jQuery.now(),
-
- // The following elements throw uncatchable exceptions if you
- // attempt to add expando properties to them.
- noData: {
- "embed": true,
- // Ban all objects except for Flash (which handle expandos)
- "object": "clsid:D27CDB6E-AE6D-11cf-96B8-444553540000",
- "applet": true
- },
-
- data: function( elem, name, data ) {
- if ( !jQuery.acceptData( elem ) ) {
- return;
- }
-
- elem = elem == window ?
- windowData :
- elem;
-
- var isNode = elem.nodeType,
- id = isNode ? elem[ jQuery.expando ] : null,
- cache = jQuery.cache, thisCache;
-
- if ( isNode && !id && typeof name === "string" && data === undefined ) {
- return;
- }
-
- // Get the data from the object directly
- if ( !isNode ) {
- cache = elem;
-
- // Compute a unique ID for the element
- } else if ( !id ) {
- elem[ jQuery.expando ] = id = ++jQuery.uuid;
- }
-
- // Avoid generating a new cache unless none exists and we
- // want to manipulate it.
- if ( typeof name === "object" ) {
- if ( isNode ) {
- cache[ id ] = jQuery.extend(cache[ id ], name);
-
- } else {
- jQuery.extend( cache, name );
- }
-
- } else if ( isNode && !cache[ id ] ) {
- cache[ id ] = {};
- }
-
- thisCache = isNode ? cache[ id ] : cache;
-
- // Prevent overriding the named cache with undefined values
- if ( data !== undefined ) {
- thisCache[ name ] = data;
- }
-
- return typeof name === "string" ? thisCache[ name ] : thisCache;
- },
-
- removeData: function( elem, name ) {
- if ( !jQuery.acceptData( elem ) ) {
- return;
- }
-
- elem = elem == window ?
- windowData :
- elem;
-
- var isNode = elem.nodeType,
- id = isNode ? elem[ jQuery.expando ] : elem,
- cache = jQuery.cache,
- thisCache = isNode ? cache[ id ] : id;
-
- // If we want to remove a specific section of the element's data
- if ( name ) {
- if ( thisCache ) {
- // Remove the section of cache data
- delete thisCache[ name ];
-
- // If we've removed all the data, remove the element's cache
- if ( isNode && jQuery.isEmptyObject(thisCache) ) {
- jQuery.removeData( elem );
- }
- }
-
- // Otherwise, we want to remove all of the element's data
- } else {
- if ( isNode && jQuery.support.deleteExpando ) {
- delete elem[ jQuery.expando ];
-
- } else if ( elem.removeAttribute ) {
- elem.removeAttribute( jQuery.expando );
-
- // Completely remove the data cache
- } else if ( isNode ) {
- delete cache[ id ];
-
- // Remove all fields from the object
- } else {
- for ( var n in elem ) {
- delete elem[ n ];
- }
- }
- }
- },
-
- // A method for determining if a DOM node can handle the data expando
- acceptData: function( elem ) {
- if ( elem.nodeName ) {
- var match = jQuery.noData[ elem.nodeName.toLowerCase() ];
-
- if ( match ) {
- return !(match === true || elem.getAttribute("classid") !== match);
- }
- }
-
- return true;
- }
-});
-
-jQuery.fn.extend({
- data: function( key, value ) {
- var data = null;
-
- if ( typeof key === "undefined" ) {
- if ( this.length ) {
- var attr = this[0].attributes, name;
- data = jQuery.data( this[0] );
-
- for ( var i = 0, l = attr.length; i < l; i++ ) {
- name = attr[i].name;
-
- if ( name.indexOf( "data-" ) === 0 ) {
- name = name.substr( 5 );
- dataAttr( this[0], name, data[ name ] );
- }
- }
- }
-
- return data;
-
- } else if ( typeof key === "object" ) {
- return this.each(function() {
- jQuery.data( this, key );
- });
- }
-
- var parts = key.split(".");
- parts[1] = parts[1] ? "." + parts[1] : "";
-
- if ( value === undefined ) {
- data = this.triggerHandler("getData" + parts[1] + "!", [parts[0]]);
-
- // Try to fetch any internally stored data first
- if ( data === undefined && this.length ) {
- data = jQuery.data( this[0], key );
- data = dataAttr( this[0], key, data );
- }
-
- return data === undefined && parts[1] ?
- this.data( parts[0] ) :
- data;
-
- } else {
- return this.each(function() {
- var $this = jQuery( this ),
- args = [ parts[0], value ];
-
- $this.triggerHandler( "setData" + parts[1] + "!", args );
- jQuery.data( this, key, value );
- $this.triggerHandler( "changeData" + parts[1] + "!", args );
- });
- }
- },
-
- removeData: function( key ) {
- return this.each(function() {
- jQuery.removeData( this, key );
- });
- }
-});
-
-function dataAttr( elem, key, data ) {
- // If nothing was found internally, try to fetch any
- // data from the HTML5 data-* attribute
- if ( data === undefined && elem.nodeType === 1 ) {
- data = elem.getAttribute( "data-" + key );
-
- if ( typeof data === "string" ) {
- try {
- data = data === "true" ? true :
- data === "false" ? false :
- data === "null" ? null :
- !jQuery.isNaN( data ) ? parseFloat( data ) :
- rbrace.test( data ) ? jQuery.parseJSON( data ) :
- data;
- } catch( e ) {}
-
- // Make sure we set the data so it isn't changed later
- jQuery.data( elem, key, data );
-
- } else {
- data = undefined;
- }
- }
-
- return data;
-}
-
-
-
-
-jQuery.extend({
- queue: function( elem, type, data ) {
- if ( !elem ) {
- return;
- }
-
- type = (type || "fx") + "queue";
- var q = jQuery.data( elem, type );
-
- // Speed up dequeue by getting out quickly if this is just a lookup
- if ( !data ) {
- return q || [];
- }
-
- if ( !q || jQuery.isArray(data) ) {
- q = jQuery.data( elem, type, jQuery.makeArray(data) );
-
- } else {
- q.push( data );
- }
-
- return q;
- },
-
- dequeue: function( elem, type ) {
- type = type || "fx";
-
- var queue = jQuery.queue( elem, type ),
- fn = queue.shift();
-
- // If the fx queue is dequeued, always remove the progress sentinel
- if ( fn === "inprogress" ) {
- fn = queue.shift();
- }
-
- if ( fn ) {
- // Add a progress sentinel to prevent the fx queue from being
- // automatically dequeued
- if ( type === "fx" ) {
- queue.unshift("inprogress");
- }
-
- fn.call(elem, function() {
- jQuery.dequeue(elem, type);
- });
- }
- }
-});
-
-jQuery.fn.extend({
- queue: function( type, data ) {
- if ( typeof type !== "string" ) {
- data = type;
- type = "fx";
- }
-
- if ( data === undefined ) {
- return jQuery.queue( this[0], type );
- }
- return this.each(function( i ) {
- var queue = jQuery.queue( this, type, data );
-
- if ( type === "fx" && queue[0] !== "inprogress" ) {
- jQuery.dequeue( this, type );
- }
- });
- },
- dequeue: function( type ) {
- return this.each(function() {
- jQuery.dequeue( this, type );
- });
- },
-
- // Based off of the plugin by Clint Helfers, with permission.
- // http://blindsignals.com/index.php/2009/07/jquery-delay/
- delay: function( time, type ) {
- time = jQuery.fx ? jQuery.fx.speeds[time] || time : time;
- type = type || "fx";
-
- return this.queue( type, function() {
- var elem = this;
- setTimeout(function() {
- jQuery.dequeue( elem, type );
- }, time );
- });
- },
-
- clearQueue: function( type ) {
- return this.queue( type || "fx", [] );
- }
-});
-
-
-
-
-var rclass = /[\n\t]/g,
- rspaces = /\s+/,
- rreturn = /\r/g,
- rspecialurl = /^(?:href|src|style)$/,
- rtype = /^(?:button|input)$/i,
- rfocusable = /^(?:button|input|object|select|textarea)$/i,
- rclickable = /^a(?:rea)?$/i,
- rradiocheck = /^(?:radio|checkbox)$/i;
-
-jQuery.props = {
- "for": "htmlFor",
- "class": "className",
- readonly: "readOnly",
- maxlength: "maxLength",
- cellspacing: "cellSpacing",
- rowspan: "rowSpan",
- colspan: "colSpan",
- tabindex: "tabIndex",
- usemap: "useMap",
- frameborder: "frameBorder"
-};
-
-jQuery.fn.extend({
- attr: function( name, value ) {
- return jQuery.access( this, name, value, true, jQuery.attr );
- },
-
- removeAttr: function( name, fn ) {
- return this.each(function(){
- jQuery.attr( this, name, "" );
- if ( this.nodeType === 1 ) {
- this.removeAttribute( name );
- }
- });
- },
-
- addClass: function( value ) {
- if ( jQuery.isFunction(value) ) {
- return this.each(function(i) {
- var self = jQuery(this);
- self.addClass( value.call(this, i, self.attr("class")) );
- });
- }
-
- if ( value && typeof value === "string" ) {
- var classNames = (value || "").split( rspaces );
-
- for ( var i = 0, l = this.length; i < l; i++ ) {
- var elem = this[i];
-
- if ( elem.nodeType === 1 ) {
- if ( !elem.className ) {
- elem.className = value;
-
- } else {
- var className = " " + elem.className + " ",
- setClass = elem.className;
-
- for ( var c = 0, cl = classNames.length; c < cl; c++ ) {
- if ( className.indexOf( " " + classNames[c] + " " ) < 0 ) {
- setClass += " " + classNames[c];
- }
- }
- elem.className = jQuery.trim( setClass );
- }
- }
- }
- }
-
- return this;
- },
-
- removeClass: function( value ) {
- if ( jQuery.isFunction(value) ) {
- return this.each(function(i) {
- var self = jQuery(this);
- self.removeClass( value.call(this, i, self.attr("class")) );
- });
- }
-
- if ( (value && typeof value === "string") || value === undefined ) {
- var classNames = (value || "").split( rspaces );
-
- for ( var i = 0, l = this.length; i < l; i++ ) {
- var elem = this[i];
-
- if ( elem.nodeType === 1 && elem.className ) {
- if ( value ) {
- var className = (" " + elem.className + " ").replace(rclass, " ");
- for ( var c = 0, cl = classNames.length; c < cl; c++ ) {
- className = className.replace(" " + classNames[c] + " ", " ");
- }
- elem.className = jQuery.trim( className );
-
- } else {
- elem.className = "";
- }
- }
- }
- }
-
- return this;
- },
-
- toggleClass: function( value, stateVal ) {
- var type = typeof value,
- isBool = typeof stateVal === "boolean";
-
- if ( jQuery.isFunction( value ) ) {
- return this.each(function(i) {
- var self = jQuery(this);
- self.toggleClass( value.call(this, i, self.attr("class"), stateVal), stateVal );
- });
- }
-
- return this.each(function() {
- if ( type === "string" ) {
- // toggle individual class names
- var className,
- i = 0,
- self = jQuery( this ),
- state = stateVal,
- classNames = value.split( rspaces );
-
- while ( (className = classNames[ i++ ]) ) {
- // check each className given, space seperated list
- state = isBool ? state : !self.hasClass( className );
- self[ state ? "addClass" : "removeClass" ]( className );
- }
-
- } else if ( type === "undefined" || type === "boolean" ) {
- if ( this.className ) {
- // store className if set
- jQuery.data( this, "__className__", this.className );
- }
-
- // toggle whole className
- this.className = this.className || value === false ? "" : jQuery.data( this, "__className__" ) || "";
- }
- });
- },
-
- hasClass: function( selector ) {
- var className = " " + selector + " ";
- for ( var i = 0, l = this.length; i < l; i++ ) {
- if ( (" " + this[i].className + " ").replace(rclass, " ").indexOf( className ) > -1 ) {
- return true;
- }
- }
-
- return false;
- },
-
- val: function( value ) {
- if ( !arguments.length ) {
- var elem = this[0];
-
- if ( elem ) {
- if ( jQuery.nodeName( elem, "option" ) ) {
- // attributes.value is undefined in Blackberry 4.7 but
- // uses .value. See #6932
- var val = elem.attributes.value;
- return !val || val.specified ? elem.value : elem.text;
- }
-
- // We need to handle select boxes special
- if ( jQuery.nodeName( elem, "select" ) ) {
- var index = elem.selectedIndex,
- values = [],
- options = elem.options,
- one = elem.type === "select-one";
-
- // Nothing was selected
- if ( index < 0 ) {
- return null;
- }
-
- // Loop through all the selected options
- for ( var i = one ? index : 0, max = one ? index + 1 : options.length; i < max; i++ ) {
- var option = options[ i ];
-
- // Don't return options that are disabled or in a disabled optgroup
- if ( option.selected && (jQuery.support.optDisabled ? !option.disabled : option.getAttribute("disabled") === null) &&
- (!option.parentNode.disabled || !jQuery.nodeName( option.parentNode, "optgroup" )) ) {
-
- // Get the specific value for the option
- value = jQuery(option).val();
-
- // We don't need an array for one selects
- if ( one ) {
- return value;
- }
-
- // Multi-Selects return an array
- values.push( value );
- }
- }
-
- return values;
- }
-
- // Handle the case where in Webkit "" is returned instead of "on" if a value isn't specified
- if ( rradiocheck.test( elem.type ) && !jQuery.support.checkOn ) {
- return elem.getAttribute("value") === null ? "on" : elem.value;
- }
-
-
- // Everything else, we just grab the value
- return (elem.value || "").replace(rreturn, "");
-
- }
-
- return undefined;
- }
-
- var isFunction = jQuery.isFunction(value);
-
- return this.each(function(i) {
- var self = jQuery(this), val = value;
-
- if ( this.nodeType !== 1 ) {
- return;
- }
-
- if ( isFunction ) {
- val = value.call(this, i, self.val());
- }
-
- // Treat null/undefined as ""; convert numbers to string
- if ( val == null ) {
- val = "";
- } else if ( typeof val === "number" ) {
- val += "";
- } else if ( jQuery.isArray(val) ) {
- val = jQuery.map(val, function (value) {
- return value == null ? "" : value + "";
- });
- }
-
- if ( jQuery.isArray(val) && rradiocheck.test( this.type ) ) {
- this.checked = jQuery.inArray( self.val(), val ) >= 0;
-
- } else if ( jQuery.nodeName( this, "select" ) ) {
- var values = jQuery.makeArray(val);
-
- jQuery( "option", this ).each(function() {
- this.selected = jQuery.inArray( jQuery(this).val(), values ) >= 0;
- });
-
- if ( !values.length ) {
- this.selectedIndex = -1;
- }
-
- } else {
- this.value = val;
- }
- });
- }
-});
-
-jQuery.extend({
- attrFn: {
- val: true,
- css: true,
- html: true,
- text: true,
- data: true,
- width: true,
- height: true,
- offset: true
- },
-
- attr: function( elem, name, value, pass ) {
- // don't set attributes on text and comment nodes
- if ( !elem || elem.nodeType === 3 || elem.nodeType === 8 ) {
- return undefined;
- }
-
- if ( pass && name in jQuery.attrFn ) {
- return jQuery(elem)[name](value);
- }
-
- var notxml = elem.nodeType !== 1 || !jQuery.isXMLDoc( elem ),
- // Whether we are setting (or getting)
- set = value !== undefined;
-
- // Try to normalize/fix the name
- name = notxml && jQuery.props[ name ] || name;
-
- // These attributes require special treatment
- var special = rspecialurl.test( name );
-
- // Safari mis-reports the default selected property of an option
- // Accessing the parent's selectedIndex property fixes it
- if ( name === "selected" && !jQuery.support.optSelected ) {
- var parent = elem.parentNode;
- if ( parent ) {
- parent.selectedIndex;
-
- // Make sure that it also works with optgroups, see #5701
- if ( parent.parentNode ) {
- parent.parentNode.selectedIndex;
- }
- }
- }
-
- // If applicable, access the attribute via the DOM 0 way
- // 'in' checks fail in Blackberry 4.7 #6931
- if ( (name in elem || elem[ name ] !== undefined) && notxml && !special ) {
- if ( set ) {
- // We can't allow the type property to be changed (since it causes problems in IE)
- if ( name === "type" && rtype.test( elem.nodeName ) && elem.parentNode ) {
- jQuery.error( "type property can't be changed" );
- }
-
- if ( value === null ) {
- if ( elem.nodeType === 1 ) {
- elem.removeAttribute( name );
- }
-
- } else {
- elem[ name ] = value;
- }
- }
-
- // browsers index elements by id/name on forms, give priority to attributes.
- if ( jQuery.nodeName( elem, "form" ) && elem.getAttributeNode(name) ) {
- return elem.getAttributeNode( name ).nodeValue;
- }
-
- // elem.tabIndex doesn't always return the correct value when it hasn't been explicitly set
- // http://fluidproject.org/blog/2008/01/09/getting-setting-and-removing-tabindex-values-with-javascript/
- if ( name === "tabIndex" ) {
- var attributeNode = elem.getAttributeNode( "tabIndex" );
-
- return attributeNode && attributeNode.specified ?
- attributeNode.value :
- rfocusable.test( elem.nodeName ) || rclickable.test( elem.nodeName ) && elem.href ?
- 0 :
- undefined;
- }
-
- return elem[ name ];
- }
-
- if ( !jQuery.support.style && notxml && name === "style" ) {
- if ( set ) {
- elem.style.cssText = "" + value;
- }
-
- return elem.style.cssText;
- }
-
- if ( set ) {
- // convert the value to a string (all browsers do this but IE) see #1070
- elem.setAttribute( name, "" + value );
- }
-
- // Ensure that missing attributes return undefined
- // Blackberry 4.7 returns "" from getAttribute #6938
- if ( !elem.attributes[ name ] && (elem.hasAttribute && !elem.hasAttribute( name )) ) {
- return undefined;
- }
-
- var attr = !jQuery.support.hrefNormalized && notxml && special ?
- // Some attributes require a special call on IE
- elem.getAttribute( name, 2 ) :
- elem.getAttribute( name );
-
- // Non-existent attributes return null, we normalize to undefined
- return attr === null ? undefined : attr;
- }
-});
-
-
-
-
-var rnamespaces = /\.(.*)$/,
- rformElems = /^(?:textarea|input|select)$/i,
- rperiod = /\./g,
- rspace = / /g,
- rescape = /[^\w\s.|`]/g,
- fcleanup = function( nm ) {
- return nm.replace(rescape, "\\$&");
- },
- focusCounts = { focusin: 0, focusout: 0 };
-
-/*
- * A number of helper functions used for managing events.
- * Many of the ideas behind this code originated from
- * Dean Edwards' addEvent library.
- */
-jQuery.event = {
-
- // Bind an event to an element
- // Original by Dean Edwards
- add: function( elem, types, handler, data ) {
- if ( elem.nodeType === 3 || elem.nodeType === 8 ) {
- return;
- }
-
- // For whatever reason, IE has trouble passing the window object
- // around, causing it to be cloned in the process
- if ( jQuery.isWindow( elem ) && ( elem !== window && !elem.frameElement ) ) {
- elem = window;
- }
-
- if ( handler === false ) {
- handler = returnFalse;
- } else if ( !handler ) {
- // Fixes bug #7229. Fix recommended by jdalton
- return;
- }
-
- var handleObjIn, handleObj;
-
- if ( handler.handler ) {
- handleObjIn = handler;
- handler = handleObjIn.handler;
- }
-
- // Make sure that the function being executed has a unique ID
- if ( !handler.guid ) {
- handler.guid = jQuery.guid++;
- }
-
- // Init the element's event structure
- var elemData = jQuery.data( elem );
-
- // If no elemData is found then we must be trying to bind to one of the
- // banned noData elements
- if ( !elemData ) {
- return;
- }
-
- // Use a key less likely to result in collisions for plain JS objects.
- // Fixes bug #7150.
- var eventKey = elem.nodeType ? "events" : "__events__",
- events = elemData[ eventKey ],
- eventHandle = elemData.handle;
-
- if ( typeof events === "function" ) {
- // On plain objects events is a fn that holds the the data
- // which prevents this data from being JSON serialized
- // the function does not need to be called, it just contains the data
- eventHandle = events.handle;
- events = events.events;
-
- } else if ( !events ) {
- if ( !elem.nodeType ) {
- // On plain objects, create a fn that acts as the holder
- // of the values to avoid JSON serialization of event data
- elemData[ eventKey ] = elemData = function(){};
- }
-
- elemData.events = events = {};
- }
-
- if ( !eventHandle ) {
- elemData.handle = eventHandle = function() {
- // Handle the second event of a trigger and when
- // an event is called after a page has unloaded
- return typeof jQuery !== "undefined" && !jQuery.event.triggered ?
- jQuery.event.handle.apply( eventHandle.elem, arguments ) :
- undefined;
- };
- }
-
- // Add elem as a property of the handle function
- // This is to prevent a memory leak with non-native events in IE.
- eventHandle.elem = elem;
-
- // Handle multiple events separated by a space
- // jQuery(...).bind("mouseover mouseout", fn);
- types = types.split(" ");
-
- var type, i = 0, namespaces;
-
- while ( (type = types[ i++ ]) ) {
- handleObj = handleObjIn ?
- jQuery.extend({}, handleObjIn) :
- { handler: handler, data: data };
-
- // Namespaced event handlers
- if ( type.indexOf(".") > -1 ) {
- namespaces = type.split(".");
- type = namespaces.shift();
- handleObj.namespace = namespaces.slice(0).sort().join(".");
-
- } else {
- namespaces = [];
- handleObj.namespace = "";
- }
-
- handleObj.type = type;
- if ( !handleObj.guid ) {
- handleObj.guid = handler.guid;
- }
-
- // Get the current list of functions bound to this event
- var handlers = events[ type ],
- special = jQuery.event.special[ type ] || {};
-
- // Init the event handler queue
- if ( !handlers ) {
- handlers = events[ type ] = [];
-
- // Check for a special event handler
- // Only use addEventListener/attachEvent if the special
- // events handler returns false
- if ( !special.setup || special.setup.call( elem, data, namespaces, eventHandle ) === false ) {
- // Bind the global event handler to the element
- if ( elem.addEventListener ) {
- elem.addEventListener( type, eventHandle, false );
-
- } else if ( elem.attachEvent ) {
- elem.attachEvent( "on" + type, eventHandle );
- }
- }
- }
-
- if ( special.add ) {
- special.add.call( elem, handleObj );
-
- if ( !handleObj.handler.guid ) {
- handleObj.handler.guid = handler.guid;
- }
- }
-
- // Add the function to the element's handler list
- handlers.push( handleObj );
-
- // Keep track of which events have been used, for global triggering
- jQuery.event.global[ type ] = true;
- }
-
- // Nullify elem to prevent memory leaks in IE
- elem = null;
- },
-
- global: {},
-
- // Detach an event or set of events from an element
- remove: function( elem, types, handler, pos ) {
- // don't do events on text and comment nodes
- if ( elem.nodeType === 3 || elem.nodeType === 8 ) {
- return;
- }
-
- if ( handler === false ) {
- handler = returnFalse;
- }
-
- var ret, type, fn, j, i = 0, all, namespaces, namespace, special, eventType, handleObj, origType,
- eventKey = elem.nodeType ? "events" : "__events__",
- elemData = jQuery.data( elem ),
- events = elemData && elemData[ eventKey ];
-
- if ( !elemData || !events ) {
- return;
- }
-
- if ( typeof events === "function" ) {
- elemData = events;
- events = events.events;
- }
-
- // types is actually an event object here
- if ( types && types.type ) {
- handler = types.handler;
- types = types.type;
- }
-
- // Unbind all events for the element
- if ( !types || typeof types === "string" && types.charAt(0) === "." ) {
- types = types || "";
-
- for ( type in events ) {
- jQuery.event.remove( elem, type + types );
- }
-
- return;
- }
-
- // Handle multiple events separated by a space
- // jQuery(...).unbind("mouseover mouseout", fn);
- types = types.split(" ");
-
- while ( (type = types[ i++ ]) ) {
- origType = type;
- handleObj = null;
- all = type.indexOf(".") < 0;
- namespaces = [];
-
- if ( !all ) {
- // Namespaced event handlers
- namespaces = type.split(".");
- type = namespaces.shift();
-
- namespace = new RegExp("(^|\\.)" +
- jQuery.map( namespaces.slice(0).sort(), fcleanup ).join("\\.(?:.*\\.)?") + "(\\.|$)");
- }
-
- eventType = events[ type ];
-
- if ( !eventType ) {
- continue;
- }
-
- if ( !handler ) {
- for ( j = 0; j < eventType.length; j++ ) {
- handleObj = eventType[ j ];
-
- if ( all || namespace.test( handleObj.namespace ) ) {
- jQuery.event.remove( elem, origType, handleObj.handler, j );
- eventType.splice( j--, 1 );
- }
- }
-
- continue;
- }
-
- special = jQuery.event.special[ type ] || {};
-
- for ( j = pos || 0; j < eventType.length; j++ ) {
- handleObj = eventType[ j ];
-
- if ( handler.guid === handleObj.guid ) {
- // remove the given handler for the given type
- if ( all || namespace.test( handleObj.namespace ) ) {
- if ( pos == null ) {
- eventType.splice( j--, 1 );
- }
-
- if ( special.remove ) {
- special.remove.call( elem, handleObj );
- }
- }
-
- if ( pos != null ) {
- break;
- }
- }
- }
-
- // remove generic event handler if no more handlers exist
- if ( eventType.length === 0 || pos != null && eventType.length === 1 ) {
- if ( !special.teardown || special.teardown.call( elem, namespaces ) === false ) {
- jQuery.removeEvent( elem, type, elemData.handle );
- }
-
- ret = null;
- delete events[ type ];
- }
- }
-
- // Remove the expando if it's no longer used
- if ( jQuery.isEmptyObject( events ) ) {
- var handle = elemData.handle;
- if ( handle ) {
- handle.elem = null;
- }
-
- delete elemData.events;
- delete elemData.handle;
-
- if ( typeof elemData === "function" ) {
- jQuery.removeData( elem, eventKey );
-
- } else if ( jQuery.isEmptyObject( elemData ) ) {
- jQuery.removeData( elem );
- }
- }
- },
-
- // bubbling is internal
- trigger: function( event, data, elem /*, bubbling */ ) {
- // Event object or event type
- var type = event.type || event,
- bubbling = arguments[3];
-
- if ( !bubbling ) {
- event = typeof event === "object" ?
- // jQuery.Event object
- event[ jQuery.expando ] ? event :
- // Object literal
- jQuery.extend( jQuery.Event(type), event ) :
- // Just the event type (string)
- jQuery.Event(type);
-
- if ( type.indexOf("!") >= 0 ) {
- event.type = type = type.slice(0, -1);
- event.exclusive = true;
- }
-
- // Handle a global trigger
- if ( !elem ) {
- // Don't bubble custom events when global (to avoid too much overhead)
- event.stopPropagation();
-
- // Only trigger if we've ever bound an event for it
- if ( jQuery.event.global[ type ] ) {
- jQuery.each( jQuery.cache, function() {
- if ( this.events && this.events[type] ) {
- jQuery.event.trigger( event, data, this.handle.elem );
- }
- });
- }
- }
-
- // Handle triggering a single element
-
- // don't do events on text and comment nodes
- if ( !elem || elem.nodeType === 3 || elem.nodeType === 8 ) {
- return undefined;
- }
-
- // Clean up in case it is reused
- event.result = undefined;
- event.target = elem;
-
- // Clone the incoming data, if any
- data = jQuery.makeArray( data );
- data.unshift( event );
- }
-
- event.currentTarget = elem;
-
- // Trigger the event, it is assumed that "handle" is a function
- var handle = elem.nodeType ?
- jQuery.data( elem, "handle" ) :
- (jQuery.data( elem, "__events__" ) || {}).handle;
-
- if ( handle ) {
- handle.apply( elem, data );
- }
-
- var parent = elem.parentNode || elem.ownerDocument;
-
- // Trigger an inline bound script
- try {
- if ( !(elem && elem.nodeName && jQuery.noData[elem.nodeName.toLowerCase()]) ) {
- if ( elem[ "on" + type ] && elem[ "on" + type ].apply( elem, data ) === false ) {
- event.result = false;
- event.preventDefault();
- }
- }
-
- // prevent IE from throwing an error for some elements with some event types, see #3533
- } catch (inlineError) {}
-
- if ( !event.isPropagationStopped() && parent ) {
- jQuery.event.trigger( event, data, parent, true );
-
- } else if ( !event.isDefaultPrevented() ) {
- var old,
- target = event.target,
- targetType = type.replace( rnamespaces, "" ),
- isClick = jQuery.nodeName( target, "a" ) && targetType === "click",
- special = jQuery.event.special[ targetType ] || {};
-
- if ( (!special._default || special._default.call( elem, event ) === false) &&
- !isClick && !(target && target.nodeName && jQuery.noData[target.nodeName.toLowerCase()]) ) {
-
- try {
- if ( target[ targetType ] ) {
- // Make sure that we don't accidentally re-trigger the onFOO events
- old = target[ "on" + targetType ];
-
- if ( old ) {
- target[ "on" + targetType ] = null;
- }
-
- jQuery.event.triggered = true;
- target[ targetType ]();
- }
-
- // prevent IE from throwing an error for some elements with some event types, see #3533
- } catch (triggerError) {}
-
- if ( old ) {
- target[ "on" + targetType ] = old;
- }
-
- jQuery.event.triggered = false;
- }
- }
- },
-
- handle: function( event ) {
- var all, handlers, namespaces, namespace_re, events,
- namespace_sort = [],
- args = jQuery.makeArray( arguments );
-
- event = args[0] = jQuery.event.fix( event || window.event );
- event.currentTarget = this;
-
- // Namespaced event handlers
- all = event.type.indexOf(".") < 0 && !event.exclusive;
-
- if ( !all ) {
- namespaces = event.type.split(".");
- event.type = namespaces.shift();
- namespace_sort = namespaces.slice(0).sort();
- namespace_re = new RegExp("(^|\\.)" + namespace_sort.join("\\.(?:.*\\.)?") + "(\\.|$)");
- }
-
- event.namespace = event.namespace || namespace_sort.join(".");
-
- events = jQuery.data(this, this.nodeType ? "events" : "__events__");
-
- if ( typeof events === "function" ) {
- events = events.events;
- }
-
- handlers = (events || {})[ event.type ];
-
- if ( events && handlers ) {
- // Clone the handlers to prevent manipulation
- handlers = handlers.slice(0);
-
- for ( var j = 0, l = handlers.length; j < l; j++ ) {
- var handleObj = handlers[ j ];
-
- // Filter the functions by class
- if ( all || namespace_re.test( handleObj.namespace ) ) {
- // Pass in a reference to the handler function itself
- // So that we can later remove it
- event.handler = handleObj.handler;
- event.data = handleObj.data;
- event.handleObj = handleObj;
-
- var ret = handleObj.handler.apply( this, args );
-
- if ( ret !== undefined ) {
- event.result = ret;
- if ( ret === false ) {
- event.preventDefault();
- event.stopPropagation();
- }
- }
-
- if ( event.isImmediatePropagationStopped() ) {
- break;
- }
- }
- }
- }
-
- return event.result;
- },
-
- props: "altKey attrChange attrName bubbles button cancelable charCode clientX clientY ctrlKey currentTarget data detail eventPhase fromElement handler keyCode layerX layerY metaKey newValue offsetX offsetY pageX pageY prevValue relatedNode relatedTarget screenX screenY shiftKey srcElement target toElement view wheelDelta which".split(" "),
-
- fix: function( event ) {
- if ( event[ jQuery.expando ] ) {
- return event;
- }
-
- // store a copy of the original event object
- // and "clone" to set read-only properties
- var originalEvent = event;
- event = jQuery.Event( originalEvent );
-
- for ( var i = this.props.length, prop; i; ) {
- prop = this.props[ --i ];
- event[ prop ] = originalEvent[ prop ];
- }
-
- // Fix target property, if necessary
- if ( !event.target ) {
- // Fixes #1925 where srcElement might not be defined either
- event.target = event.srcElement || document;
- }
-
- // check if target is a textnode (safari)
- if ( event.target.nodeType === 3 ) {
- event.target = event.target.parentNode;
- }
-
- // Add relatedTarget, if necessary
- if ( !event.relatedTarget && event.fromElement ) {
- event.relatedTarget = event.fromElement === event.target ? event.toElement : event.fromElement;
- }
-
- // Calculate pageX/Y if missing and clientX/Y available
- if ( event.pageX == null && event.clientX != null ) {
- var doc = document.documentElement,
- body = document.body;
-
- event.pageX = event.clientX + (doc && doc.scrollLeft || body && body.scrollLeft || 0) - (doc && doc.clientLeft || body && body.clientLeft || 0);
- event.pageY = event.clientY + (doc && doc.scrollTop || body && body.scrollTop || 0) - (doc && doc.clientTop || body && body.clientTop || 0);
- }
-
- // Add which for key events
- if ( event.which == null && (event.charCode != null || event.keyCode != null) ) {
- event.which = event.charCode != null ? event.charCode : event.keyCode;
- }
-
- // Add metaKey to non-Mac browsers (use ctrl for PC's and Meta for Macs)
- if ( !event.metaKey && event.ctrlKey ) {
- event.metaKey = event.ctrlKey;
- }
-
- // Add which for click: 1 === left; 2 === middle; 3 === right
- // Note: button is not normalized, so don't use it
- if ( !event.which && event.button !== undefined ) {
- event.which = (event.button & 1 ? 1 : ( event.button & 2 ? 3 : ( event.button & 4 ? 2 : 0 ) ));
- }
-
- return event;
- },
-
- // Deprecated, use jQuery.guid instead
- guid: 1E8,
-
- // Deprecated, use jQuery.proxy instead
- proxy: jQuery.proxy,
-
- special: {
- ready: {
- // Make sure the ready event is setup
- setup: jQuery.bindReady,
- teardown: jQuery.noop
- },
-
- live: {
- add: function( handleObj ) {
- jQuery.event.add( this,
- liveConvert( handleObj.origType, handleObj.selector ),
- jQuery.extend({}, handleObj, {handler: liveHandler, guid: handleObj.handler.guid}) );
- },
-
- remove: function( handleObj ) {
- jQuery.event.remove( this, liveConvert( handleObj.origType, handleObj.selector ), handleObj );
- }
- },
-
- beforeunload: {
- setup: function( data, namespaces, eventHandle ) {
- // We only want to do this special case on windows
- if ( jQuery.isWindow( this ) ) {
- this.onbeforeunload = eventHandle;
- }
- },
-
- teardown: function( namespaces, eventHandle ) {
- if ( this.onbeforeunload === eventHandle ) {
- this.onbeforeunload = null;
- }
- }
- }
- }
-};
-
-jQuery.removeEvent = document.removeEventListener ?
- function( elem, type, handle ) {
- if ( elem.removeEventListener ) {
- elem.removeEventListener( type, handle, false );
- }
- } :
- function( elem, type, handle ) {
- if ( elem.detachEvent ) {
- elem.detachEvent( "on" + type, handle );
- }
- };
-
-jQuery.Event = function( src ) {
- // Allow instantiation without the 'new' keyword
- if ( !this.preventDefault ) {
- return new jQuery.Event( src );
- }
-
- // Event object
- if ( src && src.type ) {
- this.originalEvent = src;
- this.type = src.type;
- // Event type
- } else {
- this.type = src;
- }
-
- // timeStamp is buggy for some events on Firefox(#3843)
- // So we won't rely on the native value
- this.timeStamp = jQuery.now();
-
- // Mark it as fixed
- this[ jQuery.expando ] = true;
-};
-
-function returnFalse() {
- return false;
-}
-function returnTrue() {
- return true;
-}
-
-// jQuery.Event is based on DOM3 Events as specified by the ECMAScript Language Binding
-// http://www.w3.org/TR/2003/WD-DOM-Level-3-Events-20030331/ecma-script-binding.html
-jQuery.Event.prototype = {
- preventDefault: function() {
- this.isDefaultPrevented = returnTrue;
-
- var e = this.originalEvent;
- if ( !e ) {
- return;
- }
-
- // if preventDefault exists run it on the original event
- if ( e.preventDefault ) {
- e.preventDefault();
-
- // otherwise set the returnValue property of the original event to false (IE)
- } else {
- e.returnValue = false;
- }
- },
- stopPropagation: function() {
- this.isPropagationStopped = returnTrue;
-
- var e = this.originalEvent;
- if ( !e ) {
- return;
- }
- // if stopPropagation exists run it on the original event
- if ( e.stopPropagation ) {
- e.stopPropagation();
- }
- // otherwise set the cancelBubble property of the original event to true (IE)
- e.cancelBubble = true;
- },
- stopImmediatePropagation: function() {
- this.isImmediatePropagationStopped = returnTrue;
- this.stopPropagation();
- },
- isDefaultPrevented: returnFalse,
- isPropagationStopped: returnFalse,
- isImmediatePropagationStopped: returnFalse
-};
-
-// Checks if an event happened on an element within another element
-// Used in jQuery.event.special.mouseenter and mouseleave handlers
-var withinElement = function( event ) {
- // Check if mouse(over|out) are still within the same parent element
- var parent = event.relatedTarget;
-
- // Firefox sometimes assigns relatedTarget a XUL element
- // which we cannot access the parentNode property of
- try {
- // Traverse up the tree
- while ( parent && parent !== this ) {
- parent = parent.parentNode;
- }
-
- if ( parent !== this ) {
- // set the correct event type
- event.type = event.data;
-
- // handle event if we actually just moused on to a non sub-element
- jQuery.event.handle.apply( this, arguments );
- }
-
- // assuming we've left the element since we most likely mousedover a xul element
- } catch(e) { }
-},
-
-// In case of event delegation, we only need to rename the event.type,
-// liveHandler will take care of the rest.
-delegate = function( event ) {
- event.type = event.data;
- jQuery.event.handle.apply( this, arguments );
-};
-
-// Create mouseenter and mouseleave events
-jQuery.each({
- mouseenter: "mouseover",
- mouseleave: "mouseout"
-}, function( orig, fix ) {
- jQuery.event.special[ orig ] = {
- setup: function( data ) {
- jQuery.event.add( this, fix, data && data.selector ? delegate : withinElement, orig );
- },
- teardown: function( data ) {
- jQuery.event.remove( this, fix, data && data.selector ? delegate : withinElement );
- }
- };
-});
-
-// submit delegation
-if ( !jQuery.support.submitBubbles ) {
-
- jQuery.event.special.submit = {
- setup: function( data, namespaces ) {
- if ( this.nodeName.toLowerCase() !== "form" ) {
- jQuery.event.add(this, "click.specialSubmit", function( e ) {
- var elem = e.target,
- type = elem.type;
-
- if ( (type === "submit" || type === "image") && jQuery( elem ).closest("form").length ) {
- e.liveFired = undefined;
- return trigger( "submit", this, arguments );
- }
- });
-
- jQuery.event.add(this, "keypress.specialSubmit", function( e ) {
- var elem = e.target,
- type = elem.type;
-
- if ( (type === "text" || type === "password") && jQuery( elem ).closest("form").length && e.keyCode === 13 ) {
- e.liveFired = undefined;
- return trigger( "submit", this, arguments );
- }
- });
-
- } else {
- return false;
- }
- },
-
- teardown: function( namespaces ) {
- jQuery.event.remove( this, ".specialSubmit" );
- }
- };
-
-}
-
-// change delegation, happens here so we have bind.
-if ( !jQuery.support.changeBubbles ) {
-
- var changeFilters,
-
- getVal = function( elem ) {
- var type = elem.type, val = elem.value;
-
- if ( type === "radio" || type === "checkbox" ) {
- val = elem.checked;
-
- } else if ( type === "select-multiple" ) {
- val = elem.selectedIndex > -1 ?
- jQuery.map( elem.options, function( elem ) {
- return elem.selected;
- }).join("-") :
- "";
-
- } else if ( elem.nodeName.toLowerCase() === "select" ) {
- val = elem.selectedIndex;
- }
-
- return val;
- },
-
- testChange = function testChange( e ) {
- var elem = e.target, data, val;
-
- if ( !rformElems.test( elem.nodeName ) || elem.readOnly ) {
- return;
- }
-
- data = jQuery.data( elem, "_change_data" );
- val = getVal(elem);
-
- // the current data will be also retrieved by beforeactivate
- if ( e.type !== "focusout" || elem.type !== "radio" ) {
- jQuery.data( elem, "_change_data", val );
- }
-
- if ( data === undefined || val === data ) {
- return;
- }
-
- if ( data != null || val ) {
- e.type = "change";
- e.liveFired = undefined;
- return jQuery.event.trigger( e, arguments[1], elem );
- }
- };
-
- jQuery.event.special.change = {
- filters: {
- focusout: testChange,
-
- beforedeactivate: testChange,
-
- click: function( e ) {
- var elem = e.target, type = elem.type;
-
- if ( type === "radio" || type === "checkbox" || elem.nodeName.toLowerCase() === "select" ) {
- return testChange.call( this, e );
- }
- },
-
- // Change has to be called before submit
- // Keydown will be called before keypress, which is used in submit-event delegation
- keydown: function( e ) {
- var elem = e.target, type = elem.type;
-
- if ( (e.keyCode === 13 && elem.nodeName.toLowerCase() !== "textarea") ||
- (e.keyCode === 32 && (type === "checkbox" || type === "radio")) ||
- type === "select-multiple" ) {
- return testChange.call( this, e );
- }
- },
-
- // Beforeactivate happens also before the previous element is blurred
- // with this event you can't trigger a change event, but you can store
- // information
- beforeactivate: function( e ) {
- var elem = e.target;
- jQuery.data( elem, "_change_data", getVal(elem) );
- }
- },
-
- setup: function( data, namespaces ) {
- if ( this.type === "file" ) {
- return false;
- }
-
- for ( var type in changeFilters ) {
- jQuery.event.add( this, type + ".specialChange", changeFilters[type] );
- }
-
- return rformElems.test( this.nodeName );
- },
-
- teardown: function( namespaces ) {
- jQuery.event.remove( this, ".specialChange" );
-
- return rformElems.test( this.nodeName );
- }
- };
-
- changeFilters = jQuery.event.special.change.filters;
-
- // Handle when the input is .focus()'d
- changeFilters.focus = changeFilters.beforeactivate;
-}
-
-function trigger( type, elem, args ) {
- args[0].type = type;
- return jQuery.event.handle.apply( elem, args );
-}
-
-// Create "bubbling" focus and blur events
-if ( document.addEventListener ) {
- jQuery.each({ focus: "focusin", blur: "focusout" }, function( orig, fix ) {
- jQuery.event.special[ fix ] = {
- setup: function() {
- if ( focusCounts[fix]++ === 0 ) {
- document.addEventListener( orig, handler, true );
- }
- },
- teardown: function() {
- if ( --focusCounts[fix] === 0 ) {
- document.removeEventListener( orig, handler, true );
- }
- }
- };
-
- function handler( e ) {
- e = jQuery.event.fix( e );
- e.type = fix;
- return jQuery.event.trigger( e, null, e.target );
- }
- });
-}
-
-jQuery.each(["bind", "one"], function( i, name ) {
- jQuery.fn[ name ] = function( type, data, fn ) {
- // Handle object literals
- if ( typeof type === "object" ) {
- for ( var key in type ) {
- this[ name ](key, data, type[key], fn);
- }
- return this;
- }
-
- if ( jQuery.isFunction( data ) || data === false ) {
- fn = data;
- data = undefined;
- }
-
- var handler = name === "one" ? jQuery.proxy( fn, function( event ) {
- jQuery( this ).unbind( event, handler );
- return fn.apply( this, arguments );
- }) : fn;
-
- if ( type === "unload" && name !== "one" ) {
- this.one( type, data, fn );
-
- } else {
- for ( var i = 0, l = this.length; i < l; i++ ) {
- jQuery.event.add( this[i], type, handler, data );
- }
- }
-
- return this;
- };
-});
-
-jQuery.fn.extend({
- unbind: function( type, fn ) {
- // Handle object literals
- if ( typeof type === "object" && !type.preventDefault ) {
- for ( var key in type ) {
- this.unbind(key, type[key]);
- }
-
- } else {
- for ( var i = 0, l = this.length; i < l; i++ ) {
- jQuery.event.remove( this[i], type, fn );
- }
- }
-
- return this;
- },
-
- delegate: function( selector, types, data, fn ) {
- return this.live( types, data, fn, selector );
- },
-
- undelegate: function( selector, types, fn ) {
- if ( arguments.length === 0 ) {
- return this.unbind( "live" );
-
- } else {
- return this.die( types, null, fn, selector );
- }
- },
-
- trigger: function( type, data ) {
- return this.each(function() {
- jQuery.event.trigger( type, data, this );
- });
- },
-
- triggerHandler: function( type, data ) {
- if ( this[0] ) {
- var event = jQuery.Event( type );
- event.preventDefault();
- event.stopPropagation();
- jQuery.event.trigger( event, data, this[0] );
- return event.result;
- }
- },
-
- toggle: function( fn ) {
- // Save reference to arguments for access in closure
- var args = arguments,
- i = 1;
-
- // link all the functions, so any of them can unbind this click handler
- while ( i < args.length ) {
- jQuery.proxy( fn, args[ i++ ] );
- }
-
- return this.click( jQuery.proxy( fn, function( event ) {
- // Figure out which function to execute
- var lastToggle = ( jQuery.data( this, "lastToggle" + fn.guid ) || 0 ) % i;
- jQuery.data( this, "lastToggle" + fn.guid, lastToggle + 1 );
-
- // Make sure that clicks stop
- event.preventDefault();
-
- // and execute the function
- return args[ lastToggle ].apply( this, arguments ) || false;
- }));
- },
-
- hover: function( fnOver, fnOut ) {
- return this.mouseenter( fnOver ).mouseleave( fnOut || fnOver );
- }
-});
-
-var liveMap = {
- focus: "focusin",
- blur: "focusout",
- mouseenter: "mouseover",
- mouseleave: "mouseout"
-};
-
-jQuery.each(["live", "die"], function( i, name ) {
- jQuery.fn[ name ] = function( types, data, fn, origSelector /* Internal Use Only */ ) {
- var type, i = 0, match, namespaces, preType,
- selector = origSelector || this.selector,
- context = origSelector ? this : jQuery( this.context );
-
- if ( typeof types === "object" && !types.preventDefault ) {
- for ( var key in types ) {
- context[ name ]( key, data, types[key], selector );
- }
-
- return this;
- }
-
- if ( jQuery.isFunction( data ) ) {
- fn = data;
- data = undefined;
- }
-
- types = (types || "").split(" ");
-
- while ( (type = types[ i++ ]) != null ) {
- match = rnamespaces.exec( type );
- namespaces = "";
-
- if ( match ) {
- namespaces = match[0];
- type = type.replace( rnamespaces, "" );
- }
-
- if ( type === "hover" ) {
- types.push( "mouseenter" + namespaces, "mouseleave" + namespaces );
- continue;
- }
-
- preType = type;
-
- if ( type === "focus" || type === "blur" ) {
- types.push( liveMap[ type ] + namespaces );
- type = type + namespaces;
-
- } else {
- type = (liveMap[ type ] || type) + namespaces;
- }
-
- if ( name === "live" ) {
- // bind live handler
- for ( var j = 0, l = context.length; j < l; j++ ) {
- jQuery.event.add( context[j], "live." + liveConvert( type, selector ),
- { data: data, selector: selector, handler: fn, origType: type, origHandler: fn, preType: preType } );
- }
-
- } else {
- // unbind live handler
- context.unbind( "live." + liveConvert( type, selector ), fn );
- }
- }
-
- return this;
- };
-});
-
-function liveHandler( event ) {
- var stop, maxLevel, related, match, handleObj, elem, j, i, l, data, close, namespace, ret,
- elems = [],
- selectors = [],
- events = jQuery.data( this, this.nodeType ? "events" : "__events__" );
-
- if ( typeof events === "function" ) {
- events = events.events;
- }
-
- // Make sure we avoid non-left-click bubbling in Firefox (#3861)
- if ( event.liveFired === this || !events || !events.live || event.button && event.type === "click" ) {
- return;
- }
-
- if ( event.namespace ) {
- namespace = new RegExp("(^|\\.)" + event.namespace.split(".").join("\\.(?:.*\\.)?") + "(\\.|$)");
- }
-
- event.liveFired = this;
-
- var live = events.live.slice(0);
-
- for ( j = 0; j < live.length; j++ ) {
- handleObj = live[j];
-
- if ( handleObj.origType.replace( rnamespaces, "" ) === event.type ) {
- selectors.push( handleObj.selector );
-
- } else {
- live.splice( j--, 1 );
- }
- }
-
- match = jQuery( event.target ).closest( selectors, event.currentTarget );
-
- for ( i = 0, l = match.length; i < l; i++ ) {
- close = match[i];
-
- for ( j = 0; j < live.length; j++ ) {
- handleObj = live[j];
-
- if ( close.selector === handleObj.selector && (!namespace || namespace.test( handleObj.namespace )) ) {
- elem = close.elem;
- related = null;
-
- // Those two events require additional checking
- if ( handleObj.preType === "mouseenter" || handleObj.preType === "mouseleave" ) {
- event.type = handleObj.preType;
- related = jQuery( event.relatedTarget ).closest( handleObj.selector )[0];
- }
-
- if ( !related || related !== elem ) {
- elems.push({ elem: elem, handleObj: handleObj, level: close.level });
- }
- }
- }
- }
-
- for ( i = 0, l = elems.length; i < l; i++ ) {
- match = elems[i];
-
- if ( maxLevel && match.level > maxLevel ) {
- break;
- }
-
- event.currentTarget = match.elem;
- event.data = match.handleObj.data;
- event.handleObj = match.handleObj;
-
- ret = match.handleObj.origHandler.apply( match.elem, arguments );
-
- if ( ret === false || event.isPropagationStopped() ) {
- maxLevel = match.level;
-
- if ( ret === false ) {
- stop = false;
- }
- if ( event.isImmediatePropagationStopped() ) {
- break;
- }
- }
- }
-
- return stop;
-}
-
-function liveConvert( type, selector ) {
- return (type && type !== "*" ? type + "." : "") + selector.replace(rperiod, "`").replace(rspace, "&");
-}
-
-jQuery.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").split(" "), function( i, name ) {
-
- // Handle event binding
- jQuery.fn[ name ] = function( data, fn ) {
- if ( fn == null ) {
- fn = data;
- data = null;
- }
-
- return arguments.length > 0 ?
- this.bind( name, data, fn ) :
- this.trigger( name );
- };
-
- if ( jQuery.attrFn ) {
- jQuery.attrFn[ name ] = true;
- }
-});
-
-// Prevent memory leaks in IE
-// Window isn't included so as not to unbind existing unload events
-// More info:
-// - http://isaacschlueter.com/2006/10/msie-memory-leaks/
-if ( window.attachEvent && !window.addEventListener ) {
- jQuery(window).bind("unload", function() {
- for ( var id in jQuery.cache ) {
- if ( jQuery.cache[ id ].handle ) {
- // Try/Catch is to handle iframes being unloaded, see #4280
- try {
- jQuery.event.remove( jQuery.cache[ id ].handle.elem );
- } catch(e) {}
- }
- }
- });
-}
-
-
-/*!
- * Sizzle CSS Selector Engine - v1.0
- * Copyright 2009, The Dojo Foundation
- * Released under the MIT, BSD, and GPL Licenses.
- * More information: http://sizzlejs.com/
- */
-(function(){
-
-var chunker = /((?:\((?:\([^()]+\)|[^()]+)+\)|\[(?:\[[^\[\]]*\]|['"][^'"]*['"]|[^\[\]'"]+)+\]|\\.|[^ >+~,(\[\\]+)+|[>+~])(\s*,\s*)?((?:.|\r|\n)*)/g,
- done = 0,
- toString = Object.prototype.toString,
- hasDuplicate = false,
- baseHasDuplicate = true;
-
-// Here we check if the JavaScript engine is using some sort of
-// optimization where it does not always call our comparision
-// function. If that is the case, discard the hasDuplicate value.
-// Thus far that includes Google Chrome.
-[0, 0].sort(function() {
- baseHasDuplicate = false;
- return 0;
-});
-
-var Sizzle = function( selector, context, results, seed ) {
- results = results || [];
- context = context || document;
-
- var origContext = context;
-
- if ( context.nodeType !== 1 && context.nodeType !== 9 ) {
- return [];
- }
-
- if ( !selector || typeof selector !== "string" ) {
- return results;
- }
-
- var m, set, checkSet, extra, ret, cur, pop, i,
- prune = true,
- contextXML = Sizzle.isXML( context ),
- parts = [],
- soFar = selector;
-
- // Reset the position of the chunker regexp (start from head)
- do {
- chunker.exec( "" );
- m = chunker.exec( soFar );
-
- if ( m ) {
- soFar = m[3];
-
- parts.push( m[1] );
-
- if ( m[2] ) {
- extra = m[3];
- break;
- }
- }
- } while ( m );
-
- if ( parts.length > 1 && origPOS.exec( selector ) ) {
-
- if ( parts.length === 2 && Expr.relative[ parts[0] ] ) {
- set = posProcess( parts[0] + parts[1], context );
-
- } else {
- set = Expr.relative[ parts[0] ] ?
- [ context ] :
- Sizzle( parts.shift(), context );
-
- while ( parts.length ) {
- selector = parts.shift();
-
- if ( Expr.relative[ selector ] ) {
- selector += parts.shift();
- }
-
- set = posProcess( selector, set );
- }
- }
-
- } else {
- // Take a shortcut and set the context if the root selector is an ID
- // (but not if it'll be faster if the inner selector is an ID)
- if ( !seed && parts.length > 1 && context.nodeType === 9 && !contextXML &&
- Expr.match.ID.test(parts[0]) && !Expr.match.ID.test(parts[parts.length - 1]) ) {
-
- ret = Sizzle.find( parts.shift(), context, contextXML );
- context = ret.expr ?
- Sizzle.filter( ret.expr, ret.set )[0] :
- ret.set[0];
- }
-
- if ( context ) {
- ret = seed ?
- { expr: parts.pop(), set: makeArray(seed) } :
- Sizzle.find( parts.pop(), parts.length === 1 && (parts[0] === "~" || parts[0] === "+") && context.parentNode ? context.parentNode : context, contextXML );
-
- set = ret.expr ?
- Sizzle.filter( ret.expr, ret.set ) :
- ret.set;
-
- if ( parts.length > 0 ) {
- checkSet = makeArray( set );
-
- } else {
- prune = false;
- }
-
- while ( parts.length ) {
- cur = parts.pop();
- pop = cur;
-
- if ( !Expr.relative[ cur ] ) {
- cur = "";
- } else {
- pop = parts.pop();
- }
-
- if ( pop == null ) {
- pop = context;
- }
-
- Expr.relative[ cur ]( checkSet, pop, contextXML );
- }
-
- } else {
- checkSet = parts = [];
- }
- }
-
- if ( !checkSet ) {
- checkSet = set;
- }
-
- if ( !checkSet ) {
- Sizzle.error( cur || selector );
- }
-
- if ( toString.call(checkSet) === "[object Array]" ) {
- if ( !prune ) {
- results.push.apply( results, checkSet );
-
- } else if ( context && context.nodeType === 1 ) {
- for ( i = 0; checkSet[i] != null; i++ ) {
- if ( checkSet[i] && (checkSet[i] === true || checkSet[i].nodeType === 1 && Sizzle.contains(context, checkSet[i])) ) {
- results.push( set[i] );
- }
- }
-
- } else {
- for ( i = 0; checkSet[i] != null; i++ ) {
- if ( checkSet[i] && checkSet[i].nodeType === 1 ) {
- results.push( set[i] );
- }
- }
- }
-
- } else {
- makeArray( checkSet, results );
- }
-
- if ( extra ) {
- Sizzle( extra, origContext, results, seed );
- Sizzle.uniqueSort( results );
- }
-
- return results;
-};
-
-Sizzle.uniqueSort = function( results ) {
- if ( sortOrder ) {
- hasDuplicate = baseHasDuplicate;
- results.sort( sortOrder );
-
- if ( hasDuplicate ) {
- for ( var i = 1; i < results.length; i++ ) {
- if ( results[i] === results[ i - 1 ] ) {
- results.splice( i--, 1 );
- }
- }
- }
- }
-
- return results;
-};
-
-Sizzle.matches = function( expr, set ) {
- return Sizzle( expr, null, null, set );
-};
-
-Sizzle.matchesSelector = function( node, expr ) {
- return Sizzle( expr, null, null, [node] ).length > 0;
-};
-
-Sizzle.find = function( expr, context, isXML ) {
- var set;
-
- if ( !expr ) {
- return [];
- }
-
- for ( var i = 0, l = Expr.order.length; i < l; i++ ) {
- var match,
- type = Expr.order[i];
-
- if ( (match = Expr.leftMatch[ type ].exec( expr )) ) {
- var left = match[1];
- match.splice( 1, 1 );
-
- if ( left.substr( left.length - 1 ) !== "\\" ) {
- match[1] = (match[1] || "").replace(/\\/g, "");
- set = Expr.find[ type ]( match, context, isXML );
-
- if ( set != null ) {
- expr = expr.replace( Expr.match[ type ], "" );
- break;
- }
- }
- }
- }
-
- if ( !set ) {
- set = context.getElementsByTagName( "*" );
- }
-
- return { set: set, expr: expr };
-};
-
-Sizzle.filter = function( expr, set, inplace, not ) {
- var match, anyFound,
- old = expr,
- result = [],
- curLoop = set,
- isXMLFilter = set && set[0] && Sizzle.isXML( set[0] );
-
- while ( expr && set.length ) {
- for ( var type in Expr.filter ) {
- if ( (match = Expr.leftMatch[ type ].exec( expr )) != null && match[2] ) {
- var found, item,
- filter = Expr.filter[ type ],
- left = match[1];
-
- anyFound = false;
-
- match.splice(1,1);
-
- if ( left.substr( left.length - 1 ) === "\\" ) {
- continue;
- }
-
- if ( curLoop === result ) {
- result = [];
- }
-
- if ( Expr.preFilter[ type ] ) {
- match = Expr.preFilter[ type ]( match, curLoop, inplace, result, not, isXMLFilter );
-
- if ( !match ) {
- anyFound = found = true;
-
- } else if ( match === true ) {
- continue;
- }
- }
-
- if ( match ) {
- for ( var i = 0; (item = curLoop[i]) != null; i++ ) {
- if ( item ) {
- found = filter( item, match, i, curLoop );
- var pass = not ^ !!found;
-
- if ( inplace && found != null ) {
- if ( pass ) {
- anyFound = true;
-
- } else {
- curLoop[i] = false;
- }
-
- } else if ( pass ) {
- result.push( item );
- anyFound = true;
- }
- }
- }
- }
-
- if ( found !== undefined ) {
- if ( !inplace ) {
- curLoop = result;
- }
-
- expr = expr.replace( Expr.match[ type ], "" );
-
- if ( !anyFound ) {
- return [];
- }
-
- break;
- }
- }
- }
-
- // Improper expression
- if ( expr === old ) {
- if ( anyFound == null ) {
- Sizzle.error( expr );
-
- } else {
- break;
- }
- }
-
- old = expr;
- }
-
- return curLoop;
-};
-
-Sizzle.error = function( msg ) {
- throw "Syntax error, unrecognized expression: " + msg;
-};
-
-var Expr = Sizzle.selectors = {
- order: [ "ID", "NAME", "TAG" ],
-
- match: {
- ID: /#((?:[\w\u00c0-\uFFFF\-]|\\.)+)/,
- CLASS: /\.((?:[\w\u00c0-\uFFFF\-]|\\.)+)/,
- NAME: /\[name=['"]*((?:[\w\u00c0-\uFFFF\-]|\\.)+)['"]*\]/,
- ATTR: /\[\s*((?:[\w\u00c0-\uFFFF\-]|\\.)+)\s*(?:(\S?=)\s*(['"]*)(.*?)\3|)\s*\]/,
- TAG: /^((?:[\w\u00c0-\uFFFF\*\-]|\\.)+)/,
- CHILD: /:(only|nth|last|first)-child(?:\((even|odd|[\dn+\-]*)\))?/,
- POS: /:(nth|eq|gt|lt|first|last|even|odd)(?:\((\d*)\))?(?=[^\-]|$)/,
- PSEUDO: /:((?:[\w\u00c0-\uFFFF\-]|\\.)+)(?:\((['"]?)((?:\([^\)]+\)|[^\(\)]*)+)\2\))?/
- },
-
- leftMatch: {},
-
- attrMap: {
- "class": "className",
- "for": "htmlFor"
- },
-
- attrHandle: {
- href: function( elem ) {
- return elem.getAttribute( "href" );
- }
- },
-
- relative: {
- "+": function(checkSet, part){
- var isPartStr = typeof part === "string",
- isTag = isPartStr && !/\W/.test( part ),
- isPartStrNotTag = isPartStr && !isTag;
-
- if ( isTag ) {
- part = part.toLowerCase();
- }
-
- for ( var i = 0, l = checkSet.length, elem; i < l; i++ ) {
- if ( (elem = checkSet[i]) ) {
- while ( (elem = elem.previousSibling) && elem.nodeType !== 1 ) {}
-
- checkSet[i] = isPartStrNotTag || elem && elem.nodeName.toLowerCase() === part ?
- elem || false :
- elem === part;
- }
- }
-
- if ( isPartStrNotTag ) {
- Sizzle.filter( part, checkSet, true );
- }
- },
-
- ">": function( checkSet, part ) {
- var elem,
- isPartStr = typeof part === "string",
- i = 0,
- l = checkSet.length;
-
- if ( isPartStr && !/\W/.test( part ) ) {
- part = part.toLowerCase();
-
- for ( ; i < l; i++ ) {
- elem = checkSet[i];
-
- if ( elem ) {
- var parent = elem.parentNode;
- checkSet[i] = parent.nodeName.toLowerCase() === part ? parent : false;
- }
- }
-
- } else {
- for ( ; i < l; i++ ) {
- elem = checkSet[i];
-
- if ( elem ) {
- checkSet[i] = isPartStr ?
- elem.parentNode :
- elem.parentNode === part;
- }
- }
-
- if ( isPartStr ) {
- Sizzle.filter( part, checkSet, true );
- }
- }
- },
-
- "": function(checkSet, part, isXML){
- var nodeCheck,
- doneName = done++,
- checkFn = dirCheck;
-
- if ( typeof part === "string" && !/\W/.test(part) ) {
- part = part.toLowerCase();
- nodeCheck = part;
- checkFn = dirNodeCheck;
- }
-
- checkFn( "parentNode", part, doneName, checkSet, nodeCheck, isXML );
- },
-
- "~": function( checkSet, part, isXML ) {
- var nodeCheck,
- doneName = done++,
- checkFn = dirCheck;
-
- if ( typeof part === "string" && !/\W/.test( part ) ) {
- part = part.toLowerCase();
- nodeCheck = part;
- checkFn = dirNodeCheck;
- }
-
- checkFn( "previousSibling", part, doneName, checkSet, nodeCheck, isXML );
- }
- },
-
- find: {
- ID: function( match, context, isXML ) {
- if ( typeof context.getElementById !== "undefined" && !isXML ) {
- var m = context.getElementById(match[1]);
- // Check parentNode to catch when Blackberry 4.6 returns
- // nodes that are no longer in the document #6963
- return m && m.parentNode ? [m] : [];
- }
- },
-
- NAME: function( match, context ) {
- if ( typeof context.getElementsByName !== "undefined" ) {
- var ret = [],
- results = context.getElementsByName( match[1] );
-
- for ( var i = 0, l = results.length; i < l; i++ ) {
- if ( results[i].getAttribute("name") === match[1] ) {
- ret.push( results[i] );
- }
- }
-
- return ret.length === 0 ? null : ret;
- }
- },
-
- TAG: function( match, context ) {
- return context.getElementsByTagName( match[1] );
- }
- },
- preFilter: {
- CLASS: function( match, curLoop, inplace, result, not, isXML ) {
- match = " " + match[1].replace(/\\/g, "") + " ";
-
- if ( isXML ) {
- return match;
- }
-
- for ( var i = 0, elem; (elem = curLoop[i]) != null; i++ ) {
- if ( elem ) {
- if ( not ^ (elem.className && (" " + elem.className + " ").replace(/[\t\n]/g, " ").indexOf(match) >= 0) ) {
- if ( !inplace ) {
- result.push( elem );
- }
-
- } else if ( inplace ) {
- curLoop[i] = false;
- }
- }
- }
-
- return false;
- },
-
- ID: function( match ) {
- return match[1].replace(/\\/g, "");
- },
-
- TAG: function( match, curLoop ) {
- return match[1].toLowerCase();
- },
-
- CHILD: function( match ) {
- if ( match[1] === "nth" ) {
- // parse equations like 'even', 'odd', '5', '2n', '3n+2', '4n-1', '-n+6'
- var test = /(-?)(\d*)n((?:\+|-)?\d*)/.exec(
- match[2] === "even" && "2n" || match[2] === "odd" && "2n+1" ||
- !/\D/.test( match[2] ) && "0n+" + match[2] || match[2]);
-
- // calculate the numbers (first)n+(last) including if they are negative
- match[2] = (test[1] + (test[2] || 1)) - 0;
- match[3] = test[3] - 0;
- }
-
- // TODO: Move to normal caching system
- match[0] = done++;
-
- return match;
- },
-
- ATTR: function( match, curLoop, inplace, result, not, isXML ) {
- var name = match[1].replace(/\\/g, "");
-
- if ( !isXML && Expr.attrMap[name] ) {
- match[1] = Expr.attrMap[name];
- }
-
- if ( match[2] === "~=" ) {
- match[4] = " " + match[4] + " ";
- }
-
- return match;
- },
-
- PSEUDO: function( match, curLoop, inplace, result, not ) {
- if ( match[1] === "not" ) {
- // If we're dealing with a complex expression, or a simple one
- if ( ( chunker.exec(match[3]) || "" ).length > 1 || /^\w/.test(match[3]) ) {
- match[3] = Sizzle(match[3], null, null, curLoop);
-
- } else {
- var ret = Sizzle.filter(match[3], curLoop, inplace, true ^ not);
-
- if ( !inplace ) {
- result.push.apply( result, ret );
- }
-
- return false;
- }
-
- } else if ( Expr.match.POS.test( match[0] ) || Expr.match.CHILD.test( match[0] ) ) {
- return true;
- }
-
- return match;
- },
-
- POS: function( match ) {
- match.unshift( true );
-
- return match;
- }
- },
-
- filters: {
- enabled: function( elem ) {
- return elem.disabled === false && elem.type !== "hidden";
- },
-
- disabled: function( elem ) {
- return elem.disabled === true;
- },
-
- checked: function( elem ) {
- return elem.checked === true;
- },
-
- selected: function( elem ) {
- // Accessing this property makes selected-by-default
- // options in Safari work properly
- elem.parentNode.selectedIndex;
-
- return elem.selected === true;
- },
-
- parent: function( elem ) {
- return !!elem.firstChild;
- },
-
- empty: function( elem ) {
- return !elem.firstChild;
- },
-
- has: function( elem, i, match ) {
- return !!Sizzle( match[3], elem ).length;
- },
-
- header: function( elem ) {
- return (/h\d/i).test( elem.nodeName );
- },
-
- text: function( elem ) {
- return "text" === elem.type;
- },
- radio: function( elem ) {
- return "radio" === elem.type;
- },
-
- checkbox: function( elem ) {
- return "checkbox" === elem.type;
- },
-
- file: function( elem ) {
- return "file" === elem.type;
- },
- password: function( elem ) {
- return "password" === elem.type;
- },
-
- submit: function( elem ) {
- return "submit" === elem.type;
- },
-
- image: function( elem ) {
- return "image" === elem.type;
- },
-
- reset: function( elem ) {
- return "reset" === elem.type;
- },
-
- button: function( elem ) {
- return "button" === elem.type || elem.nodeName.toLowerCase() === "button";
- },
-
- input: function( elem ) {
- return (/input|select|textarea|button/i).test( elem.nodeName );
- }
- },
- setFilters: {
- first: function( elem, i ) {
- return i === 0;
- },
-
- last: function( elem, i, match, array ) {
- return i === array.length - 1;
- },
-
- even: function( elem, i ) {
- return i % 2 === 0;
- },
-
- odd: function( elem, i ) {
- return i % 2 === 1;
- },
-
- lt: function( elem, i, match ) {
- return i < match[3] - 0;
- },
-
- gt: function( elem, i, match ) {
- return i > match[3] - 0;
- },
-
- nth: function( elem, i, match ) {
- return match[3] - 0 === i;
- },
-
- eq: function( elem, i, match ) {
- return match[3] - 0 === i;
- }
- },
- filter: {
- PSEUDO: function( elem, match, i, array ) {
- var name = match[1],
- filter = Expr.filters[ name ];
-
- if ( filter ) {
- return filter( elem, i, match, array );
-
- } else if ( name === "contains" ) {
- return (elem.textContent || elem.innerText || Sizzle.getText([ elem ]) || "").indexOf(match[3]) >= 0;
-
- } else if ( name === "not" ) {
- var not = match[3];
-
- for ( var j = 0, l = not.length; j < l; j++ ) {
- if ( not[j] === elem ) {
- return false;
- }
- }
-
- return true;
-
- } else {
- Sizzle.error( "Syntax error, unrecognized expression: " + name );
- }
- },
-
- CHILD: function( elem, match ) {
- var type = match[1],
- node = elem;
-
- switch ( type ) {
- case "only":
- case "first":
- while ( (node = node.previousSibling) ) {
- if ( node.nodeType === 1 ) {
- return false;
- }
- }
-
- if ( type === "first" ) {
- return true;
- }
-
- node = elem;
-
- case "last":
- while ( (node = node.nextSibling) ) {
- if ( node.nodeType === 1 ) {
- return false;
- }
- }
-
- return true;
-
- case "nth":
- var first = match[2],
- last = match[3];
-
- if ( first === 1 && last === 0 ) {
- return true;
- }
-
- var doneName = match[0],
- parent = elem.parentNode;
-
- if ( parent && (parent.sizcache !== doneName || !elem.nodeIndex) ) {
- var count = 0;
-
- for ( node = parent.firstChild; node; node = node.nextSibling ) {
- if ( node.nodeType === 1 ) {
- node.nodeIndex = ++count;
- }
- }
-
- parent.sizcache = doneName;
- }
-
- var diff = elem.nodeIndex - last;
-
- if ( first === 0 ) {
- return diff === 0;
-
- } else {
- return ( diff % first === 0 && diff / first >= 0 );
- }
- }
- },
-
- ID: function( elem, match ) {
- return elem.nodeType === 1 && elem.getAttribute("id") === match;
- },
-
- TAG: function( elem, match ) {
- return (match === "*" && elem.nodeType === 1) || elem.nodeName.toLowerCase() === match;
- },
-
- CLASS: function( elem, match ) {
- return (" " + (elem.className || elem.getAttribute("class")) + " ")
- .indexOf( match ) > -1;
- },
-
- ATTR: function( elem, match ) {
- var name = match[1],
- result = Expr.attrHandle[ name ] ?
- Expr.attrHandle[ name ]( elem ) :
- elem[ name ] != null ?
- elem[ name ] :
- elem.getAttribute( name ),
- value = result + "",
- type = match[2],
- check = match[4];
-
- return result == null ?
- type === "!=" :
- type === "=" ?
- value === check :
- type === "*=" ?
- value.indexOf(check) >= 0 :
- type === "~=" ?
- (" " + value + " ").indexOf(check) >= 0 :
- !check ?
- value && result !== false :
- type === "!=" ?
- value !== check :
- type === "^=" ?
- value.indexOf(check) === 0 :
- type === "$=" ?
- value.substr(value.length - check.length) === check :
- type === "|=" ?
- value === check || value.substr(0, check.length + 1) === check + "-" :
- false;
- },
-
- POS: function( elem, match, i, array ) {
- var name = match[2],
- filter = Expr.setFilters[ name ];
-
- if ( filter ) {
- return filter( elem, i, match, array );
- }
- }
- }
-};
-
-var origPOS = Expr.match.POS,
- fescape = function(all, num){
- return "\\" + (num - 0 + 1);
- };
-
-for ( var type in Expr.match ) {
- Expr.match[ type ] = new RegExp( Expr.match[ type ].source + (/(?![^\[]*\])(?![^\(]*\))/.source) );
- Expr.leftMatch[ type ] = new RegExp( /(^(?:.|\r|\n)*?)/.source + Expr.match[ type ].source.replace(/\\(\d+)/g, fescape) );
-}
-
-var makeArray = function( array, results ) {
- array = Array.prototype.slice.call( array, 0 );
-
- if ( results ) {
- results.push.apply( results, array );
- return results;
- }
-
- return array;
-};
-
-// Perform a simple check to determine if the browser is capable of
-// converting a NodeList to an array using builtin methods.
-// Also verifies that the returned array holds DOM nodes
-// (which is not the case in the Blackberry browser)
-try {
- Array.prototype.slice.call( document.documentElement.childNodes, 0 )[0].nodeType;
-
-// Provide a fallback method if it does not work
-} catch( e ) {
- makeArray = function( array, results ) {
- var i = 0,
- ret = results || [];
-
- if ( toString.call(array) === "[object Array]" ) {
- Array.prototype.push.apply( ret, array );
-
- } else {
- if ( typeof array.length === "number" ) {
- for ( var l = array.length; i < l; i++ ) {
- ret.push( array[i] );
- }
-
- } else {
- for ( ; array[i]; i++ ) {
- ret.push( array[i] );
- }
- }
- }
-
- return ret;
- };
-}
-
-var sortOrder, siblingCheck;
-
-if ( document.documentElement.compareDocumentPosition ) {
- sortOrder = function( a, b ) {
- if ( a === b ) {
- hasDuplicate = true;
- return 0;
- }
-
- if ( !a.compareDocumentPosition || !b.compareDocumentPosition ) {
- return a.compareDocumentPosition ? -1 : 1;
- }
-
- return a.compareDocumentPosition(b) & 4 ? -1 : 1;
- };
-
-} else {
- sortOrder = function( a, b ) {
- var al, bl,
- ap = [],
- bp = [],
- aup = a.parentNode,
- bup = b.parentNode,
- cur = aup;
-
- // The nodes are identical, we can exit early
- if ( a === b ) {
- hasDuplicate = true;
- return 0;
-
- // If the nodes are siblings (or identical) we can do a quick check
- } else if ( aup === bup ) {
- return siblingCheck( a, b );
-
- // If no parents were found then the nodes are disconnected
- } else if ( !aup ) {
- return -1;
-
- } else if ( !bup ) {
- return 1;
- }
-
- // Otherwise they're somewhere else in the tree so we need
- // to build up a full list of the parentNodes for comparison
- while ( cur ) {
- ap.unshift( cur );
- cur = cur.parentNode;
- }
-
- cur = bup;
-
- while ( cur ) {
- bp.unshift( cur );
- cur = cur.parentNode;
- }
-
- al = ap.length;
- bl = bp.length;
-
- // Start walking down the tree looking for a discrepancy
- for ( var i = 0; i < al && i < bl; i++ ) {
- if ( ap[i] !== bp[i] ) {
- return siblingCheck( ap[i], bp[i] );
- }
- }
-
- // We ended someplace up the tree so do a sibling check
- return i === al ?
- siblingCheck( a, bp[i], -1 ) :
- siblingCheck( ap[i], b, 1 );
- };
-
- siblingCheck = function( a, b, ret ) {
- if ( a === b ) {
- return ret;
- }
-
- var cur = a.nextSibling;
-
- while ( cur ) {
- if ( cur === b ) {
- return -1;
- }
-
- cur = cur.nextSibling;
- }
-
- return 1;
- };
-}
-
-// Utility function for retreiving the text value of an array of DOM nodes
-Sizzle.getText = function( elems ) {
- var ret = "", elem;
-
- for ( var i = 0; elems[i]; i++ ) {
- elem = elems[i];
-
- // Get the text from text nodes and CDATA nodes
- if ( elem.nodeType === 3 || elem.nodeType === 4 ) {
- ret += elem.nodeValue;
-
- // Traverse everything else, except comment nodes
- } else if ( elem.nodeType !== 8 ) {
- ret += Sizzle.getText( elem.childNodes );
- }
- }
-
- return ret;
-};
-
-// Check to see if the browser returns elements by name when
-// querying by getElementById (and provide a workaround)
-(function(){
- // We're going to inject a fake input element with a specified name
- var form = document.createElement("div"),
- id = "script" + (new Date()).getTime(),
- root = document.documentElement;
-
- form.innerHTML = "<a name='" + id + "'/>";
-
- // Inject it into the root element, check its status, and remove it quickly
- root.insertBefore( form, root.firstChild );
-
- // The workaround has to do additional checks after a getElementById
- // Which slows things down for other browsers (hence the branching)
- if ( document.getElementById( id ) ) {
- Expr.find.ID = function( match, context, isXML ) {
- if ( typeof context.getElementById !== "undefined" && !isXML ) {
- var m = context.getElementById(match[1]);
-
- return m ?
- m.id === match[1] || typeof m.getAttributeNode !== "undefined" && m.getAttributeNode("id").nodeValue === match[1] ?
- [m] :
- undefined :
- [];
- }
- };
-
- Expr.filter.ID = function( elem, match ) {
- var node = typeof elem.getAttributeNode !== "undefined" && elem.getAttributeNode("id");
-
- return elem.nodeType === 1 && node && node.nodeValue === match;
- };
- }
-
- root.removeChild( form );
-
- // release memory in IE
- root = form = null;
-})();
-
-(function(){
- // Check to see if the browser returns only elements
- // when doing getElementsByTagName("*")
-
- // Create a fake element
- var div = document.createElement("div");
- div.appendChild( document.createComment("") );
-
- // Make sure no comments are found
- if ( div.getElementsByTagName("*").length > 0 ) {
- Expr.find.TAG = function( match, context ) {
- var results = context.getElementsByTagName( match[1] );
-
- // Filter out possible comments
- if ( match[1] === "*" ) {
- var tmp = [];
-
- for ( var i = 0; results[i]; i++ ) {
- if ( results[i].nodeType === 1 ) {
- tmp.push( results[i] );
- }
- }
-
- results = tmp;
- }
-
- return results;
- };
- }
-
- // Check to see if an attribute returns normalized href attributes
- div.innerHTML = "<a href='#'></a>";
-
- if ( div.firstChild && typeof div.firstChild.getAttribute !== "undefined" &&
- div.firstChild.getAttribute("href") !== "#" ) {
-
- Expr.attrHandle.href = function( elem ) {
- return elem.getAttribute( "href", 2 );
- };
- }
-
- // release memory in IE
- div = null;
-})();
-
-if ( document.querySelectorAll ) {
- (function(){
- var oldSizzle = Sizzle,
- div = document.createElement("div"),
- id = "__sizzle__";
-
- div.innerHTML = "<p class='TEST'></p>";
-
- // Safari can't handle uppercase or unicode characters when
- // in quirks mode.
- if ( div.querySelectorAll && div.querySelectorAll(".TEST").length === 0 ) {
- return;
- }
-
- Sizzle = function( query, context, extra, seed ) {
- context = context || document;
-
- // Make sure that attribute selectors are quoted
- query = query.replace(/\=\s*([^'"\]]*)\s*\]/g, "='$1']");
-
- // Only use querySelectorAll on non-XML documents
- // (ID selectors don't work in non-HTML documents)
- if ( !seed && !Sizzle.isXML(context) ) {
- if ( context.nodeType === 9 ) {
- try {
- return makeArray( context.querySelectorAll(query), extra );
- } catch(qsaError) {}
-
- // qSA works strangely on Element-rooted queries
- // We can work around this by specifying an extra ID on the root
- // and working up from there (Thanks to Andrew Dupont for the technique)
- // IE 8 doesn't work on object elements
- } else if ( context.nodeType === 1 && context.nodeName.toLowerCase() !== "object" ) {
- var old = context.getAttribute( "id" ),
- nid = old || id;
-
- if ( !old ) {
- context.setAttribute( "id", nid );
- }
-
- try {
- return makeArray( context.querySelectorAll( "#" + nid + " " + query ), extra );
-
- } catch(pseudoError) {
- } finally {
- if ( !old ) {
- context.removeAttribute( "id" );
- }
- }
- }
- }
-
- return oldSizzle(query, context, extra, seed);
- };
-
- for ( var prop in oldSizzle ) {
- Sizzle[ prop ] = oldSizzle[ prop ];
- }
-
- // release memory in IE
- div = null;
- })();
-}
-
-(function(){
- var html = document.documentElement,
- matches = html.matchesSelector || html.mozMatchesSelector || html.webkitMatchesSelector || html.msMatchesSelector,
- pseudoWorks = false;
-
- try {
- // This should fail with an exception
- // Gecko does not error, returns false instead
- matches.call( document.documentElement, "[test!='']:sizzle" );
-
- } catch( pseudoError ) {
- pseudoWorks = true;
- }
-
- if ( matches ) {
- Sizzle.matchesSelector = function( node, expr ) {
- // Make sure that attribute selectors are quoted
- expr = expr.replace(/\=\s*([^'"\]]*)\s*\]/g, "='$1']");
-
- if ( !Sizzle.isXML( node ) ) {
- try {
- if ( pseudoWorks || !Expr.match.PSEUDO.test( expr ) && !/!=/.test( expr ) ) {
- return matches.call( node, expr );
- }
- } catch(e) {}
- }
-
- return Sizzle(expr, null, null, [node]).length > 0;
- };
- }
-})();
-
-(function(){
- var div = document.createElement("div");
-
- div.innerHTML = "<div class='test e'></div><div class='test'></div>";
-
- // Opera can't find a second classname (in 9.6)
- // Also, make sure that getElementsByClassName actually exists
- if ( !div.getElementsByClassName || div.getElementsByClassName("e").length === 0 ) {
- return;
- }
-
- // Safari caches class attributes, doesn't catch changes (in 3.2)
- div.lastChild.className = "e";
-
- if ( div.getElementsByClassName("e").length === 1 ) {
- return;
- }
-
- Expr.order.splice(1, 0, "CLASS");
- Expr.find.CLASS = function( match, context, isXML ) {
- if ( typeof context.getElementsByClassName !== "undefined" && !isXML ) {
- return context.getElementsByClassName(match[1]);
- }
- };
-
- // release memory in IE
- div = null;
-})();
-
-function dirNodeCheck( dir, cur, doneName, checkSet, nodeCheck, isXML ) {
- for ( var i = 0, l = checkSet.length; i < l; i++ ) {
- var elem = checkSet[i];
-
- if ( elem ) {
- var match = false;
-
- elem = elem[dir];
-
- while ( elem ) {
- if ( elem.sizcache === doneName ) {
- match = checkSet[elem.sizset];
- break;
- }
-
- if ( elem.nodeType === 1 && !isXML ){
- elem.sizcache = doneName;
- elem.sizset = i;
- }
-
- if ( elem.nodeName.toLowerCase() === cur ) {
- match = elem;
- break;
- }
-
- elem = elem[dir];
- }
-
- checkSet[i] = match;
- }
- }
-}
-
-function dirCheck( dir, cur, doneName, checkSet, nodeCheck, isXML ) {
- for ( var i = 0, l = checkSet.length; i < l; i++ ) {
- var elem = checkSet[i];
-
- if ( elem ) {
- var match = false;
-
- elem = elem[dir];
-
- while ( elem ) {
- if ( elem.sizcache === doneName ) {
- match = checkSet[elem.sizset];
- break;
- }
-
- if ( elem.nodeType === 1 ) {
- if ( !isXML ) {
- elem.sizcache = doneName;
- elem.sizset = i;
- }
-
- if ( typeof cur !== "string" ) {
- if ( elem === cur ) {
- match = true;
- break;
- }
-
- } else if ( Sizzle.filter( cur, [elem] ).length > 0 ) {
- match = elem;
- break;
- }
- }
-
- elem = elem[dir];
- }
-
- checkSet[i] = match;
- }
- }
-}
-
-if ( document.documentElement.contains ) {
- Sizzle.contains = function( a, b ) {
- return a !== b && (a.contains ? a.contains(b) : true);
- };
-
-} else if ( document.documentElement.compareDocumentPosition ) {
- Sizzle.contains = function( a, b ) {
- return !!(a.compareDocumentPosition(b) & 16);
- };
-
-} else {
- Sizzle.contains = function() {
- return false;
- };
-}
-
-Sizzle.isXML = function( elem ) {
- // documentElement is verified for cases where it doesn't yet exist
- // (such as loading iframes in IE - #4833)
- var documentElement = (elem ? elem.ownerDocument || elem : 0).documentElement;
-
- return documentElement ? documentElement.nodeName !== "HTML" : false;
-};
-
-var posProcess = function( selector, context ) {
- var match,
- tmpSet = [],
- later = "",
- root = context.nodeType ? [context] : context;
-
- // Position selectors must be done after the filter
- // And so must :not(positional) so we move all PSEUDOs to the end
- while ( (match = Expr.match.PSEUDO.exec( selector )) ) {
- later += match[0];
- selector = selector.replace( Expr.match.PSEUDO, "" );
- }
-
- selector = Expr.relative[selector] ? selector + "*" : selector;
-
- for ( var i = 0, l = root.length; i < l; i++ ) {
- Sizzle( selector, root[i], tmpSet );
- }
-
- return Sizzle.filter( later, tmpSet );
-};
-
-// EXPOSE
-jQuery.find = Sizzle;
-jQuery.expr = Sizzle.selectors;
-jQuery.expr[":"] = jQuery.expr.filters;
-jQuery.unique = Sizzle.uniqueSort;
-jQuery.text = Sizzle.getText;
-jQuery.isXMLDoc = Sizzle.isXML;
-jQuery.contains = Sizzle.contains;
-
-
-})();
-
-
-var runtil = /Until$/,
- rparentsprev = /^(?:parents|prevUntil|prevAll)/,
- // Note: This RegExp should be improved, or likely pulled from Sizzle
- rmultiselector = /,/,
- isSimple = /^.[^:#\[\.,]*$/,
- slice = Array.prototype.slice,
- POS = jQuery.expr.match.POS;
-
-jQuery.fn.extend({
- find: function( selector ) {
- var ret = this.pushStack( "", "find", selector ),
- length = 0;
-
- for ( var i = 0, l = this.length; i < l; i++ ) {
- length = ret.length;
- jQuery.find( selector, this[i], ret );
-
- if ( i > 0 ) {
- // Make sure that the results are unique
- for ( var n = length; n < ret.length; n++ ) {
- for ( var r = 0; r < length; r++ ) {
- if ( ret[r] === ret[n] ) {
- ret.splice(n--, 1);
- break;
- }
- }
- }
- }
- }
-
- return ret;
- },
-
- has: function( target ) {
- var targets = jQuery( target );
- return this.filter(function() {
- for ( var i = 0, l = targets.length; i < l; i++ ) {
- if ( jQuery.contains( this, targets[i] ) ) {
- return true;
- }
- }
- });
- },
-
- not: function( selector ) {
- return this.pushStack( winnow(this, selector, false), "not", selector);
- },
-
- filter: function( selector ) {
- return this.pushStack( winnow(this, selector, true), "filter", selector );
- },
-
- is: function( selector ) {
- return !!selector && jQuery.filter( selector, this ).length > 0;
- },
-
- closest: function( selectors, context ) {
- var ret = [], i, l, cur = this[0];
-
- if ( jQuery.isArray( selectors ) ) {
- var match, selector,
- matches = {},
- level = 1;
-
- if ( cur && selectors.length ) {
- for ( i = 0, l = selectors.length; i < l; i++ ) {
- selector = selectors[i];
-
- if ( !matches[selector] ) {
- matches[selector] = jQuery.expr.match.POS.test( selector ) ?
- jQuery( selector, context || this.context ) :
- selector;
- }
- }
-
- while ( cur && cur.ownerDocument && cur !== context ) {
- for ( selector in matches ) {
- match = matches[selector];
-
- if ( match.jquery ? match.index(cur) > -1 : jQuery(cur).is(match) ) {
- ret.push({ selector: selector, elem: cur, level: level });
- }
- }
-
- cur = cur.parentNode;
- level++;
- }
- }
-
- return ret;
- }
-
- var pos = POS.test( selectors ) ?
- jQuery( selectors, context || this.context ) : null;
-
- for ( i = 0, l = this.length; i < l; i++ ) {
- cur = this[i];
-
- while ( cur ) {
- if ( pos ? pos.index(cur) > -1 : jQuery.find.matchesSelector(cur, selectors) ) {
- ret.push( cur );
- break;
-
- } else {
- cur = cur.parentNode;
- if ( !cur || !cur.ownerDocument || cur === context ) {
- break;
- }
- }
- }
- }
-
- ret = ret.length > 1 ? jQuery.unique(ret) : ret;
-
- return this.pushStack( ret, "closest", selectors );
- },
-
- // Determine the position of an element within
- // the matched set of elements
- index: function( elem ) {
- if ( !elem || typeof elem === "string" ) {
- return jQuery.inArray( this[0],
- // If it receives a string, the selector is used
- // If it receives nothing, the siblings are used
- elem ? jQuery( elem ) : this.parent().children() );
- }
- // Locate the position of the desired element
- return jQuery.inArray(
- // If it receives a jQuery object, the first element is used
- elem.jquery ? elem[0] : elem, this );
- },
-
- add: function( selector, context ) {
- var set = typeof selector === "string" ?
- jQuery( selector, context || this.context ) :
- jQuery.makeArray( selector ),
- all = jQuery.merge( this.get(), set );
-
- return this.pushStack( isDisconnected( set[0] ) || isDisconnected( all[0] ) ?
- all :
- jQuery.unique( all ) );
- },
-
- andSelf: function() {
- return this.add( this.prevObject );
- }
-});
-
-// A painfully simple check to see if an element is disconnected
-// from a document (should be improved, where feasible).
-function isDisconnected( node ) {
- return !node || !node.parentNode || node.parentNode.nodeType === 11;
-}
-
-jQuery.each({
- parent: function( elem ) {
- var parent = elem.parentNode;
- return parent && parent.nodeType !== 11 ? parent : null;
- },
- parents: function( elem ) {
- return jQuery.dir( elem, "parentNode" );
- },
- parentsUntil: function( elem, i, until ) {
- return jQuery.dir( elem, "parentNode", until );
- },
- next: function( elem ) {
- return jQuery.nth( elem, 2, "nextSibling" );
- },
- prev: function( elem ) {
- return jQuery.nth( elem, 2, "previousSibling" );
- },
- nextAll: function( elem ) {
- return jQuery.dir( elem, "nextSibling" );
- },
- prevAll: function( elem ) {
- return jQuery.dir( elem, "previousSibling" );
- },
- nextUntil: function( elem, i, until ) {
- return jQuery.dir( elem, "nextSibling", until );
- },
- prevUntil: function( elem, i, until ) {
- return jQuery.dir( elem, "previousSibling", until );
- },
- siblings: function( elem ) {
- return jQuery.sibling( elem.parentNode.firstChild, elem );
- },
- children: function( elem ) {
- return jQuery.sibling( elem.firstChild );
- },
- contents: function( elem ) {
- return jQuery.nodeName( elem, "iframe" ) ?
- elem.contentDocument || elem.contentWindow.document :
- jQuery.makeArray( elem.childNodes );
- }
-}, function( name, fn ) {
- jQuery.fn[ name ] = function( until, selector ) {
- var ret = jQuery.map( this, fn, until );
-
- if ( !runtil.test( name ) ) {
- selector = until;
- }
-
- if ( selector && typeof selector === "string" ) {
- ret = jQuery.filter( selector, ret );
- }
-
- ret = this.length > 1 ? jQuery.unique( ret ) : ret;
-
- if ( (this.length > 1 || rmultiselector.test( selector )) && rparentsprev.test( name ) ) {
- ret = ret.reverse();
- }
-
- return this.pushStack( ret, name, slice.call(arguments).join(",") );
- };
-});
-
-jQuery.extend({
- filter: function( expr, elems, not ) {
- if ( not ) {
- expr = ":not(" + expr + ")";
- }
-
- return elems.length === 1 ?
- jQuery.find.matchesSelector(elems[0], expr) ? [ elems[0] ] : [] :
- jQuery.find.matches(expr, elems);
- },
-
- dir: function( elem, dir, until ) {
- var matched = [],
- cur = elem[ dir ];
-
- while ( cur && cur.nodeType !== 9 && (until === undefined || cur.nodeType !== 1 || !jQuery( cur ).is( until )) ) {
- if ( cur.nodeType === 1 ) {
- matched.push( cur );
- }
- cur = cur[dir];
- }
- return matched;
- },
-
- nth: function( cur, result, dir, elem ) {
- result = result || 1;
- var num = 0;
-
- for ( ; cur; cur = cur[dir] ) {
- if ( cur.nodeType === 1 && ++num === result ) {
- break;
- }
- }
-
- return cur;
- },
-
- sibling: function( n, elem ) {
- var r = [];
-
- for ( ; n; n = n.nextSibling ) {
- if ( n.nodeType === 1 && n !== elem ) {
- r.push( n );
- }
- }
-
- return r;
- }
-});
-
-// Implement the identical functionality for filter and not
-function winnow( elements, qualifier, keep ) {
- if ( jQuery.isFunction( qualifier ) ) {
- return jQuery.grep(elements, function( elem, i ) {
- var retVal = !!qualifier.call( elem, i, elem );
- return retVal === keep;
- });
-
- } else if ( qualifier.nodeType ) {
- return jQuery.grep(elements, function( elem, i ) {
- return (elem === qualifier) === keep;
- });
-
- } else if ( typeof qualifier === "string" ) {
- var filtered = jQuery.grep(elements, function( elem ) {
- return elem.nodeType === 1;
- });
-
- if ( isSimple.test( qualifier ) ) {
- return jQuery.filter(qualifier, filtered, !keep);
- } else {
- qualifier = jQuery.filter( qualifier, filtered );
- }
- }
-
- return jQuery.grep(elements, function( elem, i ) {
- return (jQuery.inArray( elem, qualifier ) >= 0) === keep;
- });
-}
-
-
-
-
-var rinlinejQuery = / jQuery\d+="(?:\d+|null)"/g,
- rleadingWhitespace = /^\s+/,
- rxhtmlTag = /<(?!area|br|col|embed|hr|img|input|link|meta|param)(([\w:]+)[^>]*)\/>/ig,
- rtagName = /<([\w:]+)/,
- rtbody = /<tbody/i,
- rhtml = /<|&#?\w+;/,
- rnocache = /<(?:script|object|embed|option|style)/i,
- // checked="checked" or checked (html5)
- rchecked = /checked\s*(?:[^=]|=\s*.checked.)/i,
- raction = /\=([^="'>\s]+\/)>/g,
- wrapMap = {
- option: [ 1, "<select multiple='multiple'>", "</select>" ],
- legend: [ 1, "<fieldset>", "</fieldset>" ],
- thead: [ 1, "<table>", "</table>" ],
- tr: [ 2, "<table><tbody>", "</tbody></table>" ],
- td: [ 3, "<table><tbody><tr>", "</tr></tbody></table>" ],
- col: [ 2, "<table><tbody></tbody><colgroup>", "</colgroup></table>" ],
- area: [ 1, "<map>", "</map>" ],
- _default: [ 0, "", "" ]
- };
-
-wrapMap.optgroup = wrapMap.option;
-wrapMap.tbody = wrapMap.tfoot = wrapMap.colgroup = wrapMap.caption = wrapMap.thead;
-wrapMap.th = wrapMap.td;
-
-// IE can't serialize <link> and <script> tags normally
-if ( !jQuery.support.htmlSerialize ) {
- wrapMap._default = [ 1, "div<div>", "</div>" ];
-}
-
-jQuery.fn.extend({
- text: function( text ) {
- if ( jQuery.isFunction(text) ) {
- return this.each(function(i) {
- var self = jQuery( this );
-
- self.text( text.call(this, i, self.text()) );
- });
- }
-
- if ( typeof text !== "object" && text !== undefined ) {
- return this.empty().append( (this[0] && this[0].ownerDocument || document).createTextNode( text ) );
- }
-
- return jQuery.text( this );
- },
-
- wrapAll: function( html ) {
- if ( jQuery.isFunction( html ) ) {
- return this.each(function(i) {
- jQuery(this).wrapAll( html.call(this, i) );
- });
- }
-
- if ( this[0] ) {
- // The elements to wrap the target around
- var wrap = jQuery( html, this[0].ownerDocument ).eq(0).clone(true);
-
- if ( this[0].parentNode ) {
- wrap.insertBefore( this[0] );
- }
-
- wrap.map(function() {
- var elem = this;
-
- while ( elem.firstChild && elem.firstChild.nodeType === 1 ) {
- elem = elem.firstChild;
- }
-
- return elem;
- }).append(this);
- }
-
- return this;
- },
-
- wrapInner: function( html ) {
- if ( jQuery.isFunction( html ) ) {
- return this.each(function(i) {
- jQuery(this).wrapInner( html.call(this, i) );
- });
- }
-
- return this.each(function() {
- var self = jQuery( this ),
- contents = self.contents();
-
- if ( contents.length ) {
- contents.wrapAll( html );
-
- } else {
- self.append( html );
- }
- });
- },
-
- wrap: function( html ) {
- return this.each(function() {
- jQuery( this ).wrapAll( html );
- });
- },
-
- unwrap: function() {
- return this.parent().each(function() {
- if ( !jQuery.nodeName( this, "body" ) ) {
- jQuery( this ).replaceWith( this.childNodes );
- }
- }).end();
- },
-
- append: function() {
- return this.domManip(arguments, true, function( elem ) {
- if ( this.nodeType === 1 ) {
- this.appendChild( elem );
- }
- });
- },
-
- prepend: function() {
- return this.domManip(arguments, true, function( elem ) {
- if ( this.nodeType === 1 ) {
- this.insertBefore( elem, this.firstChild );
- }
- });
- },
-
- before: function() {
- if ( this[0] && this[0].parentNode ) {
- return this.domManip(arguments, false, function( elem ) {
- this.parentNode.insertBefore( elem, this );
- });
- } else if ( arguments.length ) {
- var set = jQuery(arguments[0]);
- set.push.apply( set, this.toArray() );
- return this.pushStack( set, "before", arguments );
- }
- },
-
- after: function() {
- if ( this[0] && this[0].parentNode ) {
- return this.domManip(arguments, false, function( elem ) {
- this.parentNode.insertBefore( elem, this.nextSibling );
- });
- } else if ( arguments.length ) {
- var set = this.pushStack( this, "after", arguments );
- set.push.apply( set, jQuery(arguments[0]).toArray() );
- return set;
- }
- },
-
- // keepData is for internal use only--do not document
- remove: function( selector, keepData ) {
- for ( var i = 0, elem; (elem = this[i]) != null; i++ ) {
- if ( !selector || jQuery.filter( selector, [ elem ] ).length ) {
- if ( !keepData && elem.nodeType === 1 ) {
- jQuery.cleanData( elem.getElementsByTagName("*") );
- jQuery.cleanData( [ elem ] );
- }
-
- if ( elem.parentNode ) {
- elem.parentNode.removeChild( elem );
- }
- }
- }
-
- return this;
- },
-
- empty: function() {
- for ( var i = 0, elem; (elem = this[i]) != null; i++ ) {
- // Remove element nodes and prevent memory leaks
- if ( elem.nodeType === 1 ) {
- jQuery.cleanData( elem.getElementsByTagName("*") );
- }
-
- // Remove any remaining nodes
- while ( elem.firstChild ) {
- elem.removeChild( elem.firstChild );
- }
- }
-
- return this;
- },
-
- clone: function( events ) {
- // Do the clone
- var ret = this.map(function() {
- if ( !jQuery.support.noCloneEvent && !jQuery.isXMLDoc(this) ) {
- // IE copies events bound via attachEvent when
- // using cloneNode. Calling detachEvent on the
- // clone will also remove the events from the orignal
- // In order to get around this, we use innerHTML.
- // Unfortunately, this means some modifications to
- // attributes in IE that are actually only stored
- // as properties will not be copied (such as the
- // the name attribute on an input).
- var html = this.outerHTML,
- ownerDocument = this.ownerDocument;
-
- if ( !html ) {
- var div = ownerDocument.createElement("div");
- div.appendChild( this.cloneNode(true) );
- html = div.innerHTML;
- }
-
- return jQuery.clean([html.replace(rinlinejQuery, "")
- // Handle the case in IE 8 where action=/test/> self-closes a tag
- .replace(raction, '="$1">')
- .replace(rleadingWhitespace, "")], ownerDocument)[0];
- } else {
- return this.cloneNode(true);
- }
- });
-
- // Copy the events from the original to the clone
- if ( events === true ) {
- cloneCopyEvent( this, ret );
- cloneCopyEvent( this.find("*"), ret.find("*") );
- }
-
- // Return the cloned set
- return ret;
- },
-
- html: function( value ) {
- if ( value === undefined ) {
- return this[0] && this[0].nodeType === 1 ?
- this[0].innerHTML.replace(rinlinejQuery, "") :
- null;
-
- // See if we can take a shortcut and just use innerHTML
- } else if ( typeof value === "string" && !rnocache.test( value ) &&
- (jQuery.support.leadingWhitespace || !rleadingWhitespace.test( value )) &&
- !wrapMap[ (rtagName.exec( value ) || ["", ""])[1].toLowerCase() ] ) {
-
- value = value.replace(rxhtmlTag, "<$1></$2>");
-
- try {
- for ( var i = 0, l = this.length; i < l; i++ ) {
- // Remove element nodes and prevent memory leaks
- if ( this[i].nodeType === 1 ) {
- jQuery.cleanData( this[i].getElementsByTagName("*") );
- this[i].innerHTML = value;
- }
- }
-
- // If using innerHTML throws an exception, use the fallback method
- } catch(e) {
- this.empty().append( value );
- }
-
- } else if ( jQuery.isFunction( value ) ) {
- this.each(function(i){
- var self = jQuery( this );
-
- self.html( value.call(this, i, self.html()) );
- });
-
- } else {
- this.empty().append( value );
- }
-
- return this;
- },
-
- replaceWith: function( value ) {
- if ( this[0] && this[0].parentNode ) {
- // Make sure that the elements are removed from the DOM before they are inserted
- // this can help fix replacing a parent with child elements
- if ( jQuery.isFunction( value ) ) {
- return this.each(function(i) {
- var self = jQuery(this), old = self.html();
- self.replaceWith( value.call( this, i, old ) );
- });
- }
-
- if ( typeof value !== "string" ) {
- value = jQuery( value ).detach();
- }
-
- return this.each(function() {
- var next = this.nextSibling,
- parent = this.parentNode;
-
- jQuery( this ).remove();
-
- if ( next ) {
- jQuery(next).before( value );
- } else {
- jQuery(parent).append( value );
- }
- });
- } else {
- return this.pushStack( jQuery(jQuery.isFunction(value) ? value() : value), "replaceWith", value );
- }
- },
-
- detach: function( selector ) {
- return this.remove( selector, true );
- },
-
- domManip: function( args, table, callback ) {
- var results, first, fragment, parent,
- value = args[0],
- scripts = [];
-
- // We can't cloneNode fragments that contain checked, in WebKit
- if ( !jQuery.support.checkClone && arguments.length === 3 && typeof value === "string" && rchecked.test( value ) ) {
- return this.each(function() {
- jQuery(this).domManip( args, table, callback, true );
- });
- }
-
- if ( jQuery.isFunction(value) ) {
- return this.each(function(i) {
- var self = jQuery(this);
- args[0] = value.call(this, i, table ? self.html() : undefined);
- self.domManip( args, table, callback );
- });
- }
-
- if ( this[0] ) {
- parent = value && value.parentNode;
-
- // If we're in a fragment, just use that instead of building a new one
- if ( jQuery.support.parentNode && parent && parent.nodeType === 11 && parent.childNodes.length === this.length ) {
- results = { fragment: parent };
-
- } else {
- results = jQuery.buildFragment( args, this, scripts );
- }
-
- fragment = results.fragment;
-
- if ( fragment.childNodes.length === 1 ) {
- first = fragment = fragment.firstChild;
- } else {
- first = fragment.firstChild;
- }
-
- if ( first ) {
- table = table && jQuery.nodeName( first, "tr" );
-
- for ( var i = 0, l = this.length; i < l; i++ ) {
- callback.call(
- table ?
- root(this[i], first) :
- this[i],
- i > 0 || results.cacheable || this.length > 1 ?
- fragment.cloneNode(true) :
- fragment
- );
- }
- }
-
- if ( scripts.length ) {
- jQuery.each( scripts, evalScript );
- }
- }
-
- return this;
- }
-});
-
-function root( elem, cur ) {
- return jQuery.nodeName(elem, "table") ?
- (elem.getElementsByTagName("tbody")[0] ||
- elem.appendChild(elem.ownerDocument.createElement("tbody"))) :
- elem;
-}
-
-function cloneCopyEvent(orig, ret) {
- var i = 0;
-
- ret.each(function() {
- if ( this.nodeName !== (orig[i] && orig[i].nodeName) ) {
- return;
- }
-
- var oldData = jQuery.data( orig[i++] ),
- curData = jQuery.data( this, oldData ),
- events = oldData && oldData.events;
-
- if ( events ) {
- delete curData.handle;
- curData.events = {};
-
- for ( var type in events ) {
- for ( var handler in events[ type ] ) {
- jQuery.event.add( this, type, events[ type ][ handler ], events[ type ][ handler ].data );
- }
- }
- }
- });
-}
-
-jQuery.buildFragment = function( args, nodes, scripts ) {
- var fragment, cacheable, cacheresults,
- doc = (nodes && nodes[0] ? nodes[0].ownerDocument || nodes[0] : document);
-
- // Only cache "small" (1/2 KB) strings that are associated with the main document
- // Cloning options loses the selected state, so don't cache them
- // IE 6 doesn't like it when you put <object> or <embed> elements in a fragment
- // Also, WebKit does not clone 'checked' attributes on cloneNode, so don't cache
- if ( args.length === 1 && typeof args[0] === "string" && args[0].length < 512 && doc === document &&
- !rnocache.test( args[0] ) && (jQuery.support.checkClone || !rchecked.test( args[0] )) ) {
-
- cacheable = true;
- cacheresults = jQuery.fragments[ args[0] ];
- if ( cacheresults ) {
- if ( cacheresults !== 1 ) {
- fragment = cacheresults;
- }
- }
- }
-
- if ( !fragment ) {
- fragment = doc.createDocumentFragment();
- jQuery.clean( args, doc, fragment, scripts );
- }
-
- if ( cacheable ) {
- jQuery.fragments[ args[0] ] = cacheresults ? fragment : 1;
- }
-
- return { fragment: fragment, cacheable: cacheable };
-};
-
-jQuery.fragments = {};
-
-jQuery.each({
- appendTo: "append",
- prependTo: "prepend",
- insertBefore: "before",
- insertAfter: "after",
- replaceAll: "replaceWith"
-}, function( name, original ) {
- jQuery.fn[ name ] = function( selector ) {
- var ret = [],
- insert = jQuery( selector ),
- parent = this.length === 1 && this[0].parentNode;
-
- if ( parent && parent.nodeType === 11 && parent.childNodes.length === 1 && insert.length === 1 ) {
- insert[ original ]( this[0] );
- return this;
-
- } else {
- for ( var i = 0, l = insert.length; i < l; i++ ) {
- var elems = (i > 0 ? this.clone(true) : this).get();
- jQuery( insert[i] )[ original ]( elems );
- ret = ret.concat( elems );
- }
-
- return this.pushStack( ret, name, insert.selector );
- }
- };
-});
-
-jQuery.extend({
- clean: function( elems, context, fragment, scripts ) {
- context = context || document;
-
- // !context.createElement fails in IE with an error but returns typeof 'object'
- if ( typeof context.createElement === "undefined" ) {
- context = context.ownerDocument || context[0] && context[0].ownerDocument || document;
- }
-
- var ret = [];
-
- for ( var i = 0, elem; (elem = elems[i]) != null; i++ ) {
- if ( typeof elem === "number" ) {
- elem += "";
- }
-
- if ( !elem ) {
- continue;
- }
-
- // Convert html string into DOM nodes
- if ( typeof elem === "string" && !rhtml.test( elem ) ) {
- elem = context.createTextNode( elem );
-
- } else if ( typeof elem === "string" ) {
- // Fix "XHTML"-style tags in all browsers
- elem = elem.replace(rxhtmlTag, "<$1></$2>");
-
- // Trim whitespace, otherwise indexOf won't work as expected
- var tag = (rtagName.exec( elem ) || ["", ""])[1].toLowerCase(),
- wrap = wrapMap[ tag ] || wrapMap._default,
- depth = wrap[0],
- div = context.createElement("div");
-
- // Go to html and back, then peel off extra wrappers
- div.innerHTML = wrap[1] + elem + wrap[2];
-
- // Move to the right depth
- while ( depth-- ) {
- div = div.lastChild;
- }
-
- // Remove IE's autoinserted <tbody> from table fragments
- if ( !jQuery.support.tbody ) {
-
- // String was a <table>, *may* have spurious <tbody>
- var hasBody = rtbody.test(elem),
- tbody = tag === "table" && !hasBody ?
- div.firstChild && div.firstChild.childNodes :
-
- // String was a bare <thead> or <tfoot>
- wrap[1] === "<table>" && !hasBody ?
- div.childNodes :
- [];
-
- for ( var j = tbody.length - 1; j >= 0 ; --j ) {
- if ( jQuery.nodeName( tbody[ j ], "tbody" ) && !tbody[ j ].childNodes.length ) {
- tbody[ j ].parentNode.removeChild( tbody[ j ] );
- }
- }
-
- }
-
- // IE completely kills leading whitespace when innerHTML is used
- if ( !jQuery.support.leadingWhitespace && rleadingWhitespace.test( elem ) ) {
- div.insertBefore( context.createTextNode( rleadingWhitespace.exec(elem)[0] ), div.firstChild );
- }
-
- elem = div.childNodes;
- }
-
- if ( elem.nodeType ) {
- ret.push( elem );
- } else {
- ret = jQuery.merge( ret, elem );
- }
- }
-
- if ( fragment ) {
- for ( i = 0; ret[i]; i++ ) {
- if ( scripts && jQuery.nodeName( ret[i], "script" ) && (!ret[i].type || ret[i].type.toLowerCase() === "text/javascript") ) {
- scripts.push( ret[i].parentNode ? ret[i].parentNode.removeChild( ret[i] ) : ret[i] );
-
- } else {
- if ( ret[i].nodeType === 1 ) {
- ret.splice.apply( ret, [i + 1, 0].concat(jQuery.makeArray(ret[i].getElementsByTagName("script"))) );
- }
- fragment.appendChild( ret[i] );
- }
- }
- }
-
- return ret;
- },
-
- cleanData: function( elems ) {
- var data, id, cache = jQuery.cache,
- special = jQuery.event.special,
- deleteExpando = jQuery.support.deleteExpando;
-
- for ( var i = 0, elem; (elem = elems[i]) != null; i++ ) {
- if ( elem.nodeName && jQuery.noData[elem.nodeName.toLowerCase()] ) {
- continue;
- }
-
- id = elem[ jQuery.expando ];
-
- if ( id ) {
- data = cache[ id ];
-
- if ( data && data.events ) {
- for ( var type in data.events ) {
- if ( special[ type ] ) {
- jQuery.event.remove( elem, type );
-
- } else {
- jQuery.removeEvent( elem, type, data.handle );
- }
- }
- }
-
- if ( deleteExpando ) {
- delete elem[ jQuery.expando ];
-
- } else if ( elem.removeAttribute ) {
- elem.removeAttribute( jQuery.expando );
- }
-
- delete cache[ id ];
- }
- }
- }
-});
-
-function evalScript( i, elem ) {
- if ( elem.src ) {
- jQuery.ajax({
- url: elem.src,
- async: false,
- dataType: "script"
- });
- } else {
- jQuery.globalEval( elem.text || elem.textContent || elem.innerHTML || "" );
- }
-
- if ( elem.parentNode ) {
- elem.parentNode.removeChild( elem );
- }
-}
-
-
-
-
-var ralpha = /alpha\([^)]*\)/i,
- ropacity = /opacity=([^)]*)/,
- rdashAlpha = /-([a-z])/ig,
- rupper = /([A-Z])/g,
- rnumpx = /^-?\d+(?:px)?$/i,
- rnum = /^-?\d/,
-
- cssShow = { position: "absolute", visibility: "hidden", display: "block" },
- cssWidth = [ "Left", "Right" ],
- cssHeight = [ "Top", "Bottom" ],
- curCSS,
-
- getComputedStyle,
- currentStyle,
-
- fcamelCase = function( all, letter ) {
- return letter.toUpperCase();
- };
-
-jQuery.fn.css = function( name, value ) {
- // Setting 'undefined' is a no-op
- if ( arguments.length === 2 && value === undefined ) {
- return this;
- }
-
- return jQuery.access( this, name, value, true, function( elem, name, value ) {
- return value !== undefined ?
- jQuery.style( elem, name, value ) :
- jQuery.css( elem, name );
- });
-};
-
-jQuery.extend({
- // Add in style property hooks for overriding the default
- // behavior of getting and setting a style property
- cssHooks: {
- opacity: {
- get: function( elem, computed ) {
- if ( computed ) {
- // We should always get a number back from opacity
- var ret = curCSS( elem, "opacity", "opacity" );
- return ret === "" ? "1" : ret;
-
- } else {
- return elem.style.opacity;
- }
- }
- }
- },
-
- // Exclude the following css properties to add px
- cssNumber: {
- "zIndex": true,
- "fontWeight": true,
- "opacity": true,
- "zoom": true,
- "lineHeight": true
- },
-
- // Add in properties whose names you wish to fix before
- // setting or getting the value
- cssProps: {
- // normalize float css property
- "float": jQuery.support.cssFloat ? "cssFloat" : "styleFloat"
- },
-
- // Get and set the style property on a DOM Node
- style: function( elem, name, value, extra ) {
- // Don't set styles on text and comment nodes
- if ( !elem || elem.nodeType === 3 || elem.nodeType === 8 || !elem.style ) {
- return;
- }
-
- // Make sure that we're working with the right name
- var ret, origName = jQuery.camelCase( name ),
- style = elem.style, hooks = jQuery.cssHooks[ origName ];
-
- name = jQuery.cssProps[ origName ] || origName;
-
- // Check if we're setting a value
- if ( value !== undefined ) {
- // Make sure that NaN and null values aren't set. See: #7116
- if ( typeof value === "number" && isNaN( value ) || value == null ) {
- return;
- }
-
- // If a number was passed in, add 'px' to the (except for certain CSS properties)
- if ( typeof value === "number" && !jQuery.cssNumber[ origName ] ) {
- value += "px";
- }
-
- // If a hook was provided, use that value, otherwise just set the specified value
- if ( !hooks || !("set" in hooks) || (value = hooks.set( elem, value )) !== undefined ) {
- // Wrapped to prevent IE from throwing errors when 'invalid' values are provided
- // Fixes bug #5509
- try {
- style[ name ] = value;
- } catch(e) {}
- }
-
- } else {
- // If a hook was provided get the non-computed value from there
- if ( hooks && "get" in hooks && (ret = hooks.get( elem, false, extra )) !== undefined ) {
- return ret;
- }
-
- // Otherwise just get the value from the style object
- return style[ name ];
- }
- },
-
- css: function( elem, name, extra ) {
- // Make sure that we're working with the right name
- var ret, origName = jQuery.camelCase( name ),
- hooks = jQuery.cssHooks[ origName ];
-
- name = jQuery.cssProps[ origName ] || origName;
-
- // If a hook was provided get the computed value from there
- if ( hooks && "get" in hooks && (ret = hooks.get( elem, true, extra )) !== undefined ) {
- return ret;
-
- // Otherwise, if a way to get the computed value exists, use that
- } else if ( curCSS ) {
- return curCSS( elem, name, origName );
- }
- },
-
- // A method for quickly swapping in/out CSS properties to get correct calculations
- swap: function( elem, options, callback ) {
- var old = {};
-
- // Remember the old values, and insert the new ones
- for ( var name in options ) {
- old[ name ] = elem.style[ name ];
- elem.style[ name ] = options[ name ];
- }
-
- callback.call( elem );
-
- // Revert the old values
- for ( name in options ) {
- elem.style[ name ] = old[ name ];
- }
- },
-
- camelCase: function( string ) {
- return string.replace( rdashAlpha, fcamelCase );
- }
-});
-
-// DEPRECATED, Use jQuery.css() instead
-jQuery.curCSS = jQuery.css;
-
-jQuery.each(["height", "width"], function( i, name ) {
- jQuery.cssHooks[ name ] = {
- get: function( elem, computed, extra ) {
- var val;
-
- if ( computed ) {
- if ( elem.offsetWidth !== 0 ) {
- val = getWH( elem, name, extra );
-
- } else {
- jQuery.swap( elem, cssShow, function() {
- val = getWH( elem, name, extra );
- });
- }
-
- if ( val <= 0 ) {
- val = curCSS( elem, name, name );
-
- if ( val === "0px" && currentStyle ) {
- val = currentStyle( elem, name, name );
- }
-
- if ( val != null ) {
- // Should return "auto" instead of 0, use 0 for
- // temporary backwards-compat
- return val === "" || val === "auto" ? "0px" : val;
- }
- }
-
- if ( val < 0 || val == null ) {
- val = elem.style[ name ];
-
- // Should return "auto" instead of 0, use 0 for
- // temporary backwards-compat
- return val === "" || val === "auto" ? "0px" : val;
- }
-
- return typeof val === "string" ? val : val + "px";
- }
- },
-
- set: function( elem, value ) {
- if ( rnumpx.test( value ) ) {
- // ignore negative width and height values #1599
- value = parseFloat(value);
-
- if ( value >= 0 ) {
- return value + "px";
- }
-
- } else {
- return value;
- }
- }
- };
-});
-
-if ( !jQuery.support.opacity ) {
- jQuery.cssHooks.opacity = {
- get: function( elem, computed ) {
- // IE uses filters for opacity
- return ropacity.test((computed && elem.currentStyle ? elem.currentStyle.filter : elem.style.filter) || "") ?
- (parseFloat(RegExp.$1) / 100) + "" :
- computed ? "1" : "";
- },
-
- set: function( elem, value ) {
- var style = elem.style;
-
- // IE has trouble with opacity if it does not have layout
- // Force it by setting the zoom level
- style.zoom = 1;
-
- // Set the alpha filter to set the opacity
- var opacity = jQuery.isNaN(value) ?
- "" :
- "alpha(opacity=" + value * 100 + ")",
- filter = style.filter || "";
-
- style.filter = ralpha.test(filter) ?
- filter.replace(ralpha, opacity) :
- style.filter + ' ' + opacity;
- }
- };
-}
-
-if ( document.defaultView && document.defaultView.getComputedStyle ) {
- getComputedStyle = function( elem, newName, name ) {
- var ret, defaultView, computedStyle;
-
- name = name.replace( rupper, "-$1" ).toLowerCase();
-
- if ( !(defaultView = elem.ownerDocument.defaultView) ) {
- return undefined;
- }
-
- if ( (computedStyle = defaultView.getComputedStyle( elem, null )) ) {
- ret = computedStyle.getPropertyValue( name );
- if ( ret === "" && !jQuery.contains( elem.ownerDocument.documentElement, elem ) ) {
- ret = jQuery.style( elem, name );
- }
- }
-
- return ret;
- };
-}
-
-if ( document.documentElement.currentStyle ) {
- currentStyle = function( elem, name ) {
- var left, rsLeft,
- ret = elem.currentStyle && elem.currentStyle[ name ],
- style = elem.style;
-
- // From the awesome hack by Dean Edwards
- // http://erik.eae.net/archives/2007/07/27/18.54.15/#comment-102291
-
- // If we're not dealing with a regular pixel number
- // but a number that has a weird ending, we need to convert it to pixels
- if ( !rnumpx.test( ret ) && rnum.test( ret ) ) {
- // Remember the original values
- left = style.left;
- rsLeft = elem.runtimeStyle.left;
-
- // Put in the new values to get a computed value out
- elem.runtimeStyle.left = elem.currentStyle.left;
- style.left = name === "fontSize" ? "1em" : (ret || 0);
- ret = style.pixelLeft + "px";
-
- // Revert the changed values
- style.left = left;
- elem.runtimeStyle.left = rsLeft;
- }
-
- return ret === "" ? "auto" : ret;
- };
-}
-
-curCSS = getComputedStyle || currentStyle;
-
-function getWH( elem, name, extra ) {
- var which = name === "width" ? cssWidth : cssHeight,
- val = name === "width" ? elem.offsetWidth : elem.offsetHeight;
-
- if ( extra === "border" ) {
- return val;
- }
-
- jQuery.each( which, function() {
- if ( !extra ) {
- val -= parseFloat(jQuery.css( elem, "padding" + this )) || 0;
- }
-
- if ( extra === "margin" ) {
- val += parseFloat(jQuery.css( elem, "margin" + this )) || 0;
-
- } else {
- val -= parseFloat(jQuery.css( elem, "border" + this + "Width" )) || 0;
- }
- });
-
- return val;
-}
-
-if ( jQuery.expr && jQuery.expr.filters ) {
- jQuery.expr.filters.hidden = function( elem ) {
- var width = elem.offsetWidth,
- height = elem.offsetHeight;
-
- return (width === 0 && height === 0) || (!jQuery.support.reliableHiddenOffsets && (elem.style.display || jQuery.css( elem, "display" )) === "none");
- };
-
- jQuery.expr.filters.visible = function( elem ) {
- return !jQuery.expr.filters.hidden( elem );
- };
-}
-
-
-
-
-var jsc = jQuery.now(),
- rscript = /<script\b[^<]*(?:(?!<\/script>)<[^<]*)*<\/script>/gi,
- rselectTextarea = /^(?:select|textarea)/i,
- rinput = /^(?:color|date|datetime|email|hidden|month|number|password|range|search|tel|text|time|url|week)$/i,
- rnoContent = /^(?:GET|HEAD)$/,
- rbracket = /\[\]$/,
- jsre = /\=\?(&|$)/,
- rquery = /\?/,
- rts = /([?&])_=[^&]*/,
- rurl = /^(\w+:)?\/\/([^\/?#]+)/,
- r20 = /%20/g,
- rhash = /#.*$/,
-
- // Keep a copy of the old load method
- _load = jQuery.fn.load;
-
-jQuery.fn.extend({
- load: function( url, params, callback ) {
- if ( typeof url !== "string" && _load ) {
- return _load.apply( this, arguments );
-
- // Don't do a request if no elements are being requested
- } else if ( !this.length ) {
- return this;
- }
-
- var off = url.indexOf(" ");
- if ( off >= 0 ) {
- var selector = url.slice(off, url.length);
- url = url.slice(0, off);
- }
-
- // Default to a GET request
- var type = "GET";
-
- // If the second parameter was provided
- if ( params ) {
- // If it's a function
- if ( jQuery.isFunction( params ) ) {
- // We assume that it's the callback
- callback = params;
- params = null;
-
- // Otherwise, build a param string
- } else if ( typeof params === "object" ) {
- params = jQuery.param( params, jQuery.ajaxSettings.traditional );
- type = "POST";
- }
- }
-
- var self = this;
-
- // Request the remote document
- jQuery.ajax({
- url: url,
- type: type,
- dataType: "html",
- data: params,
- complete: function( res, status ) {
- // If successful, inject the HTML into all the matched elements
- if ( status === "success" || status === "notmodified" ) {
- // See if a selector was specified
- self.html( selector ?
- // Create a dummy div to hold the results
- jQuery("<div>")
- // inject the contents of the document in, removing the scripts
- // to avoid any 'Permission Denied' errors in IE
- .append(res.responseText.replace(rscript, ""))
-
- // Locate the specified elements
- .find(selector) :
-
- // If not, just inject the full result
- res.responseText );
- }
-
- if ( callback ) {
- self.each( callback, [res.responseText, status, res] );
- }
- }
- });
-
- return this;
- },
-
- serialize: function() {
- return jQuery.param(this.serializeArray());
- },
-
- serializeArray: function() {
- return this.map(function() {
- return this.elements ? jQuery.makeArray(this.elements) : this;
- })
- .filter(function() {
- return this.name && !this.disabled &&
- (this.checked || rselectTextarea.test(this.nodeName) ||
- rinput.test(this.type));
- })
- .map(function( i, elem ) {
- var val = jQuery(this).val();
-
- return val == null ?
- null :
- jQuery.isArray(val) ?
- jQuery.map( val, function( val, i ) {
- return { name: elem.name, value: val };
- }) :
- { name: elem.name, value: val };
- }).get();
- }
-});
-
-// Attach a bunch of functions for handling common AJAX events
-jQuery.each( "ajaxStart ajaxStop ajaxComplete ajaxError ajaxSuccess ajaxSend".split(" "), function( i, o ) {
- jQuery.fn[o] = function( f ) {
- return this.bind(o, f);
- };
-});
-
-jQuery.extend({
- get: function( url, data, callback, type ) {
- // shift arguments if data argument was omited
- if ( jQuery.isFunction( data ) ) {
- type = type || callback;
- callback = data;
- data = null;
- }
-
- return jQuery.ajax({
- type: "GET",
- url: url,
- data: data,
- success: callback,
- dataType: type
- });
- },
-
- getScript: function( url, callback ) {
- return jQuery.get(url, null, callback, "script");
- },
-
- getJSON: function( url, data, callback ) {
- return jQuery.get(url, data, callback, "json");
- },
-
- post: function( url, data, callback, type ) {
- // shift arguments if data argument was omited
- if ( jQuery.isFunction( data ) ) {
- type = type || callback;
- callback = data;
- data = {};
- }
-
- return jQuery.ajax({
- type: "POST",
- url: url,
- data: data,
- success: callback,
- dataType: type
- });
- },
-
- ajaxSetup: function( settings ) {
- jQuery.extend( jQuery.ajaxSettings, settings );
- },
-
- ajaxSettings: {
- url: location.href,
- global: true,
- type: "GET",
- contentType: "application/x-www-form-urlencoded",
- processData: true,
- async: true,
- /*
- timeout: 0,
- data: null,
- username: null,
- password: null,
- traditional: false,
- */
- // This function can be overriden by calling jQuery.ajaxSetup
- xhr: function() {
- return new window.XMLHttpRequest();
- },
- accepts: {
- xml: "application/xml, text/xml",
- html: "text/html",
- script: "text/javascript, application/javascript",
- json: "application/json, text/javascript",
- text: "text/plain",
- _default: "*/*"
- }
- },
-
- ajax: function( origSettings ) {
- var s = jQuery.extend(true, {}, jQuery.ajaxSettings, origSettings),
- jsonp, status, data, type = s.type.toUpperCase(), noContent = rnoContent.test(type);
-
- s.url = s.url.replace( rhash, "" );
-
- // Use original (not extended) context object if it was provided
- s.context = origSettings && origSettings.context != null ? origSettings.context : s;
-
- // convert data if not already a string
- if ( s.data && s.processData && typeof s.data !== "string" ) {
- s.data = jQuery.param( s.data, s.traditional );
- }
-
- // Handle JSONP Parameter Callbacks
- if ( s.dataType === "jsonp" ) {
- if ( type === "GET" ) {
- if ( !jsre.test( s.url ) ) {
- s.url += (rquery.test( s.url ) ? "&" : "?") + (s.jsonp || "callback") + "=?";
- }
- } else if ( !s.data || !jsre.test(s.data) ) {
- s.data = (s.data ? s.data + "&" : "") + (s.jsonp || "callback") + "=?";
- }
- s.dataType = "json";
- }
-
- // Build temporary JSONP function
- if ( s.dataType === "json" && (s.data && jsre.test(s.data) || jsre.test(s.url)) ) {
- jsonp = s.jsonpCallback || ("jsonp" + jsc++);
-
- // Replace the =? sequence both in the query string and the data
- if ( s.data ) {
- s.data = (s.data + "").replace(jsre, "=" + jsonp + "$1");
- }
-
- s.url = s.url.replace(jsre, "=" + jsonp + "$1");
-
- // We need to make sure
- // that a JSONP style response is executed properly
- s.dataType = "script";
-
- // Handle JSONP-style loading
- var customJsonp = window[ jsonp ];
-
- window[ jsonp ] = function( tmp ) {
- if ( jQuery.isFunction( customJsonp ) ) {
- customJsonp( tmp );
-
- } else {
- // Garbage collect
- window[ jsonp ] = undefined;
-
- try {
- delete window[ jsonp ];
- } catch( jsonpError ) {}
- }
-
- data = tmp;
- jQuery.handleSuccess( s, xhr, status, data );
- jQuery.handleComplete( s, xhr, status, data );
-
- if ( head ) {
- head.removeChild( script );
- }
- };
- }
-
- if ( s.dataType === "script" && s.cache === null ) {
- s.cache = false;
- }
-
- if ( s.cache === false && noContent ) {
- var ts = jQuery.now();
-
- // try replacing _= if it is there
- var ret = s.url.replace(rts, "$1_=" + ts);
-
- // if nothing was replaced, add timestamp to the end
- s.url = ret + ((ret === s.url) ? (rquery.test(s.url) ? "&" : "?") + "_=" + ts : "");
- }
-
- // If data is available, append data to url for GET/HEAD requests
- if ( s.data && noContent ) {
- s.url += (rquery.test(s.url) ? "&" : "?") + s.data;
- }
-
- // Watch for a new set of requests
- if ( s.global && jQuery.active++ === 0 ) {
- jQuery.event.trigger( "ajaxStart" );
- }
-
- // Matches an absolute URL, and saves the domain
- var parts = rurl.exec( s.url ),
- remote = parts && (parts[1] && parts[1].toLowerCase() !== location.protocol || parts[2].toLowerCase() !== location.host);
-
- // If we're requesting a remote document
- // and trying to load JSON or Script with a GET
- if ( s.dataType === "script" && type === "GET" && remote ) {
- var head = document.getElementsByTagName("head")[0] || document.documentElement;
- var script = document.createElement("script");
- if ( s.scriptCharset ) {
- script.charset = s.scriptCharset;
- }
- script.src = s.url;
-
- // Handle Script loading
- if ( !jsonp ) {
- var done = false;
-
- // Attach handlers for all browsers
- script.onload = script.onreadystatechange = function() {
- if ( !done && (!this.readyState ||
- this.readyState === "loaded" || this.readyState === "complete") ) {
- done = true;
- jQuery.handleSuccess( s, xhr, status, data );
- jQuery.handleComplete( s, xhr, status, data );
-
- // Handle memory leak in IE
- script.onload = script.onreadystatechange = null;
- if ( head && script.parentNode ) {
- head.removeChild( script );
- }
- }
- };
- }
-
- // Use insertBefore instead of appendChild to circumvent an IE6 bug.
- // This arises when a base node is used (#2709 and #4378).
- head.insertBefore( script, head.firstChild );
-
- // We handle everything using the script element injection
- return undefined;
- }
-
- var requestDone = false;
-
- // Create the request object
- var xhr = s.xhr();
-
- if ( !xhr ) {
- return;
- }
-
- // Open the socket
- // Passing null username, generates a login popup on Opera (#2865)
- if ( s.username ) {
- xhr.open(type, s.url, s.async, s.username, s.password);
- } else {
- xhr.open(type, s.url, s.async);
- }
-
- // Need an extra try/catch for cross domain requests in Firefox 3
- try {
- // Set content-type if data specified and content-body is valid for this type
- if ( (s.data != null && !noContent) || (origSettings && origSettings.contentType) ) {
- xhr.setRequestHeader("Content-Type", s.contentType);
- }
-
- // Set the If-Modified-Since and/or If-None-Match header, if in ifModified mode.
- if ( s.ifModified ) {
- if ( jQuery.lastModified[s.url] ) {
- xhr.setRequestHeader("If-Modified-Since", jQuery.lastModified[s.url]);
- }
-
- if ( jQuery.etag[s.url] ) {
- xhr.setRequestHeader("If-None-Match", jQuery.etag[s.url]);
- }
- }
-
- // Set header so the called script knows that it's an XMLHttpRequest
- // Only send the header if it's not a remote XHR
- if ( !remote ) {
- xhr.setRequestHeader("X-Requested-With", "XMLHttpRequest");
- }
-
- // Set the Accepts header for the server, depending on the dataType
- xhr.setRequestHeader("Accept", s.dataType && s.accepts[ s.dataType ] ?
- s.accepts[ s.dataType ] + ", */*; q=0.01" :
- s.accepts._default );
- } catch( headerError ) {}
-
- // Allow custom headers/mimetypes and early abort
- if ( s.beforeSend && s.beforeSend.call(s.context, xhr, s) === false ) {
- // Handle the global AJAX counter
- if ( s.global && jQuery.active-- === 1 ) {
- jQuery.event.trigger( "ajaxStop" );
- }
-
- // close opended socket
- xhr.abort();
- return false;
- }
-
- if ( s.global ) {
- jQuery.triggerGlobal( s, "ajaxSend", [xhr, s] );
- }
-
- // Wait for a response to come back
- var onreadystatechange = xhr.onreadystatechange = function( isTimeout ) {
- // The request was aborted
- if ( !xhr || xhr.readyState === 0 || isTimeout === "abort" ) {
- // Opera doesn't call onreadystatechange before this point
- // so we simulate the call
- if ( !requestDone ) {
- jQuery.handleComplete( s, xhr, status, data );
- }
-
- requestDone = true;
- if ( xhr ) {
- xhr.onreadystatechange = jQuery.noop;
- }
-
- // The transfer is complete and the data is available, or the request timed out
- } else if ( !requestDone && xhr && (xhr.readyState === 4 || isTimeout === "timeout") ) {
- requestDone = true;
- xhr.onreadystatechange = jQuery.noop;
-
- status = isTimeout === "timeout" ?
- "timeout" :
- !jQuery.httpSuccess( xhr ) ?
- "error" :
- s.ifModified && jQuery.httpNotModified( xhr, s.url ) ?
- "notmodified" :
- "success";
-
- var errMsg;
-
- if ( status === "success" ) {
- // Watch for, and catch, XML document parse errors
- try {
- // process the data (runs the xml through httpData regardless of callback)
- data = jQuery.httpData( xhr, s.dataType, s );
- } catch( parserError ) {
- status = "parsererror";
- errMsg = parserError;
- }
- }
-
- // Make sure that the request was successful or notmodified
- if ( status === "success" || status === "notmodified" ) {
- // JSONP handles its own success callback
- if ( !jsonp ) {
- jQuery.handleSuccess( s, xhr, status, data );
- }
- } else {
- jQuery.handleError( s, xhr, status, errMsg );
- }
-
- // Fire the complete handlers
- if ( !jsonp ) {
- jQuery.handleComplete( s, xhr, status, data );
- }
-
- if ( isTimeout === "timeout" ) {
- xhr.abort();
- }
-
- // Stop memory leaks
- if ( s.async ) {
- xhr = null;
- }
- }
- };
-
- // Override the abort handler, if we can (IE 6 doesn't allow it, but that's OK)
- // Opera doesn't fire onreadystatechange at all on abort
- try {
- var oldAbort = xhr.abort;
- xhr.abort = function() {
- if ( xhr ) {
- // oldAbort has no call property in IE7 so
- // just do it this way, which works in all
- // browsers
- Function.prototype.call.call( oldAbort, xhr );
- }
-
- onreadystatechange( "abort" );
- };
- } catch( abortError ) {}
-
- // Timeout checker
- if ( s.async && s.timeout > 0 ) {
- setTimeout(function() {
- // Check to see if the request is still happening
- if ( xhr && !requestDone ) {
- onreadystatechange( "timeout" );
- }
- }, s.timeout);
- }
-
- // Send the data
- try {
- xhr.send( noContent || s.data == null ? null : s.data );
-
- } catch( sendError ) {
- jQuery.handleError( s, xhr, null, sendError );
-
- // Fire the complete handlers
- jQuery.handleComplete( s, xhr, status, data );
- }
-
- // firefox 1.5 doesn't fire statechange for sync requests
- if ( !s.async ) {
- onreadystatechange();
- }
-
- // return XMLHttpRequest to allow aborting the request etc.
- return xhr;
- },
-
- // Serialize an array of form elements or a set of
- // key/values into a query string
- param: function( a, traditional ) {
- var s = [],
- add = function( key, value ) {
- // If value is a function, invoke it and return its value
- value = jQuery.isFunction(value) ? value() : value;
- s[ s.length ] = encodeURIComponent(key) + "=" + encodeURIComponent(value);
- };
-
- // Set traditional to true for jQuery <= 1.3.2 behavior.
- if ( traditional === undefined ) {
- traditional = jQuery.ajaxSettings.traditional;
- }
-
- // If an array was passed in, assume that it is an array of form elements.
- if ( jQuery.isArray(a) || a.jquery ) {
- // Serialize the form elements
- jQuery.each( a, function() {
- add( this.name, this.value );
- });
-
- } else {
- // If traditional, encode the "old" way (the way 1.3.2 or older
- // did it), otherwise encode params recursively.
- for ( var prefix in a ) {
- buildParams( prefix, a[prefix], traditional, add );
- }
- }
-
- // Return the resulting serialization
- return s.join("&").replace(r20, "+");
- }
-});
-
-function buildParams( prefix, obj, traditional, add ) {
- if ( jQuery.isArray(obj) && obj.length ) {
- // Serialize array item.
- jQuery.each( obj, function( i, v ) {
- if ( traditional || rbracket.test( prefix ) ) {
- // Treat each array item as a scalar.
- add( prefix, v );
-
- } else {
- // If array item is non-scalar (array or object), encode its
- // numeric index to resolve deserialization ambiguity issues.
- // Note that rack (as of 1.0.0) can't currently deserialize
- // nested arrays properly, and attempting to do so may cause
- // a server error. Possible fixes are to modify rack's
- // deserialization algorithm or to provide an option or flag
- // to force array serialization to be shallow.
- buildParams( prefix + "[" + ( typeof v === "object" || jQuery.isArray(v) ? i : "" ) + "]", v, traditional, add );
- }
- });
-
- } else if ( !traditional && obj != null && typeof obj === "object" ) {
- if ( jQuery.isEmptyObject( obj ) ) {
- add( prefix, "" );
-
- // Serialize object item.
- } else {
- jQuery.each( obj, function( k, v ) {
- buildParams( prefix + "[" + k + "]", v, traditional, add );
- });
- }
-
- } else {
- // Serialize scalar item.
- add( prefix, obj );
- }
-}
-
-// This is still on the jQuery object... for now
-// Want to move this to jQuery.ajax some day
-jQuery.extend({
-
- // Counter for holding the number of active queries
- active: 0,
-
- // Last-Modified header cache for next request
- lastModified: {},
- etag: {},
-
- handleError: function( s, xhr, status, e ) {
- // If a local callback was specified, fire it
- if ( s.error ) {
- s.error.call( s.context, xhr, status, e );
- }
-
- // Fire the global callback
- if ( s.global ) {
- jQuery.triggerGlobal( s, "ajaxError", [xhr, s, e] );
- }
- },
-
- handleSuccess: function( s, xhr, status, data ) {
- // If a local callback was specified, fire it and pass it the data
- if ( s.success ) {
- s.success.call( s.context, data, status, xhr );
- }
-
- // Fire the global callback
- if ( s.global ) {
- jQuery.triggerGlobal( s, "ajaxSuccess", [xhr, s] );
- }
- },
-
- handleComplete: function( s, xhr, status ) {
- // Process result
- if ( s.complete ) {
- s.complete.call( s.context, xhr, status );
- }
-
- // The request was completed
- if ( s.global ) {
- jQuery.triggerGlobal( s, "ajaxComplete", [xhr, s] );
- }
-
- // Handle the global AJAX counter
- if ( s.global && jQuery.active-- === 1 ) {
- jQuery.event.trigger( "ajaxStop" );
- }
- },
-
- triggerGlobal: function( s, type, args ) {
- (s.context && s.context.url == null ? jQuery(s.context) : jQuery.event).trigger(type, args);
- },
-
- // Determines if an XMLHttpRequest was successful or not
- httpSuccess: function( xhr ) {
- try {
- // IE error sometimes returns 1223 when it should be 204 so treat it as success, see #1450
- return !xhr.status && location.protocol === "file:" ||
- xhr.status >= 200 && xhr.status < 300 ||
- xhr.status === 304 || xhr.status === 1223;
- } catch(e) {}
-
- return false;
- },
-
- // Determines if an XMLHttpRequest returns NotModified
- httpNotModified: function( xhr, url ) {
- var lastModified = xhr.getResponseHeader("Last-Modified"),
- etag = xhr.getResponseHeader("Etag");
-
- if ( lastModified ) {
- jQuery.lastModified[url] = lastModified;
- }
-
- if ( etag ) {
- jQuery.etag[url] = etag;
- }
-
- return xhr.status === 304;
- },
-
- httpData: function( xhr, type, s ) {
- var ct = xhr.getResponseHeader("content-type") || "",
- xml = type === "xml" || !type && ct.indexOf("xml") >= 0,
- data = xml ? xhr.responseXML : xhr.responseText;
-
- if ( xml && data.documentElement.nodeName === "parsererror" ) {
- jQuery.error( "parsererror" );
- }
-
- // Allow a pre-filtering function to sanitize the response
- // s is checked to keep backwards compatibility
- if ( s && s.dataFilter ) {
- data = s.dataFilter( data, type );
- }
-
- // The filter can actually parse the response
- if ( typeof data === "string" ) {
- // Get the JavaScript object, if JSON is used.
- if ( type === "json" || !type && ct.indexOf("json") >= 0 ) {
- data = jQuery.parseJSON( data );
-
- // If the type is "script", eval it in global context
- } else if ( type === "script" || !type && ct.indexOf("javascript") >= 0 ) {
- jQuery.globalEval( data );
- }
- }
-
- return data;
- }
-
-});
-
-/*
- * Create the request object; Microsoft failed to properly
- * implement the XMLHttpRequest in IE7 (can't request local files),
- * so we use the ActiveXObject when it is available
- * Additionally XMLHttpRequest can be disabled in IE7/IE8 so
- * we need a fallback.
- */
-if ( window.ActiveXObject ) {
- jQuery.ajaxSettings.xhr = function() {
- if ( window.location.protocol !== "file:" ) {
- try {
- return new window.XMLHttpRequest();
- } catch(xhrError) {}
- }
-
- try {
- return new window.ActiveXObject("Microsoft.XMLHTTP");
- } catch(activeError) {}
- };
-}
-
-// Does this browser support XHR requests?
-jQuery.support.ajax = !!jQuery.ajaxSettings.xhr();
-
-
-
-
-var elemdisplay = {},
- rfxtypes = /^(?:toggle|show|hide)$/,
- rfxnum = /^([+\-]=)?([\d+.\-]+)(.*)$/,
- timerId,
- fxAttrs = [
- // height animations
- [ "height", "marginTop", "marginBottom", "paddingTop", "paddingBottom" ],
- // width animations
- [ "width", "marginLeft", "marginRight", "paddingLeft", "paddingRight" ],
- // opacity animations
- [ "opacity" ]
- ];
-
-jQuery.fn.extend({
- show: function( speed, easing, callback ) {
- var elem, display;
-
- if ( speed || speed === 0 ) {
- return this.animate( genFx("show", 3), speed, easing, callback);
-
- } else {
- for ( var i = 0, j = this.length; i < j; i++ ) {
- elem = this[i];
- display = elem.style.display;
-
- // Reset the inline display of this element to learn if it is
- // being hidden by cascaded rules or not
- if ( !jQuery.data(elem, "olddisplay") && display === "none" ) {
- display = elem.style.display = "";
- }
-
- // Set elements which have been overridden with display: none
- // in a stylesheet to whatever the default browser style is
- // for such an element
- if ( display === "" && jQuery.css( elem, "display" ) === "none" ) {
- jQuery.data(elem, "olddisplay", defaultDisplay(elem.nodeName));
- }
- }
-
- // Set the display of most of the elements in a second loop
- // to avoid the constant reflow
- for ( i = 0; i < j; i++ ) {
- elem = this[i];
- display = elem.style.display;
-
- if ( display === "" || display === "none" ) {
- elem.style.display = jQuery.data(elem, "olddisplay") || "";
- }
- }
-
- return this;
- }
- },
-
- hide: function( speed, easing, callback ) {
- if ( speed || speed === 0 ) {
- return this.animate( genFx("hide", 3), speed, easing, callback);
-
- } else {
- for ( var i = 0, j = this.length; i < j; i++ ) {
- var display = jQuery.css( this[i], "display" );
-
- if ( display !== "none" ) {
- jQuery.data( this[i], "olddisplay", display );
- }
- }
-
- // Set the display of the elements in a second loop
- // to avoid the constant reflow
- for ( i = 0; i < j; i++ ) {
- this[i].style.display = "none";
- }
-
- return this;
- }
- },
-
- // Save the old toggle function
- _toggle: jQuery.fn.toggle,
-
- toggle: function( fn, fn2, callback ) {
- var bool = typeof fn === "boolean";
-
- if ( jQuery.isFunction(fn) && jQuery.isFunction(fn2) ) {
- this._toggle.apply( this, arguments );
-
- } else if ( fn == null || bool ) {
- this.each(function() {
- var state = bool ? fn : jQuery(this).is(":hidden");
- jQuery(this)[ state ? "show" : "hide" ]();
- });
-
- } else {
- this.animate(genFx("toggle", 3), fn, fn2, callback);
- }
-
- return this;
- },
-
- fadeTo: function( speed, to, easing, callback ) {
- return this.filter(":hidden").css("opacity", 0).show().end()
- .animate({opacity: to}, speed, easing, callback);
- },
-
- animate: function( prop, speed, easing, callback ) {
- var optall = jQuery.speed(speed, easing, callback);
-
- if ( jQuery.isEmptyObject( prop ) ) {
- return this.each( optall.complete );
- }
-
- return this[ optall.queue === false ? "each" : "queue" ](function() {
- // XXX 'this' does not always have a nodeName when running the
- // test suite
-
- var opt = jQuery.extend({}, optall), p,
- isElement = this.nodeType === 1,
- hidden = isElement && jQuery(this).is(":hidden"),
- self = this;
-
- for ( p in prop ) {
- var name = jQuery.camelCase( p );
-
- if ( p !== name ) {
- prop[ name ] = prop[ p ];
- delete prop[ p ];
- p = name;
- }
-
- if ( prop[p] === "hide" && hidden || prop[p] === "show" && !hidden ) {
- return opt.complete.call(this);
- }
-
- if ( isElement && ( p === "height" || p === "width" ) ) {
- // Make sure that nothing sneaks out
- // Record all 3 overflow attributes because IE does not
- // change the overflow attribute when overflowX and
- // overflowY are set to the same value
- opt.overflow = [ this.style.overflow, this.style.overflowX, this.style.overflowY ];
-
- // Set display property to inline-block for height/width
- // animations on inline elements that are having width/height
- // animated
- if ( jQuery.css( this, "display" ) === "inline" &&
- jQuery.css( this, "float" ) === "none" ) {
- if ( !jQuery.support.inlineBlockNeedsLayout ) {
- this.style.display = "inline-block";
-
- } else {
- var display = defaultDisplay(this.nodeName);
-
- // inline-level elements accept inline-block;
- // block-level elements need to be inline with layout
- if ( display === "inline" ) {
- this.style.display = "inline-block";
-
- } else {
- this.style.display = "inline";
- this.style.zoom = 1;
- }
- }
- }
- }
-
- if ( jQuery.isArray( prop[p] ) ) {
- // Create (if needed) and add to specialEasing
- (opt.specialEasing = opt.specialEasing || {})[p] = prop[p][1];
- prop[p] = prop[p][0];
- }
- }
-
- if ( opt.overflow != null ) {
- this.style.overflow = "hidden";
- }
-
- opt.curAnim = jQuery.extend({}, prop);
-
- jQuery.each( prop, function( name, val ) {
- var e = new jQuery.fx( self, opt, name );
-
- if ( rfxtypes.test(val) ) {
- e[ val === "toggle" ? hidden ? "show" : "hide" : val ]( prop );
-
- } else {
- var parts = rfxnum.exec(val),
- start = e.cur() || 0;
-
- if ( parts ) {
- var end = parseFloat( parts[2] ),
- unit = parts[3] || "px";
-
- // We need to compute starting value
- if ( unit !== "px" ) {
- jQuery.style( self, name, (end || 1) + unit);
- start = ((end || 1) / e.cur()) * start;
- jQuery.style( self, name, start + unit);
- }
-
- // If a +=/-= token was provided, we're doing a relative animation
- if ( parts[1] ) {
- end = ((parts[1] === "-=" ? -1 : 1) * end) + start;
- }
-
- e.custom( start, end, unit );
-
- } else {
- e.custom( start, val, "" );
- }
- }
- });
-
- // For JS strict compliance
- return true;
- });
- },
-
- stop: function( clearQueue, gotoEnd ) {
- var timers = jQuery.timers;
-
- if ( clearQueue ) {
- this.queue([]);
- }
-
- this.each(function() {
- // go in reverse order so anything added to the queue during the loop is ignored
- for ( var i = timers.length - 1; i >= 0; i-- ) {
- if ( timers[i].elem === this ) {
- if (gotoEnd) {
- // force the next step to be the last
- timers[i](true);
- }
-
- timers.splice(i, 1);
- }
- }
- });
-
- // start the next in the queue if the last step wasn't forced
- if ( !gotoEnd ) {
- this.dequeue();
- }
-
- return this;
- }
-
-});
-
-function genFx( type, num ) {
- var obj = {};
-
- jQuery.each( fxAttrs.concat.apply([], fxAttrs.slice(0,num)), function() {
- obj[ this ] = type;
- });
-
- return obj;
-}
-
-// Generate shortcuts for custom animations
-jQuery.each({
- slideDown: genFx("show", 1),
- slideUp: genFx("hide", 1),
- slideToggle: genFx("toggle", 1),
- fadeIn: { opacity: "show" },
- fadeOut: { opacity: "hide" },
- fadeToggle: { opacity: "toggle" }
-}, function( name, props ) {
- jQuery.fn[ name ] = function( speed, easing, callback ) {
- return this.animate( props, speed, easing, callback );
- };
-});
-
-jQuery.extend({
- speed: function( speed, easing, fn ) {
- var opt = speed && typeof speed === "object" ? jQuery.extend({}, speed) : {
- complete: fn || !fn && easing ||
- jQuery.isFunction( speed ) && speed,
- duration: speed,
- easing: fn && easing || easing && !jQuery.isFunction(easing) && easing
- };
-
- opt.duration = jQuery.fx.off ? 0 : typeof opt.duration === "number" ? opt.duration :
- opt.duration in jQuery.fx.speeds ? jQuery.fx.speeds[opt.duration] : jQuery.fx.speeds._default;
-
- // Queueing
- opt.old = opt.complete;
- opt.complete = function() {
- if ( opt.queue !== false ) {
- jQuery(this).dequeue();
- }
- if ( jQuery.isFunction( opt.old ) ) {
- opt.old.call( this );
- }
- };
-
- return opt;
- },
-
- easing: {
- linear: function( p, n, firstNum, diff ) {
- return firstNum + diff * p;
- },
- swing: function( p, n, firstNum, diff ) {
- return ((-Math.cos(p*Math.PI)/2) + 0.5) * diff + firstNum;
- }
- },
-
- timers: [],
-
- fx: function( elem, options, prop ) {
- this.options = options;
- this.elem = elem;
- this.prop = prop;
-
- if ( !options.orig ) {
- options.orig = {};
- }
- }
-
-});
-
-jQuery.fx.prototype = {
- // Simple function for setting a style value
- update: function() {
- if ( this.options.step ) {
- this.options.step.call( this.elem, this.now, this );
- }
-
- (jQuery.fx.step[this.prop] || jQuery.fx.step._default)( this );
- },
-
- // Get the current size
- cur: function() {
- if ( this.elem[this.prop] != null && (!this.elem.style || this.elem.style[this.prop] == null) ) {
- return this.elem[ this.prop ];
- }
-
- var r = parseFloat( jQuery.css( this.elem, this.prop ) );
- return r && r > -10000 ? r : 0;
- },
-
- // Start an animation from one number to another
- custom: function( from, to, unit ) {
- var self = this,
- fx = jQuery.fx;
-
- this.startTime = jQuery.now();
- this.start = from;
- this.end = to;
- this.unit = unit || this.unit || "px";
- this.now = this.start;
- this.pos = this.state = 0;
-
- function t( gotoEnd ) {
- return self.step(gotoEnd);
- }
-
- t.elem = this.elem;
-
- if ( t() && jQuery.timers.push(t) && !timerId ) {
- timerId = setInterval(fx.tick, fx.interval);
- }
- },
-
- // Simple 'show' function
- show: function() {
- // Remember where we started, so that we can go back to it later
- this.options.orig[this.prop] = jQuery.style( this.elem, this.prop );
- this.options.show = true;
-
- // Begin the animation
- // Make sure that we start at a small width/height to avoid any
- // flash of content
- this.custom(this.prop === "width" || this.prop === "height" ? 1 : 0, this.cur());
-
- // Start by showing the element
- jQuery( this.elem ).show();
- },
-
- // Simple 'hide' function
- hide: function() {
- // Remember where we started, so that we can go back to it later
- this.options.orig[this.prop] = jQuery.style( this.elem, this.prop );
- this.options.hide = true;
-
- // Begin the animation
- this.custom(this.cur(), 0);
- },
-
- // Each step of an animation
- step: function( gotoEnd ) {
- var t = jQuery.now(), done = true;
-
- if ( gotoEnd || t >= this.options.duration + this.startTime ) {
- this.now = this.end;
- this.pos = this.state = 1;
- this.update();
-
- this.options.curAnim[ this.prop ] = true;
-
- for ( var i in this.options.curAnim ) {
- if ( this.options.curAnim[i] !== true ) {
- done = false;
- }
- }
-
- if ( done ) {
- // Reset the overflow
- if ( this.options.overflow != null && !jQuery.support.shrinkWrapBlocks ) {
- var elem = this.elem,
- options = this.options;
-
- jQuery.each( [ "", "X", "Y" ], function (index, value) {
- elem.style[ "overflow" + value ] = options.overflow[index];
- } );
- }
-
- // Hide the element if the "hide" operation was done
- if ( this.options.hide ) {
- jQuery(this.elem).hide();
- }
-
- // Reset the properties, if the item has been hidden or shown
- if ( this.options.hide || this.options.show ) {
- for ( var p in this.options.curAnim ) {
- jQuery.style( this.elem, p, this.options.orig[p] );
- }
- }
-
- // Execute the complete function
- this.options.complete.call( this.elem );
- }
-
- return false;
-
- } else {
- var n = t - this.startTime;
- this.state = n / this.options.duration;
-
- // Perform the easing function, defaults to swing
- var specialEasing = this.options.specialEasing && this.options.specialEasing[this.prop];
- var defaultEasing = this.options.easing || (jQuery.easing.swing ? "swing" : "linear");
- this.pos = jQuery.easing[specialEasing || defaultEasing](this.state, n, 0, 1, this.options.duration);
- this.now = this.start + ((this.end - this.start) * this.pos);
-
- // Perform the next step of the animation
- this.update();
- }
-
- return true;
- }
-};
-
-jQuery.extend( jQuery.fx, {
- tick: function() {
- var timers = jQuery.timers;
-
- for ( var i = 0; i < timers.length; i++ ) {
- if ( !timers[i]() ) {
- timers.splice(i--, 1);
- }
- }
-
- if ( !timers.length ) {
- jQuery.fx.stop();
- }
- },
-
- interval: 13,
-
- stop: function() {
- clearInterval( timerId );
- timerId = null;
- },
-
- speeds: {
- slow: 600,
- fast: 200,
- // Default speed
- _default: 400
- },
-
- step: {
- opacity: function( fx ) {
- jQuery.style( fx.elem, "opacity", fx.now );
- },
-
- _default: function( fx ) {
- if ( fx.elem.style && fx.elem.style[ fx.prop ] != null ) {
- fx.elem.style[ fx.prop ] = (fx.prop === "width" || fx.prop === "height" ? Math.max(0, fx.now) : fx.now) + fx.unit;
- } else {
- fx.elem[ fx.prop ] = fx.now;
- }
- }
- }
-});
-
-if ( jQuery.expr && jQuery.expr.filters ) {
- jQuery.expr.filters.animated = function( elem ) {
- return jQuery.grep(jQuery.timers, function( fn ) {
- return elem === fn.elem;
- }).length;
- };
-}
-
-function defaultDisplay( nodeName ) {
- if ( !elemdisplay[ nodeName ] ) {
- var elem = jQuery("<" + nodeName + ">").appendTo("body"),
- display = elem.css("display");
-
- elem.remove();
-
- if ( display === "none" || display === "" ) {
- display = "block";
- }
-
- elemdisplay[ nodeName ] = display;
- }
-
- return elemdisplay[ nodeName ];
-}
-
-
-
-
-var rtable = /^t(?:able|d|h)$/i,
- rroot = /^(?:body|html)$/i;
-
-if ( "getBoundingClientRect" in document.documentElement ) {
- jQuery.fn.offset = function( options ) {
- var elem = this[0], box;
-
- if ( options ) {
- return this.each(function( i ) {
- jQuery.offset.setOffset( this, options, i );
- });
- }
-
- if ( !elem || !elem.ownerDocument ) {
- return null;
- }
-
- if ( elem === elem.ownerDocument.body ) {
- return jQuery.offset.bodyOffset( elem );
- }
-
- try {
- box = elem.getBoundingClientRect();
- } catch(e) {}
-
- var doc = elem.ownerDocument,
- docElem = doc.documentElement;
-
- // Make sure we're not dealing with a disconnected DOM node
- if ( !box || !jQuery.contains( docElem, elem ) ) {
- return box || { top: 0, left: 0 };
- }
-
- var body = doc.body,
- win = getWindow(doc),
- clientTop = docElem.clientTop || body.clientTop || 0,
- clientLeft = docElem.clientLeft || body.clientLeft || 0,
- scrollTop = (win.pageYOffset || jQuery.support.boxModel && docElem.scrollTop || body.scrollTop ),
- scrollLeft = (win.pageXOffset || jQuery.support.boxModel && docElem.scrollLeft || body.scrollLeft),
- top = box.top + scrollTop - clientTop,
- left = box.left + scrollLeft - clientLeft;
-
- return { top: top, left: left };
- };
-
-} else {
- jQuery.fn.offset = function( options ) {
- var elem = this[0];
-
- if ( options ) {
- return this.each(function( i ) {
- jQuery.offset.setOffset( this, options, i );
- });
- }
-
- if ( !elem || !elem.ownerDocument ) {
- return null;
- }
-
- if ( elem === elem.ownerDocument.body ) {
- return jQuery.offset.bodyOffset( elem );
- }
-
- jQuery.offset.initialize();
-
- var computedStyle,
- offsetParent = elem.offsetParent,
- prevOffsetParent = elem,
- doc = elem.ownerDocument,
- docElem = doc.documentElement,
- body = doc.body,
- defaultView = doc.defaultView,
- prevComputedStyle = defaultView ? defaultView.getComputedStyle( elem, null ) : elem.currentStyle,
- top = elem.offsetTop,
- left = elem.offsetLeft;
-
- while ( (elem = elem.parentNode) && elem !== body && elem !== docElem ) {
- if ( jQuery.offset.supportsFixedPosition && prevComputedStyle.position === "fixed" ) {
- break;
- }
-
- computedStyle = defaultView ? defaultView.getComputedStyle(elem, null) : elem.currentStyle;
- top -= elem.scrollTop;
- left -= elem.scrollLeft;
-
- if ( elem === offsetParent ) {
- top += elem.offsetTop;
- left += elem.offsetLeft;
-
- if ( jQuery.offset.doesNotAddBorder && !(jQuery.offset.doesAddBorderForTableAndCells && rtable.test(elem.nodeName)) ) {
- top += parseFloat( computedStyle.borderTopWidth ) || 0;
- left += parseFloat( computedStyle.borderLeftWidth ) || 0;
- }
-
- prevOffsetParent = offsetParent;
- offsetParent = elem.offsetParent;
- }
-
- if ( jQuery.offset.subtractsBorderForOverflowNotVisible && computedStyle.overflow !== "visible" ) {
- top += parseFloat( computedStyle.borderTopWidth ) || 0;
- left += parseFloat( computedStyle.borderLeftWidth ) || 0;
- }
-
- prevComputedStyle = computedStyle;
- }
-
- if ( prevComputedStyle.position === "relative" || prevComputedStyle.position === "static" ) {
- top += body.offsetTop;
- left += body.offsetLeft;
- }
-
- if ( jQuery.offset.supportsFixedPosition && prevComputedStyle.position === "fixed" ) {
- top += Math.max( docElem.scrollTop, body.scrollTop );
- left += Math.max( docElem.scrollLeft, body.scrollLeft );
- }
-
- return { top: top, left: left };
- };
-}
-
-jQuery.offset = {
- initialize: function() {
- var body = document.body, container = document.createElement("div"), innerDiv, checkDiv, table, td, bodyMarginTop = parseFloat( jQuery.css(body, "marginTop") ) || 0,
- html = "<div style='position:absolute;top:0;left:0;margin:0;border:5px solid #000;padding:0;width:1px;height:1px;'><div></div></div><table style='position:absolute;top:0;left:0;margin:0;border:5px solid #000;padding:0;width:1px;height:1px;' cellpadding='0' cellspacing='0'><tr><td></td></tr></table>";
-
- jQuery.extend( container.style, { position: "absolute", top: 0, left: 0, margin: 0, border: 0, width: "1px", height: "1px", visibility: "hidden" } );
-
- container.innerHTML = html;
- body.insertBefore( container, body.firstChild );
- innerDiv = container.firstChild;
- checkDiv = innerDiv.firstChild;
- td = innerDiv.nextSibling.firstChild.firstChild;
-
- this.doesNotAddBorder = (checkDiv.offsetTop !== 5);
- this.doesAddBorderForTableAndCells = (td.offsetTop === 5);
-
- checkDiv.style.position = "fixed";
- checkDiv.style.top = "20px";
-
- // safari subtracts parent border width here which is 5px
- this.supportsFixedPosition = (checkDiv.offsetTop === 20 || checkDiv.offsetTop === 15);
- checkDiv.style.position = checkDiv.style.top = "";
-
- innerDiv.style.overflow = "hidden";
- innerDiv.style.position = "relative";
-
- this.subtractsBorderForOverflowNotVisible = (checkDiv.offsetTop === -5);
-
- this.doesNotIncludeMarginInBodyOffset = (body.offsetTop !== bodyMarginTop);
-
- body.removeChild( container );
- body = container = innerDiv = checkDiv = table = td = null;
- jQuery.offset.initialize = jQuery.noop;
- },
-
- bodyOffset: function( body ) {
- var top = body.offsetTop,
- left = body.offsetLeft;
-
- jQuery.offset.initialize();
-
- if ( jQuery.offset.doesNotIncludeMarginInBodyOffset ) {
- top += parseFloat( jQuery.css(body, "marginTop") ) || 0;
- left += parseFloat( jQuery.css(body, "marginLeft") ) || 0;
- }
-
- return { top: top, left: left };
- },
-
- setOffset: function( elem, options, i ) {
- var position = jQuery.css( elem, "position" );
-
- // set position first, in-case top/left are set even on static elem
- if ( position === "static" ) {
- elem.style.position = "relative";
- }
-
- var curElem = jQuery( elem ),
- curOffset = curElem.offset(),
- curCSSTop = jQuery.css( elem, "top" ),
- curCSSLeft = jQuery.css( elem, "left" ),
- calculatePosition = (position === "absolute" && jQuery.inArray('auto', [curCSSTop, curCSSLeft]) > -1),
- props = {}, curPosition = {}, curTop, curLeft;
-
- // need to be able to calculate position if either top or left is auto and position is absolute
- if ( calculatePosition ) {
- curPosition = curElem.position();
- }
-
- curTop = calculatePosition ? curPosition.top : parseInt( curCSSTop, 10 ) || 0;
- curLeft = calculatePosition ? curPosition.left : parseInt( curCSSLeft, 10 ) || 0;
-
- if ( jQuery.isFunction( options ) ) {
- options = options.call( elem, i, curOffset );
- }
-
- if (options.top != null) {
- props.top = (options.top - curOffset.top) + curTop;
- }
- if (options.left != null) {
- props.left = (options.left - curOffset.left) + curLeft;
- }
-
- if ( "using" in options ) {
- options.using.call( elem, props );
- } else {
- curElem.css( props );
- }
- }
-};
-
-
-jQuery.fn.extend({
- position: function() {
- if ( !this[0] ) {
- return null;
- }
-
- var elem = this[0],
-
- // Get *real* offsetParent
- offsetParent = this.offsetParent(),
-
- // Get correct offsets
- offset = this.offset(),
- parentOffset = rroot.test(offsetParent[0].nodeName) ? { top: 0, left: 0 } : offsetParent.offset();
-
- // Subtract element margins
- // note: when an element has margin: auto the offsetLeft and marginLeft
- // are the same in Safari causing offset.left to incorrectly be 0
- offset.top -= parseFloat( jQuery.css(elem, "marginTop") ) || 0;
- offset.left -= parseFloat( jQuery.css(elem, "marginLeft") ) || 0;
-
- // Add offsetParent borders
- parentOffset.top += parseFloat( jQuery.css(offsetParent[0], "borderTopWidth") ) || 0;
- parentOffset.left += parseFloat( jQuery.css(offsetParent[0], "borderLeftWidth") ) || 0;
-
- // Subtract the two offsets
- return {
- top: offset.top - parentOffset.top,
- left: offset.left - parentOffset.left
- };
- },
-
- offsetParent: function() {
- return this.map(function() {
- var offsetParent = this.offsetParent || document.body;
- while ( offsetParent && (!rroot.test(offsetParent.nodeName) && jQuery.css(offsetParent, "position") === "static") ) {
- offsetParent = offsetParent.offsetParent;
- }
- return offsetParent;
- });
- }
-});
-
-
-// Create scrollLeft and scrollTop methods
-jQuery.each( ["Left", "Top"], function( i, name ) {
- var method = "scroll" + name;
-
- jQuery.fn[ method ] = function(val) {
- var elem = this[0], win;
-
- if ( !elem ) {
- return null;
- }
-
- if ( val !== undefined ) {
- // Set the scroll offset
- return this.each(function() {
- win = getWindow( this );
-
- if ( win ) {
- win.scrollTo(
- !i ? val : jQuery(win).scrollLeft(),
- i ? val : jQuery(win).scrollTop()
- );
-
- } else {
- this[ method ] = val;
- }
- });
- } else {
- win = getWindow( elem );
-
- // Return the scroll offset
- return win ? ("pageXOffset" in win) ? win[ i ? "pageYOffset" : "pageXOffset" ] :
- jQuery.support.boxModel && win.document.documentElement[ method ] ||
- win.document.body[ method ] :
- elem[ method ];
- }
- };
-});
-
-function getWindow( elem ) {
- return jQuery.isWindow( elem ) ?
- elem :
- elem.nodeType === 9 ?
- elem.defaultView || elem.parentWindow :
- false;
-}
-
-
-
-
-// Create innerHeight, innerWidth, outerHeight and outerWidth methods
-jQuery.each([ "Height", "Width" ], function( i, name ) {
-
- var type = name.toLowerCase();
-
- // innerHeight and innerWidth
- jQuery.fn["inner" + name] = function() {
- return this[0] ?
- parseFloat( jQuery.css( this[0], type, "padding" ) ) :
- null;
- };
-
- // outerHeight and outerWidth
- jQuery.fn["outer" + name] = function( margin ) {
- return this[0] ?
- parseFloat( jQuery.css( this[0], type, margin ? "margin" : "border" ) ) :
- null;
- };
-
- jQuery.fn[ type ] = function( size ) {
- // Get window width or height
- var elem = this[0];
- if ( !elem ) {
- return size == null ? null : this;
- }
-
- if ( jQuery.isFunction( size ) ) {
- return this.each(function( i ) {
- var self = jQuery( this );
- self[ type ]( size.call( this, i, self[ type ]() ) );
- });
- }
-
- if ( jQuery.isWindow( elem ) ) {
- // Everyone else use document.documentElement or document.body depending on Quirks vs Standards mode
- return elem.document.compatMode === "CSS1Compat" && elem.document.documentElement[ "client" + name ] ||
- elem.document.body[ "client" + name ];
-
- // Get document width or height
- } else if ( elem.nodeType === 9 ) {
- // Either scroll[Width/Height] or offset[Width/Height], whichever is greater
- return Math.max(
- elem.documentElement["client" + name],
- elem.body["scroll" + name], elem.documentElement["scroll" + name],
- elem.body["offset" + name], elem.documentElement["offset" + name]
- );
-
- // Get or set width or height on the element
- } else if ( size === undefined ) {
- var orig = jQuery.css( elem, type ),
- ret = parseFloat( orig );
-
- return jQuery.isNaN( ret ) ? orig : ret;
-
- // Set the width or height on the element (default to pixels if value is unitless)
- } else {
- return this.css( type, typeof size === "string" ? size : size + "px" );
- }
- };
-
-});
-
-
-})(window);
diff --git a/frc971/http_status/www/lib/reconnecting-websocket.min.js b/frc971/http_status/www/lib/reconnecting-websocket.min.js
deleted file mode 100644
index f40b6c7..0000000
--- a/frc971/http_status/www/lib/reconnecting-websocket.min.js
+++ /dev/null
@@ -1,96 +0,0 @@
-// MIT License:
-//
-// Copyright (c) 2010-2012, Joe Walnes
-//
-// Permission is hereby granted, free of charge, to any person obtaining a copy
-// of this software and associated documentation files (the "Software"), to deal
-// in the Software without restriction, including without limitation the rights
-// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-// copies of the Software, and to permit persons to whom the Software is
-// furnished to do so, subject to the following conditions:
-//
-// The above copyright notice and this permission notice shall be included in
-// all copies or substantial portions of the Software.
-//
-// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
-// THE SOFTWARE.
-
-/**
- * This behaves like a WebSocket in every way, except if it fails to connect,
- * or it gets disconnected, it will repeatedly poll until it successfully connects
- * again.
- *
- * It is API compatible, so when you have:
- * ws = new WebSocket('ws://....');
- * you can replace with:
- * ws = new ReconnectingWebSocket('ws://....');
- *
- * The event stream will typically look like:
- * onconnecting
- * onopen
- * onmessage
- * onmessage
- * onclose // lost connection
- * onconnecting
- * onopen // sometime later...
- * onmessage
- * onmessage
- * etc...
- *
- * It is API compatible with the standard WebSocket API, apart from the following members:
- *
- * - `bufferedAmount`
- * - `extensions`
- * - `binaryType`
- *
- * Latest version: https://github.com/joewalnes/reconnecting-websocket/
- * - Joe Walnes
- *
- * Syntax
- * ======
- * var socket = new ReconnectingWebSocket(url, protocols, options);
- *
- * Parameters
- * ==========
- * url - The url you are connecting to.
- * protocols - Optional string or array of protocols.
- * options - See below
- *
- * Options
- * =======
- * Options can either be passed upon instantiation or set after instantiation:
- *
- * var socket = new ReconnectingWebSocket(url, null, { debug: true, reconnectInterval: 4000 });
- *
- * or
- *
- * var socket = new ReconnectingWebSocket(url);
- * socket.debug = true;
- * socket.reconnectInterval = 4000;
- *
- * debug
- * - Whether this instance should log debug messages. Accepts true or false. Default: false.
- *
- * automaticOpen
- * - Whether or not the websocket should attempt to connect immediately upon instantiation. The socket can be manually opened or closed at any time using ws.open() and ws.close().
- *
- * reconnectInterval
- * - The number of milliseconds to delay before attempting to reconnect. Accepts integer. Default: 1000.
- *
- * maxReconnectInterval
- * - The maximum number of milliseconds to delay a reconnection attempt. Accepts integer. Default: 30000.
- *
- * reconnectDecay
- * - The rate of increase of the reconnect delay. Allows reconnect attempts to back off when problems persist. Accepts integer or float. Default: 1.5.
- *
- * timeoutInterval
- * - The maximum time in milliseconds to wait for a connection to succeed before closing and retrying. Accepts integer. Default: 2000.
- *
- */
-
-!function(a,b){"function"==typeof define&&define.amd?define([],b):"undefined"!=typeof module&&module.exports?module.exports=b():a.ReconnectingWebSocket=b()}(this,function(){function a(b,c,d){function l(a,b){var c=document.createEvent("CustomEvent");return c.initCustomEvent(a,!1,!1,b),c}var e={debug:!1,automaticOpen:!0,reconnectInterval:1e3,maxReconnectInterval:3e4,reconnectDecay:1.5,timeoutInterval:2e3};d||(d={});for(var f in e)this[f]="undefined"!=typeof d[f]?d[f]:e[f];this.url=b,this.reconnectAttempts=0,this.readyState=WebSocket.CONNECTING,this.protocol=null;var h,g=this,i=!1,j=!1,k=document.createElement("div");k.addEventListener("open",function(a){g.onopen(a)}),k.addEventListener("close",function(a){g.onclose(a)}),k.addEventListener("connecting",function(a){g.onconnecting(a)}),k.addEventListener("message",function(a){g.onmessage(a)}),k.addEventListener("error",function(a){g.onerror(a)}),this.addEventListener=k.addEventListener.bind(k),this.removeEventListener=k.removeEventListener.bind(k),this.dispatchEvent=k.dispatchEvent.bind(k),this.open=function(b){h=new WebSocket(g.url,c||[]),b||k.dispatchEvent(l("connecting")),(g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","attempt-connect",g.url);var d=h,e=setTimeout(function(){(g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","connection-timeout",g.url),j=!0,d.close(),j=!1},g.timeoutInterval);h.onopen=function(){clearTimeout(e),(g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","onopen",g.url),g.protocol=h.protocol,g.readyState=WebSocket.OPEN,g.reconnectAttempts=0;var d=l("open");d.isReconnect=b,b=!1,k.dispatchEvent(d)},h.onclose=function(c){if(clearTimeout(e),h=null,i)g.readyState=WebSocket.CLOSED,k.dispatchEvent(l("close"));else{g.readyState=WebSocket.CONNECTING;var d=l("connecting");d.code=c.code,d.reason=c.reason,d.wasClean=c.wasClean,k.dispatchEvent(d),b||j||((g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","onclose",g.url),k.dispatchEvent(l("close")));var e=g.reconnectInterval*Math.pow(g.reconnectDecay,g.reconnectAttempts);setTimeout(function(){g.reconnectAttempts++,g.open(!0)},e>g.maxReconnectInterval?g.maxReconnectInterval:e)}},h.onmessage=function(b){(g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","onmessage",g.url,b.data);var c=l("message");c.data=b.data,k.dispatchEvent(c)},h.onerror=function(b){(g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","onerror",g.url,b),k.dispatchEvent(l("error"))}},1==this.automaticOpen&&this.open(!1),this.send=function(b){if(h)return(g.debug||a.debugAll)&&console.debug("ReconnectingWebSocket","send",g.url,b),h.send(b);throw"INVALID_STATE_ERR : Pausing to reconnect websocket"},this.close=function(a,b){"undefined"==typeof a&&(a=1e3),i=!0,h&&h.close(a,b)},this.refresh=function(){h&&h.close()}}return a.prototype.onopen=function(){},a.prototype.onclose=function(){},a.prototype.onconnecting=function(){},a.prototype.onmessage=function(){},a.prototype.onerror=function(){},a.debugAll=!1,a.CONNECTING=WebSocket.CONNECTING,a.OPEN=WebSocket.OPEN,a.CLOSING=WebSocket.CLOSING,a.CLOSED=WebSocket.CLOSED,a});
diff --git a/frc971/http_status/www_defaults/_404.png b/frc971/http_status/www_defaults/_404.png
deleted file mode 100644
index 8a43cb8..0000000
--- a/frc971/http_status/www_defaults/_404.png
+++ /dev/null
Binary files differ
diff --git a/frc971/http_status/www_defaults/_error.css b/frc971/http_status/www_defaults/_error.css
deleted file mode 100644
index 565d0a4..0000000
--- a/frc971/http_status/www_defaults/_error.css
+++ /dev/null
@@ -1,60 +0,0 @@
-/*
-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/frc971/http_status/www_defaults/_error.html b/frc971/http_status/www_defaults/_error.html
deleted file mode 100644
index e3d422d..0000000
--- a/frc971/http_status/www_defaults/_error.html
+++ /dev/null
@@ -1,42 +0,0 @@
-<!--
-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/frc971/http_status/www_defaults/_seasocks.css b/frc971/http_status/www_defaults/_seasocks.css
deleted file mode 100644
index 5f0b655..0000000
--- a/frc971/http_status/www_defaults/_seasocks.css
+++ /dev/null
@@ -1,49 +0,0 @@
-/*
-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/frc971/http_status/www_defaults/_stats.html b/frc971/http_status/www_defaults/_stats.html
deleted file mode 100644
index 2390334..0000000
--- a/frc971/http_status/www_defaults/_stats.html
+++ /dev/null
@@ -1,88 +0,0 @@
-<!--
-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/frc971/http_status/www_defaults/favicon.ico b/frc971/http_status/www_defaults/favicon.ico
deleted file mode 100644
index 30a95b9..0000000
--- a/frc971/http_status/www_defaults/favicon.ico
+++ /dev/null
Binary files differ
diff --git a/frc971/joystick_reader.cc b/frc971/joystick_reader.cc
deleted file mode 100644
index b8ad544..0000000
--- a/frc971/joystick_reader.cc
+++ /dev/null
@@ -1,549 +0,0 @@
-#include <stdio.h>
-#include <string.h>
-#include <unistd.h>
-#include <math.h>
-
-#include "aos/linux_code/init.h"
-#include "aos/prime/input/joystick_input.h"
-#include "aos/common/input/driver_station_data.h"
-#include "aos/common/logging/logging.h"
-#include "aos/common/util/log_interval.h"
-#include "aos/common/time.h"
-#include "aos/common/actions/actions.h"
-
-#include "frc971/control_loops/claw/claw.q.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "frc971/constants.h"
-#include "frc971/queues/gyro.q.h"
-#include "frc971/autonomous/auto.q.h"
-#include "frc971/actors/pickup_actor.h"
-#include "frc971/actors/stack_actor.h"
-#include "frc971/actors/score_actor.h"
-#include "frc971/actors/stack_and_lift_actor.h"
-#include "frc971/actors/stack_and_hold_actor.h"
-#include "frc971/actors/held_to_lift_actor.h"
-#include "frc971/actors/lift_actor.h"
-#include "frc971/actors/can_pickup_actor.h"
-#include "frc971/actors/horizontal_can_pickup_actor.h"
-
-using ::frc971::control_loops::claw_queue;
-using ::frc971::control_loops::drivetrain_queue;
-using ::frc971::control_loops::fridge_queue;
-using ::frc971::sensors::gyro_reading;
-
-using ::aos::input::driver_station::ButtonLocation;
-using ::aos::input::driver_station::POVLocation;
-using ::aos::input::driver_station::JoystickAxis;
-using ::aos::input::driver_station::ControlBit;
-
-namespace frc971 {
-namespace input {
-namespace joysticks {
-
-// Actions needed.
-
-// Human Player Station Intake Button
-// Claw open
-// Claw close
-// Claw down
-
-// Stack + Lift (together)
-// Place
-
-// Hold stack
-
-// Horizontal can pickup
-// Vertical can pickup
-
-// TODO(austin): Pull a lot of the constants below out up here so they can be
-// globally changed easier.
-
-// preset motion limits
-constexpr actors::ProfileParams kArmMove{0.5, 1.0};
-constexpr actors::ProfileParams kElevatorMove{0.3, 1.0};
-
-const JoystickAxis kSteeringWheel(1, 1), kDriveThrottle(2, 2);
-const ButtonLocation kShiftHigh(2, 1), kShiftLow(2, 3);
-const ButtonLocation kQuickTurn(1, 5);
-
-//const ButtonLocation kClawClosed(3, 5);
-//const ButtonLocation kFridgeClosed(3, 1);
-
-
-const ButtonLocation kStackAndHold(3, 5);
-const ButtonLocation kRollersIn(3, 2);
-const ButtonLocation kHorizontalCanRollersIn(4, 5);
-const ButtonLocation kClawToggle(4, 1);
-
-const POVLocation kElevatorCanUp(4, 0);
-
-// POV stick 3, 180
-const POVLocation kCanPickup(4, 180);
-const ButtonLocation kToteChute(4, 6);
-const ButtonLocation kStackAndLift(4, 7);
-
-// Pull in the 6th tote.
-//const ButtonLocation kSixthTote(4, 10);
-const ButtonLocation kCanUp(4, 10);
-
-const ButtonLocation kHeldToLift(4, 11);
-const ButtonLocation kPickup(4, 9);
-
-const ButtonLocation kStack(4, 2);
-
-// Move the fridge out with the stack in preparation for scoring.
-const ButtonLocation kScore(4, 8);
-const ButtonLocation kCoopTop(3, 8);
-const ButtonLocation kCoopTopRetract(3, 7);
-const ButtonLocation kCoopBottom(3, 6);
-const ButtonLocation kCoopBottomRetract(4, 12);
-
-const ButtonLocation kCanReset(3, 9);
-
-const POVLocation kFridgeToggle(4, 270);
-const ButtonLocation kSpit(4, 3);
-
-// Set stack down in the bot.
-const POVLocation kSetStackDownAndHold(4, 90);
-
-const double kClawTotePackAngle = 0.90;
-const double kArmRaiseLowerClearance = -0.08;
-const double kClawStackClearance = 0.55;
-const double kHorizontalCanClawAngle = 0.12;
-
-const double kStackUpHeight = 0.60;
-const double kStackUpArm = 0.0;
-
-class Reader : public ::aos::input::JoystickInput {
- public:
- Reader() : was_running_(false) {}
-
- static actors::ScoreParams MakeScoreParams() {
- actors::ScoreParams r;
- r.move_the_stack = r.place_the_stack = true;
- r.upper_move_height = 0.14;
- r.begin_horizontal_move_height = 0.13;
- r.horizontal_move_target = -0.7;
- r.horizontal_start_lowering = -0.65;
- r.home_lift_horizontal_start_position = -0.60;
- r.place_height = -0.10;
- r.home_return_height = 0.05;
- return r;
- }
-
- static actors::ScoreParams MakeCoopTopParams(bool place_the_stack) {
- actors::ScoreParams r;
- r.move_the_stack = !place_the_stack;
- r.place_the_stack = place_the_stack;
- r.upper_move_height = 0.52;
- r.begin_horizontal_move_height = 0.5;
- r.horizontal_move_target = -0.48;
- r.horizontal_start_lowering = r.horizontal_move_target;
- r.home_lift_horizontal_start_position = -0.3;
- r.place_height = 0.35;
- r.home_return_height = 0.1;
- return r;
- }
-
- static actors::ScoreParams MakeCoopBottomParams(bool place_the_stack) {
- actors::ScoreParams r;
- r.move_the_stack = !place_the_stack;
- r.place_the_stack = place_the_stack;
- r.upper_move_height = 0.17;
- r.begin_horizontal_move_height = 0.16;
- r.horizontal_move_target = -0.7;
- r.horizontal_start_lowering = r.horizontal_move_target;
- r.home_lift_horizontal_start_position = -0.3;
- r.place_height = 0.0;
- r.home_return_height = 0.1;
- return r;
- }
-
- virtual void RunIteration(const ::aos::input::driver_station::Data &data) {
- bool last_auto_running = auto_running_;
- auto_running_ = data.GetControlBit(ControlBit::kAutonomous) &&
- data.GetControlBit(ControlBit::kEnabled);
- if (auto_running_ != last_auto_running) {
- if (auto_running_) {
- StartAuto();
- } else {
- StopAuto();
- }
- }
-
- if (!data.GetControlBit(ControlBit::kAutonomous)) {
- HandleDrivetrain(data);
- HandleTeleop(data);
- }
- }
-
- void HandleDrivetrain(const ::aos::input::driver_station::Data &data) {
- const double wheel = -data.GetAxis(kSteeringWheel);
- const double throttle = -data.GetAxis(kDriveThrottle);
-
- if (!drivetrain_queue.goal.MakeWithBuilder()
- .steering(wheel)
- .throttle(throttle)
- .quickturn(data.IsPressed(kQuickTurn))
- .control_loop_driving(false)
- .Send()) {
- LOG(WARNING, "sending stick values failed\n");
- }
- }
-
- void HandleTeleop(const ::aos::input::driver_station::Data &data) {
- double intake_power = 0.0;
- if (!data.GetControlBit(ControlBit::kEnabled)) {
- action_queue_.CancelAllActions();
- LOG(DEBUG, "Canceling\n");
- }
-
- if (data.IsPressed(kRollersIn)) {
- intake_power = 10.0;
- claw_goal_ = 0.0;
- }
- if (data.IsPressed(kHorizontalCanRollersIn)) {
- intake_power = 10.0;
- claw_goal_ = kHorizontalCanClawAngle;
- }
- if (data.IsPressed(kSpit)) {
- intake_power = -12.0;
- action_queue_.CancelAllActions();
- }
-
- // Toggle button for the claw
- if (data.PosEdge(kClawToggle)) {
- claw_rollers_closed_ = !claw_rollers_closed_;
- }
-
- /*
- if (data.IsPressed(kClawClosed)) {
- claw_rollers_closed_ = true;
- }
- */
-
- // Horizontal can pickup.
- if (data.PosEdge(kElevatorCanUp)) {
- actors::HorizontalCanPickupParams params;
- params.elevator_height = 0.3;
- params.pickup_angle = 0.80 + kHorizontalCanClawAngle;
- params.spit_time = 0.01;
- params.spit_power = -8.0;
-
- params.suck_time = 0.10;
- params.suck_power = 10.0;
-
- params.claw_settle_time = 0.05;
- params.claw_settle_power = 5.0;
- params.claw_full_lift_angle = 1.35;
- params.claw_end_angle = 0.5;
-
- // End low so we don't drop it.
- params.elevator_end_height = 0.28;
- params.arm_end_angle = 0.0;
- action_queue_.EnqueueAction(
- actors::MakeHorizontalCanPickupAction(params));
- fridge_closed_ = true;
- }
-
- // -0.942503 arm, 0.374752 elevator
- // Vertical can pickup.
- if (data.PosEdge(kCanPickup)) {
- actors::CanPickupParams params;
- params.pickup_x = 0.6;
- params.pickup_y = 0.1;
- params.lift_height = 0.25;
- params.pickup_goal_before_move_height = 0.3;
- params.start_lowering_x = 0.1;
- // End low so the can is supported.
- params.before_place_height = 0.4;
- params.end_height = 0.28;
- params.end_angle = 0.0;
- action_queue_.EnqueueAction(actors::MakeCanPickupAction(params));
- fridge_closed_ = true;
- }
-
- if (data.PosEdge(kCanReset)) {
- action_queue_.CancelAllActions();
- elevator_goal_ = 0.28;
- arm_goal_ = 0.0;
- }
-
- // Tote chute pull in when button is pressed, pack when done.
- if (data.IsPressed(kToteChute)) {
- claw_goal_ = 0.8;
- intake_power = 6.0;
- }
- if (data.NegEdge(kToteChute)) {
- claw_goal_ = kClawTotePackAngle;
- }
-
- if (data.PosEdge(kStackAndLift)) {
- actors::StackAndLiftParams params;
- params.stack_params.claw_out_angle = kClawTotePackAngle;
- params.stack_params.bottom = 0.020;
- params.stack_params.over_box_before_place_height = 0.39;
- params.stack_params.arm_clearance = kArmRaiseLowerClearance;
-
- params.grab_after_stack = true;
- params.clamp_pause_time = 0.0;
- params.lift_params.lift_height = kStackUpHeight;
- params.lift_params.lift_arm = kStackUpArm;
- params.lift_params.second_lift = false;
- params.grab_after_lift = true;
- fridge_closed_ = true;
-
- action_queue_.EnqueueAction(actors::MakeStackAndLiftAction(params));
- }
-
- if (data.PosEdge(kStackAndHold) || data.PosEdge(kSetStackDownAndHold)) {
- actors::StackAndHoldParams params;
- params.bottom = 0.020;
- params.over_box_before_place_height = 0.39;
-
- params.arm_clearance = kArmRaiseLowerClearance;
- params.clamp_pause_time = 0.25;
- params.claw_clamp_angle = kClawTotePackAngle;
-
- params.hold_height = 0.68;
- params.claw_out_angle = kClawTotePackAngle;
-
- if (data.PosEdge(kSetStackDownAndHold)) {
- params.place_not_stack = true;
- params.clamp_pause_time = 0.1;
- //params.claw_clamp_angle = kClawTotePackAngle - 0.5;
- } else {
- params.place_not_stack = false;
- }
-
- action_queue_.EnqueueAction(actors::MakeStackAndHoldAction(params));
- fridge_closed_ = true;
- }
-
- // TODO(austin): Figure out what action needed to pull the 6th tote into the
- // claw.
-
- // Lower the fridge from holding the stack, grab the stack, and then lift.
- if (data.PosEdge(kHeldToLift)) {
- actors::HeldToLiftParams params;
- params.arm_clearance = kArmRaiseLowerClearance;
- params.clamp_pause_time = 0.1;
- params.before_lift_settle_time = 0.1;
- params.bottom_height = 0.020;
- params.claw_out_angle = kClawStackClearance;
- params.lift_params.lift_height = kStackUpHeight;
- params.lift_params.lift_arm = kStackUpArm;
- params.lift_params.second_lift = false;
- fridge_closed_ = true;
-
- action_queue_.EnqueueAction(actors::MakeHeldToLiftAction(params));
- }
-
- // Lift the can up.
- if (data.PosEdge(kCanUp)) {
- actors::LiftParams params;
- params.lift_height = 0.68;
- params.lift_arm = 0.3;
- params.pack_claw = false;
- params.pack_claw_angle = 0;
- params.intermediate_lift_height = 0.37;
- params.second_lift = true;
- fridge_closed_ = true;
-
- action_queue_.EnqueueAction(actors::MakeLiftAction(params));
- }
-
- // Pick up a tote from the ground and put it in the bottom of the bot.
- if (data.PosEdge(kPickup)) {
- actors::PickupParams params;
- // TODO(austin): These parameters are coppied into auto right now, need
- // to dedup...
-
- // Lift to here initially.
- params.pickup_angle = 0.9;
- // Start sucking here
- params.suck_angle = 0.8;
- // Go back down to here to finish sucking.
- params.suck_angle_finish = 0.4;
- // Pack the box back in here.
- params.pickup_finish_angle = kClawTotePackAngle;
- params.intake_time = 0.8;
- params.intake_voltage = 7.0;
- action_queue_.EnqueueAction(actors::MakePickupAction(params));
- }
-
- // Place stack on a tote in the tray, and grab it.
- if (data.PosEdge(kStack)) {
- actors::StackParams params;
- params.claw_out_angle = kClawTotePackAngle;
- params.bottom = 0.020;
- params.only_place = false;
- params.arm_clearance = kArmRaiseLowerClearance;
- params.over_box_before_place_height = 0.39;
- action_queue_.EnqueueAction(actors::MakeStackAction(params));
- claw_rollers_closed_ = true;
- fridge_closed_ = true;
- }
-
- if (data.PosEdge(kScore)) {
- action_queue_.EnqueueAction(
- actors::MakeScoreAction(MakeScoreParams()));
- fridge_closed_ = false;
- }
-
- if (data.PosEdge(kCoopTop)) {
- action_queue_.EnqueueAction(
- actors::MakeScoreAction(MakeCoopTopParams(false)));
- }
- if (data.PosEdge(kCoopTopRetract)) {
- action_queue_.EnqueueAction(
- actors::MakeScoreAction(MakeCoopTopParams(true)));
- fridge_closed_ = false;
- }
-
- if (data.PosEdge(kCoopBottom)) {
- action_queue_.EnqueueAction(
- actors::MakeScoreAction(MakeCoopBottomParams(false)));
- }
- if (data.PosEdge(kCoopBottomRetract)) {
- action_queue_.EnqueueAction(
- actors::MakeScoreAction(MakeCoopBottomParams(true)));
- fridge_closed_ = false;
- }
-
- if (data.PosEdge(kFridgeToggle)) {
- fridge_closed_ = !fridge_closed_;
- }
-
- if (data.PosEdge(ControlBit::kEnabled)) {
- // If we got enabled, wait for everything to zero.
- LOG(INFO, "Waiting for zero.\n");
- waiting_for_zero_ = true;
- }
-
- claw_queue.status.FetchLatest();
- fridge_queue.status.FetchLatest();
- if (!claw_queue.status.get()) {
- LOG(ERROR, "Got no claw status packet.\n");
- }
- if (!fridge_queue.status.get()) {
- LOG(ERROR, "Got no fridge status packet.\n");
- }
-
- if (claw_queue.status.get() && fridge_queue.status.get() &&
- claw_queue.status->zeroed && fridge_queue.status->zeroed) {
- if (waiting_for_zero_) {
- LOG(INFO, "Zeroed! Starting teleop mode.\n");
- waiting_for_zero_ = false;
-
- // Set the initial goals to where we are now.
- elevator_goal_ = 0.3;
- arm_goal_ = 0.0;
- claw_goal_ = 0.6;
- }
- } else {
- waiting_for_zero_ = true;
- }
-
- if (!waiting_for_zero_) {
- if (!action_queue_.Running()) {
- auto new_fridge_goal = fridge_queue.goal.MakeMessage();
- new_fridge_goal->max_velocity = elevator_params_.velocity;
- new_fridge_goal->max_acceleration = elevator_params_.acceleration;
- new_fridge_goal->profiling_type = 0;
- new_fridge_goal->height = elevator_goal_;
- new_fridge_goal->velocity = 0.0;
- new_fridge_goal->max_angular_velocity = arm_params_.velocity;
- new_fridge_goal->max_angular_acceleration = arm_params_.acceleration;
- new_fridge_goal->angle = arm_goal_;
- new_fridge_goal->angular_velocity = 0.0;
- new_fridge_goal->grabbers.top_front = fridge_closed_;
- new_fridge_goal->grabbers.top_back = fridge_closed_;
- new_fridge_goal->grabbers.bottom_front = fridge_closed_;
- new_fridge_goal->grabbers.bottom_back = fridge_closed_;
-
- if (!new_fridge_goal.Send()) {
- LOG(ERROR, "Sending fridge goal failed.\n");
- } else {
- LOG(DEBUG, "sending goals: elevator: %f, arm: %f\n", elevator_goal_,
- arm_goal_);
- }
- if (!claw_queue.goal.MakeWithBuilder()
- .angle(claw_goal_)
- .rollers_closed(claw_rollers_closed_)
- .max_velocity(5.0)
- .max_acceleration(6.0)
- .intake(intake_power)
- .Send()) {
- LOG(ERROR, "Sending claw goal failed.\n");
- }
- }
- }
-
- if (action_queue_.Running()) {
- // If we are running an action, update our goals to the current goals.
- control_loops::fridge_queue.status.FetchLatest();
- if (control_loops::fridge_queue.status.get()) {
- arm_goal_ = control_loops::fridge_queue.status->goal_angle;
- elevator_goal_ = control_loops::fridge_queue.status->goal_height;
- } else {
- LOG(ERROR, "No fridge status!\n");
- }
-
- // If we are running an action, update our goals to the current goals.
- control_loops::claw_queue.status.FetchLatest();
- if (control_loops::claw_queue.status.get()) {
- claw_goal_ = control_loops::claw_queue.status->goal_angle;
- } else {
- LOG(ERROR, "No claw status!\n");
- }
- }
- action_queue_.Tick();
- was_running_ = action_queue_.Running();
- }
-
- private:
- void StartAuto() {
- LOG(INFO, "Starting auto mode\n");
- ::frc971::autonomous::autonomous.MakeWithBuilder().run_auto(true).Send();
- }
-
- void StopAuto() {
- LOG(INFO, "Stopping auto mode\n");
- ::frc971::autonomous::autonomous.MakeWithBuilder().run_auto(false).Send();
- }
-
- bool was_running_;
-
- // Previous goals for systems.
- double elevator_goal_ = 0.2;
- double arm_goal_ = 0.0;
- double claw_goal_ = 0.0;
- bool claw_rollers_closed_ = false;
- bool fridge_closed_ = false;
- actors::ProfileParams arm_params_ = kArmMove;
- actors::ProfileParams elevator_params_ = kElevatorMove;
-
- // If we're waiting for the subsystems to zero.
- bool waiting_for_zero_ = true;
-
- bool auto_running_ = false;
-
- ::aos::common::actions::ActionQueue action_queue_;
-
- ::aos::util::SimpleLogInterval no_drivetrain_status_ =
- ::aos::util::SimpleLogInterval(::aos::time::Time::InSeconds(0.2), WARNING,
- "no drivetrain status");
-};
-
-} // namespace joysticks
-} // namespace input
-} // namespace frc971
-
-int main() {
- ::aos::Init();
- ::frc971::input::joysticks::Reader reader;
- reader.Run();
- ::aos::Cleanup();
-}
diff --git a/frc971/prime/build.sh b/frc971/prime/build.sh
deleted file mode 100755
index fe48451..0000000
--- a/frc971/prime/build.sh
+++ /dev/null
@@ -1,5 +0,0 @@
-#!/bin/bash
-
-cd $(dirname $0)
-
-exec ../../aos/build/build.py $0 prime prime.gyp "$@"
diff --git a/frc971/prime/compile_loop.sh b/frc971/prime/compile_loop.sh
deleted file mode 100755
index de6b0d3..0000000
--- a/frc971/prime/compile_loop.sh
+++ /dev/null
@@ -1,16 +0,0 @@
-#!/bin/bash
-
-# Runs `build.sh all` and then waits for a file to be modified in a loop.
-# Useful for making changes to the code while continuously making sure they
-# compile.
-# Requires the util-linux and inotify-tools packages.
-
-chrt -i -p 0 $$
-ionice -c 3 -p $$
-
-while true; do
- $(dirname $0)/build.sh all
- echo 'compile_loop.sh: Waiting for a file modification...' 1>&2
- inotifywait -e close_write -r aos frc971 bbb_cape
- echo 'compile_loop.sh: Done waiting for a file modification' 1>&2
-done
diff --git a/frc971/prime/prime.gyp b/frc971/prime/prime.gyp
deleted file mode 100644
index 88a37ba..0000000
--- a/frc971/prime/prime.gyp
+++ /dev/null
@@ -1,44 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'All',
- 'type': 'none',
- 'dependencies': [
- '<(AOS)/build/aos_all.gyp:Prime',
-
- '../control_loops/control_loops.gyp:state_feedback_loop_test',
- '../control_loops/control_loops.gyp:position_sensor_sim_test',
- '../control_loops/drivetrain/drivetrain.gyp:drivetrain',
- '../control_loops/drivetrain/drivetrain.gyp:drivetrain_lib_test',
- '../control_loops/drivetrain/drivetrain.gyp:replay_drivetrain',
- '../control_loops/fridge/fridge.gyp:fridge',
- '../control_loops/fridge/fridge.gyp:fridge_lib_test',
- '../control_loops/fridge/fridge.gyp:replay_fridge',
- '../control_loops/claw/claw.gyp:claw',
- '../control_loops/claw/claw.gyp:claw_lib_test',
- '../control_loops/claw/claw.gyp:replay_claw',
- '../autonomous/autonomous.gyp:auto',
- '../frc971.gyp:joystick_reader',
- '../zeroing/zeroing.gyp:zeroing_test',
- '../http_status/http_status.gyp:http_status',
- '../control_loops/voltage_cap/voltage_cap.gyp:voltage_cap_test',
- '../actors/actors.gyp:binaries',
- ],
- 'copies': [
- {
- 'destination': '<(rsync_dir)',
- 'files': [
- 'start_list.txt',
- ],
- },
- ],
- 'conditions': [
- ['ARCHITECTURE=="arm_frc"', {
- 'dependencies': [
- '../wpilib/wpilib.gyp:wpilib_interface',
- ],
- }],
- ],
- },
- ],
-}
diff --git a/frc971/prime/start_list.txt b/frc971/prime/start_list.txt
deleted file mode 100644
index e4f0a8a..0000000
--- a/frc971/prime/start_list.txt
+++ /dev/null
@@ -1,18 +0,0 @@
-can_pickup_action
-joystick_reader
-pickup_action
-score_action
-stack_action
-wpilib_interface
-binary_log_writer
-claw
-fridge
-horizontal_can_pickup_action
-lift_action
-stack_and_lift_action
-stack_and_hold_action
-held_to_lift_action
-drivetrain
-auto
-drivetrain_action
-http_status
diff --git a/frc971/vision/CameraServer.cc b/frc971/vision/CameraServer.cc
deleted file mode 100644
index 35b16b4..0000000
--- a/frc971/vision/CameraServer.cc
+++ /dev/null
@@ -1,82 +0,0 @@
-#include <string.h>
-
-#include "aos/linux_code/output/HTTPServer.h"
-#include "aos/linux_code/output/evhttp_ctemplate_emitter.h"
-#include "aos/linux_code/output/ctemplate_cache.h"
-#include "ctemplate/template.h"
-#include "aos/linux_code/init.h"
-#include "aos/common/logging/logging.h"
-#include "aos/linux_code/configuration.h"
-
-#include "frc971/constants.h"
-
-RegisterTemplateFilename(ROBOT_HTML, "robot.html.tpl");
-
-namespace frc971 {
-
-class CameraServer : public aos::http::HTTPServer {
- public:
- CameraServer() : HTTPServer(::aos::configuration::GetRootDirectory(), 8080),
- buf_(NULL) {
- AddPage<CameraServer>("/robot.html", &CameraServer::RobotHTML, this);
- }
-
- private:
- evbuffer *buf_;
- bool Setup(evhttp_request *request, const char *content_type) {
- if (evhttp_add_header(evhttp_request_get_output_headers(request),
- "Content-Type", content_type) == -1) {
- LOG(WARNING, "adding Content-Type failed\n");
- evhttp_send_error(request, HTTP_INTERNAL, NULL);
- return false;
- }
- if (buf_ == NULL) buf_ = evbuffer_new();
- if (buf_ == NULL) {
- LOG(WARNING, "evbuffer_new() failed\n");
- evhttp_send_error(request, HTTP_INTERNAL, NULL);
- return false;
- }
- return true;
- }
- void RobotHTML(evhttp_request *request) {
- if (!Setup(request, "text/html")) return;
-
- ctemplate::TemplateDictionary dict(ROBOT_HTML);
- const char *host = evhttp_find_header(
- evhttp_request_get_input_headers(request), "Host");
- if (host == NULL) {
- evhttp_send_error(request, HTTP_BADREQUEST, "no Host header");
- return;
- }
- const char *separator = strchrnul(host, ':');
- size_t length = separator - host;
- // Don't include the last ':' (or the terminating '\0') or anything else
- // after it.
- dict.SetValue("HOST", ctemplate::TemplateString(host, length));
-
- dict.SetIntValue("CENTER", constants::GetValues().camera_center);
-
- aos::http::EvhttpCtemplateEmitter emitter(buf_);
- if (!aos::http::get_template_cache()->
- ExpandWithData(ROBOT_HTML, ctemplate::STRIP_WHITESPACE,
- &dict, NULL, &emitter)) {
- LOG(ERROR, "expanding the template failed\n");
- evhttp_send_error(request, HTTP_INTERNAL, NULL);
- return;
- }
- if (emitter.error()) {
- evhttp_send_error(request, HTTP_INTERNAL, NULL);
- return;
- }
- evhttp_send_reply(request, HTTP_OK, NULL, buf_);
- }
-};
-
-} // namespace frc971
-
-int main() {
- ::aos::InitNRT();
- ::frc971::CameraServer server;
- server.Run();
- ::aos::Cleanup();
-}
diff --git a/frc971/vision/robot.html.tpl b/frc971/vision/robot.html.tpl
deleted file mode 100644
index 7ae51a6..0000000
--- a/frc971/vision/robot.html.tpl
+++ /dev/null
@@ -1,56 +0,0 @@
-<!DOCTYPE HTML>
-<html>
- <head>
- <title>971 Camera Code: Robot Stream</title>
- <style type="text/css">
- #body {
- display: block;
- margin: 0px;
- margin-top: 0px;
- margin-right: 0px;
- margin-bottom: 0px;
- margin-left: 0px;
- }
- #img {
- position: absolute;
- left: 50%;
- top: 0%;
- margin: 0 0 0 -320px;
- }
- #center {
- left: 50%;
- position: absolute;
- width: 2px;
- height: 100%;
- background-color: red;
- }
- #middle {
- top: 240px;
- margin-top: -1px;
- width: 100%;
- position: absolute;
- height: 2px;
- background-color: red;
- }
- #footer {
- top: 482px;
- left: 10px;
- position: absolute;
- }
- #center {
- margin-left: {{CENTER}}px;
- }
- </style>
- </head>
- <body id="body">
- <img id="img" src="http://{{HOST}}:9714" />
- <div id="center"></div>
- <div id="middle"></div>
- <div id="footer">
- <!--<form>
- <input type="button" value="Camera Controls"
- onclick="window.open('control.htm', 'Camera_Controls')">
- </form>-->
- </div>
- </body>
-</html>
diff --git a/frc971/vision/vision.gyp b/frc971/vision/vision.gyp
deleted file mode 100644
index b5cf558..0000000
--- a/frc971/vision/vision.gyp
+++ /dev/null
@@ -1,26 +0,0 @@
-{
- 'targets': [
- {
- 'target_name': 'CameraServer',
- 'type': 'executable',
- 'sources': [
- 'CameraServer.cc',
- ],
- 'dependencies': [
- '<(AOS)/linux_code/output/output.gyp:http_server',
- '../frc971.gyp:constants',
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/build/aos.gyp:logging',
- '<(AOS)/linux_code/linux_code.gyp:configuration',
- ],
- 'copies': [
- {
- 'destination': '<(rsync_dir)',
- 'files': [
- 'robot.html.tpl',
- ],
- },
- ],
- },
- ],
-}
diff --git a/frc971/wpilib/wpilib.gyp b/frc971/wpilib/wpilib.gyp
index 3422782..997b810 100644
--- a/frc971/wpilib/wpilib.gyp
+++ b/frc971/wpilib/wpilib.gyp
@@ -1,40 +1,6 @@
{
'targets': [
{
- 'target_name': 'wpilib_interface',
- 'type': 'executable',
- 'sources': [
- 'wpilib_interface.cc'
- ],
- 'dependencies': [
- '<(AOS)/linux_code/linux_code.gyp:init',
- '<(AOS)/common/common.gyp:stl_mutex',
- '<(AOS)/build/aos.gyp:logging',
- '<(EXTERNALS):WPILib',
- '<(DEPTH)/frc971/frc971.gyp:constants',
- '<(DEPTH)/frc971/control_loops/drivetrain/drivetrain.gyp:drivetrain_queue',
- '<(DEPTH)/frc971/control_loops/fridge/fridge.gyp:fridge_queue',
- '<(DEPTH)/frc971/control_loops/claw/claw.gyp:claw_queue',
- '<(AOS)/common/controls/controls.gyp:control_loop',
- '<(AOS)/common/util/util.gyp:log_interval',
- '<(AOS)/common/common.gyp:time',
- '<(AOS)/common/logging/logging.gyp:queue_logging',
- '<(AOS)/common/messages/messages.gyp:robot_state',
- '<(AOS)/common/util/util.gyp:phased_loop',
- '<(AOS)/common/messages/messages.gyp:robot_state',
- 'hall_effect',
- 'joystick_sender',
- 'loop_output_handler',
- 'buffered_pcm',
- 'gyro_sender',
- 'dma_edge_counting',
- 'interrupt_edge_counting',
- 'encoder_and_potentiometer',
- '<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
- 'logging_queue',
- ],
- },
- {
'target_name': 'logging_queue',
'type': 'static_library',
'sources': [
diff --git a/frc971/wpilib/wpilib_interface.cc b/frc971/wpilib/wpilib_interface.cc
deleted file mode 100644
index 25da16a..0000000
--- a/frc971/wpilib/wpilib_interface.cc
+++ /dev/null
@@ -1,716 +0,0 @@
-#include <stdio.h>
-#include <string.h>
-#include <unistd.h>
-#include <inttypes.h>
-
-#include <thread>
-#include <mutex>
-#include <functional>
-
-#include "aos/common/logging/logging.h"
-#include "aos/common/logging/queue_logging.h"
-#include "aos/common/time.h"
-#include "aos/common/util/log_interval.h"
-#include "aos/common/util/phased_loop.h"
-#include "aos/common/util/wrapping_counter.h"
-#include "aos/common/stl_mutex.h"
-#include "aos/linux_code/init.h"
-#include "aos/common/messages/robot_state.q.h"
-
-#include "frc971/constants.h"
-#include "frc971/control_loops/control_loops.q.h"
-#include "frc971/control_loops/drivetrain/drivetrain.q.h"
-#include "frc971/control_loops/fridge/fridge.q.h"
-#include "frc971/control_loops/claw/claw.q.h"
-
-#include "frc971/wpilib/hall_effect.h"
-#include "frc971/wpilib/joystick_sender.h"
-#include "frc971/wpilib/loop_output_handler.h"
-#include "frc971/wpilib/buffered_solenoid.h"
-#include "frc971/wpilib/buffered_pcm.h"
-#include "frc971/wpilib/gyro_sender.h"
-#include "frc971/wpilib/dma_edge_counting.h"
-#include "frc971/wpilib/interrupt_edge_counting.h"
-#include "frc971/wpilib/encoder_and_potentiometer.h"
-#include "frc971/wpilib/logging.q.h"
-
-#include "Encoder.h"
-#include "Talon.h"
-#include "DriverStation.h"
-#include "AnalogInput.h"
-#include "Compressor.h"
-#include "Relay.h"
-#include "RobotBase.h"
-#include "dma.h"
-#include "ControllerPower.h"
-
-#ifndef M_PI
-#define M_PI 3.14159265358979323846
-#endif
-
-using ::aos::util::SimpleLogInterval;
-using ::frc971::control_loops::drivetrain_queue;
-using ::frc971::control_loops::fridge_queue;
-using ::frc971::control_loops::claw_queue;
-
-namespace frc971 {
-namespace wpilib {
-
-double drivetrain_translate(int32_t in) {
- return static_cast<double>(in) /
- (256.0 /*cpr*/ * 4.0 /*4x*/) *
- constants::GetValues().drivetrain_encoder_ratio *
- (4 /*wheel diameter*/ * 2.54 / 100.0 * M_PI);
-}
-
-double arm_translate(int32_t in) {
- return -static_cast<double>(in) /
- (512.0 /*cpr*/ * 4.0 /*4x*/) *
- constants::GetValues().arm_encoder_ratio *
- (2 * M_PI /*radians*/);
-}
-
-double arm_potentiometer_translate(double voltage) {
- return voltage *
- constants::GetValues().arm_pot_ratio *
- (5.0 /*turns*/ / 5.0 /*volts*/) *
- (2 * M_PI /*radians*/);
-}
-
-double elevator_translate(int32_t in) {
- return static_cast<double>(in) /
- (512.0 /*cpr*/ * 4.0 /*4x*/) *
- constants::GetValues().elev_encoder_ratio *
- (2 * M_PI /*radians*/) *
- constants::GetValues().elev_distance_per_radian;
-}
-
-double elevator_potentiometer_translate(double voltage) {
- return -voltage *
- constants::GetValues().elev_pot_ratio *
- (2 * M_PI /*radians*/) *
- constants::GetValues().elev_distance_per_radian *
- (5.0 /*turns*/ / 5.0 /*volts*/);
-}
-
-double claw_translate(int32_t in) {
- return static_cast<double>(in) /
- (512.0 /*cpr*/ * 4.0 /*4x*/) *
- constants::GetValues().claw_encoder_ratio *
- (2 * M_PI /*radians*/);
-}
-
-double claw_potentiometer_translate(double voltage) {
- return -voltage *
- constants::GetValues().claw_pot_ratio *
- (5.0 /*turns*/ / 5.0 /*volts*/) *
- (2 * M_PI /*radians*/);
-}
-
-static const double kMaximumEncoderPulsesPerSecond =
- 19500.0 /* free speed RPM */ * 12.0 / 56.0 /* belt reduction */ /
- 60.0 /* seconds / minute */ * 256.0 /* CPR */ *
- 4.0 /* index pulse = 1/4 cycle */;
-
-class SensorReader {
- public:
- SensorReader() {
- // Set it to filter out anything shorter than 1/4 of the minimum pulse width
- // we should ever see.
- filter_.SetPeriodNanoSeconds(
- static_cast<int>(1 / 4.0 / kMaximumEncoderPulsesPerSecond * 1e9 + 0.5));
- }
-
- void set_arm_left_encoder(::std::unique_ptr<Encoder> encoder) {
- filter_.Add(encoder.get());
- arm_left_encoder_.set_encoder(::std::move(encoder));
- }
-
- void set_arm_left_index(::std::unique_ptr<DigitalSource> index) {
- filter_.Add(index.get());
- arm_left_encoder_.set_index(::std::move(index));
- }
-
- void set_arm_left_potentiometer(
- ::std::unique_ptr<AnalogInput> potentiometer) {
- arm_left_encoder_.set_potentiometer(::std::move(potentiometer));
- }
-
- void set_arm_right_encoder(::std::unique_ptr<Encoder> encoder) {
- filter_.Add(encoder.get());
- arm_right_encoder_.set_encoder(::std::move(encoder));
- }
-
- void set_arm_right_index(::std::unique_ptr<DigitalSource> index) {
- filter_.Add(index.get());
- arm_right_encoder_.set_index(::std::move(index));
- }
-
- void set_arm_right_potentiometer(
- ::std::unique_ptr<AnalogInput> potentiometer) {
- arm_right_encoder_.set_potentiometer(::std::move(potentiometer));
- }
-
- void set_elevator_left_encoder(::std::unique_ptr<Encoder> encoder) {
- filter_.Add(encoder.get());
- elevator_left_encoder_.set_encoder(::std::move(encoder));
- }
-
- void set_elevator_left_index(::std::unique_ptr<DigitalSource> index) {
- filter_.Add(index.get());
- elevator_left_encoder_.set_index(::std::move(index));
- }
-
- void set_elevator_left_potentiometer(
- ::std::unique_ptr<AnalogInput> potentiometer) {
- elevator_left_encoder_.set_potentiometer(::std::move(potentiometer));
- }
-
- void set_elevator_right_encoder(::std::unique_ptr<Encoder> encoder) {
- filter_.Add(encoder.get());
- elevator_right_encoder_.set_encoder(::std::move(encoder));
- }
-
- void set_elevator_right_index(::std::unique_ptr<DigitalSource> index) {
- filter_.Add(index.get());
- elevator_right_encoder_.set_index(::std::move(index));
- }
-
- void set_elevator_right_potentiometer(
- ::std::unique_ptr<AnalogInput> potentiometer) {
- elevator_right_encoder_.set_potentiometer(::std::move(potentiometer));
- }
-
- void set_wrist_encoder(::std::unique_ptr<Encoder> encoder) {
- filter_.Add(encoder.get());
- wrist_encoder_.set_encoder(::std::move(encoder));
- }
-
- void set_wrist_index(::std::unique_ptr<DigitalSource> index) {
- filter_.Add(index.get());
- wrist_encoder_.set_index(::std::move(index));
- }
-
- void set_wrist_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
- wrist_encoder_.set_potentiometer(::std::move(potentiometer));
- }
-
- void set_left_encoder(::std::unique_ptr<Encoder> left_encoder) {
- left_encoder_ = ::std::move(left_encoder);
- }
-
- void set_right_encoder(::std::unique_ptr<Encoder> right_encoder) {
- right_encoder_ = ::std::move(right_encoder);
- }
-
- // All of the DMA-related set_* calls must be made before this, and it doesn't
- // hurt to do all of them.
- void set_dma(::std::unique_ptr<DMA> dma) {
- dma_synchronizer_.reset(new DMASynchronizer(::std::move(dma)));
- dma_synchronizer_->Add(&arm_left_encoder_);
- dma_synchronizer_->Add(&elevator_left_encoder_);
- dma_synchronizer_->Add(&arm_right_encoder_);
- dma_synchronizer_->Add(&elevator_right_encoder_);
- }
-
- void operator()() {
- LOG(INFO, "In sensor reader thread\n");
- ::aos::SetCurrentThreadName("SensorReader");
-
- my_pid_ = getpid();
- ds_ = DriverStation::GetInstance();
-
- wrist_encoder_.Start();
- dma_synchronizer_->Start();
- LOG(INFO, "Things are now started\n");
-
- ::aos::SetCurrentThreadRealtimePriority(kPriority);
- while (run_) {
- ::aos::time::PhasedLoopXMS(5, 4000);
- RunIteration();
- }
-
- wrist_encoder_.Stop();
- }
-
- void RunIteration() {
- {
- auto new_state = ::aos::robot_state.MakeMessage();
-
- new_state->reader_pid = my_pid_;
- new_state->outputs_enabled = ds_->IsSysActive();
- new_state->browned_out = ds_->IsSysBrownedOut();
-
- new_state->is_3v3_active = ControllerPower::GetEnabled3V3();
- new_state->is_5v_active = ControllerPower::GetEnabled5V();
- new_state->voltage_3v3 = ControllerPower::GetVoltage3V3();
- new_state->voltage_5v = ControllerPower::GetVoltage5V();
-
- new_state->voltage_roborio_in = ControllerPower::GetInputVoltage();
- new_state->voltage_battery = ds_->GetBatteryVoltage();
-
- LOG_STRUCT(DEBUG, "robot_state", *new_state);
-
- new_state.Send();
- }
-
- {
- auto drivetrain_message = drivetrain_queue.position.MakeMessage();
- drivetrain_message->right_encoder =
- -drivetrain_translate(right_encoder_->GetRaw());
- drivetrain_message->left_encoder =
- drivetrain_translate(left_encoder_->GetRaw());
-
- drivetrain_message.Send();
- }
-
- dma_synchronizer_->RunIteration();
-
- const auto &values = constants::GetValues();
-
- {
- auto fridge_message = fridge_queue.position.MakeMessage();
- CopyPotAndIndexPosition(arm_left_encoder_, &fridge_message->arm.left,
- arm_translate, arm_potentiometer_translate, false,
- values.fridge.left_arm_potentiometer_offset);
- CopyPotAndIndexPosition(
- arm_right_encoder_, &fridge_message->arm.right, arm_translate,
- arm_potentiometer_translate, true,
- values.fridge.right_arm_potentiometer_offset);
- CopyPotAndIndexPosition(
- elevator_left_encoder_, &fridge_message->elevator.left,
- elevator_translate, elevator_potentiometer_translate, false,
- values.fridge.left_elevator_potentiometer_offset);
- CopyPotAndIndexPosition(
- elevator_right_encoder_, &fridge_message->elevator.right,
- elevator_translate, elevator_potentiometer_translate, true,
- values.fridge.right_elevator_potentiometer_offset);
- fridge_message.Send();
- }
-
- {
- auto claw_message = claw_queue.position.MakeMessage();
- CopyPotAndIndexPosition(wrist_encoder_, &claw_message->joint,
- claw_translate, claw_potentiometer_translate,
- false, values.claw.potentiometer_offset);
- claw_message.Send();
- }
- }
-
- void Quit() { run_ = false; }
-
- private:
- static const int kPriority = 30;
- static const int kInterruptPriority = 55;
-
- int32_t my_pid_;
- DriverStation *ds_;
-
- void CopyPotAndIndexPosition(
- const DMAEncoderAndPotentiometer &encoder, PotAndIndexPosition *position,
- ::std::function<double(int32_t)> encoder_translate,
- ::std::function<double(double)> potentiometer_translate, bool reverse,
- double potentiometer_offset) {
- const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.polled_encoder_value());
- position->pot = multiplier * potentiometer_translate(
- encoder.polled_potentiometer_voltage()) +
- potentiometer_offset;
- position->latched_encoder =
- multiplier * encoder_translate(encoder.last_encoder_value());
- position->latched_pot =
- multiplier *
- potentiometer_translate(encoder.last_potentiometer_voltage()) +
- potentiometer_offset;
- position->index_pulses = encoder.index_posedge_count();
- }
-
- void CopyPotAndIndexPosition(
- const InterruptEncoderAndPotentiometer &encoder,
- PotAndIndexPosition *position,
- ::std::function<double(int32_t)> encoder_translate,
- ::std::function<double(double)> potentiometer_translate, bool reverse,
- double potentiometer_offset) {
- const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.encoder()->GetRaw());
- position->pot = multiplier * potentiometer_translate(
- encoder.potentiometer()->GetVoltage()) +
- potentiometer_offset;
- position->latched_encoder =
- multiplier * encoder_translate(encoder.last_encoder_value());
- position->latched_pot =
- multiplier *
- potentiometer_translate(encoder.last_potentiometer_voltage()) +
- potentiometer_offset;
- position->index_pulses = encoder.index_posedge_count();
- }
-
- ::std::unique_ptr<DMASynchronizer> dma_synchronizer_;
-
- DMAEncoderAndPotentiometer arm_left_encoder_, arm_right_encoder_,
- elevator_left_encoder_, elevator_right_encoder_;
-
- InterruptEncoderAndPotentiometer wrist_encoder_{kInterruptPriority};
-
- ::std::unique_ptr<Encoder> left_encoder_;
- ::std::unique_ptr<Encoder> right_encoder_;
-
- ::std::atomic<bool> run_{true};
- DigitalGlitchFilter filter_;
-};
-
-class SolenoidWriter {
- public:
- SolenoidWriter(const ::std::unique_ptr<BufferedPcm> &pcm)
- : pcm_(pcm),
- fridge_(".frc971.control_loops.fridge_queue.output"),
- claw_(".frc971.control_loops.claw_queue.output") {}
-
- void set_pressure_switch(::std::unique_ptr<DigitalSource> pressure_switch) {
- pressure_switch_ = ::std::move(pressure_switch);
- }
-
- void set_compressor_relay(::std::unique_ptr<Relay> compressor_relay) {
- compressor_relay_ = ::std::move(compressor_relay);
- }
-
- void set_fridge_grabbers_top_front(::std::unique_ptr<BufferedSolenoid> s) {
- fridge_grabbers_top_front_ = ::std::move(s);
- }
-
- void set_fridge_grabbers_top_back(::std::unique_ptr<BufferedSolenoid> s) {
- fridge_grabbers_top_back_ = ::std::move(s);
- }
-
- void set_fridge_grabbers_bottom_front(
- ::std::unique_ptr<BufferedSolenoid> s) {
- fridge_grabbers_bottom_front_ = ::std::move(s);
- }
-
- void set_fridge_grabbers_bottom_back(
- ::std::unique_ptr<BufferedSolenoid> s) {
- fridge_grabbers_bottom_back_ = ::std::move(s);
- }
-
- void set_claw_pinchers(::std::unique_ptr<BufferedSolenoid> s) {
- claw_pinchers_ = ::std::move(s);
- }
-
- void set_grabber_latch_release(::std::unique_ptr<BufferedSolenoid> s) {
- grabber_latch_release_ = ::std::move(s);
- }
-
- void set_grabber_fold_up(::std::unique_ptr<BufferedSolenoid> s) {
- grabber_fold_up_ = ::std::move(s);
- }
-
- void operator()() {
- ::aos::SetCurrentThreadName("Solenoids");
- ::aos::SetCurrentThreadRealtimePriority(30);
-
- while (run_) {
- ::aos::time::PhasedLoopXMS(20, 1000);
-
- {
- fridge_.FetchLatest();
- if (fridge_.get()) {
- LOG_STRUCT(DEBUG, "solenoids", *fridge_);
- fridge_grabbers_top_front_->Set(!fridge_->grabbers.top_front);
- fridge_grabbers_top_back_->Set(!fridge_->grabbers.top_back);
- fridge_grabbers_bottom_front_->Set(!fridge_->grabbers.bottom_front);
- fridge_grabbers_bottom_back_->Set(!fridge_->grabbers.bottom_back);
- }
- }
-
- {
- claw_.FetchLatest();
- if (claw_.get()) {
- LOG_STRUCT(DEBUG, "solenoids", *claw_);
- claw_pinchers_->Set(claw_->rollers_closed);
- }
- }
-
- ::aos::joystick_state.FetchLatest();
- grabber_latch_release_->Set(::aos::joystick_state.get() != nullptr &&
- ::aos::joystick_state->autonomous);
- grabber_fold_up_->Set(::aos::joystick_state.get() != nullptr &&
- ::aos::joystick_state->joysticks[1].buttons & 1);
-
- {
- PneumaticsToLog to_log;
- {
- const bool compressor_on = !pressure_switch_->Get();
- to_log.compressor_on = compressor_on;
- if (compressor_on) {
- compressor_relay_->Set(Relay::kForward);
- } else {
- compressor_relay_->Set(Relay::kOff);
- }
- }
-
- pcm_->Flush();
- to_log.read_solenoids = pcm_->GetAll();
- LOG_STRUCT(DEBUG, "pneumatics info", to_log);
- }
- }
- }
-
- void Quit() { run_ = false; }
-
- private:
- const ::std::unique_ptr<BufferedPcm> &pcm_;
- ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_top_front_;
- ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_top_back_;
- ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_bottom_front_;
- ::std::unique_ptr<BufferedSolenoid> fridge_grabbers_bottom_back_;
- ::std::unique_ptr<BufferedSolenoid> claw_pinchers_;
- ::std::unique_ptr<BufferedSolenoid> grabber_latch_release_;
- ::std::unique_ptr<BufferedSolenoid> grabber_fold_up_;
- ::std::unique_ptr<DigitalSource> pressure_switch_;
- ::std::unique_ptr<Relay> compressor_relay_;
-
- ::aos::Queue<::frc971::control_loops::FridgeQueue::Output> fridge_;
- ::aos::Queue<::frc971::control_loops::ClawQueue::Output> claw_;
-
- ::std::atomic<bool> run_{true};
-};
-
-class DrivetrainWriter : public LoopOutputHandler {
- public:
- void set_left_drivetrain_talon(::std::unique_ptr<Talon> t) {
- left_drivetrain_talon_ = ::std::move(t);
- }
-
- void set_right_drivetrain_talon(::std::unique_ptr<Talon> t) {
- right_drivetrain_talon_ = ::std::move(t);
- }
-
- private:
- virtual void Read() override {
- ::frc971::control_loops::drivetrain_queue.output.FetchAnother();
- }
-
- virtual void Write() override {
- auto &queue = ::frc971::control_loops::drivetrain_queue.output;
- LOG_STRUCT(DEBUG, "will output", *queue);
- left_drivetrain_talon_->Set(queue->left_voltage / 12.0);
- right_drivetrain_talon_->Set(-queue->right_voltage / 12.0);
- }
-
- virtual void Stop() override {
- LOG(WARNING, "drivetrain output too old\n");
- left_drivetrain_talon_->Disable();
- right_drivetrain_talon_->Disable();
- }
-
- ::std::unique_ptr<Talon> left_drivetrain_talon_;
- ::std::unique_ptr<Talon> right_drivetrain_talon_;
-};
-
-class FridgeWriter : public LoopOutputHandler {
- public:
- void set_left_arm_talon(::std::unique_ptr<Talon> t) {
- left_arm_talon_ = ::std::move(t);
- }
-
- void set_right_arm_talon(::std::unique_ptr<Talon> t) {
- right_arm_talon_ = ::std::move(t);
- }
-
- void set_left_elevator_talon(::std::unique_ptr<Talon> t) {
- left_elevator_talon_ = ::std::move(t);
- }
-
- void set_right_elevator_talon(::std::unique_ptr<Talon> t) {
- right_elevator_talon_ = ::std::move(t);
- }
-
- private:
- virtual void Read() override {
- ::frc971::control_loops::fridge_queue.output.FetchAnother();
- }
-
- virtual void Write() override {
- auto &queue = ::frc971::control_loops::fridge_queue.output;
- LOG_STRUCT(DEBUG, "will output", *queue);
- left_arm_talon_->Set(queue->left_arm / 12.0);
- right_arm_talon_->Set(-queue->right_arm / 12.0);
- left_elevator_talon_->Set(queue->left_elevator / 12.0);
- right_elevator_talon_->Set(-queue->right_elevator / 12.0);
- }
-
- virtual void Stop() override {
- LOG(WARNING, "Fridge output too old.\n");
- left_arm_talon_->Disable();
- right_arm_talon_->Disable();
- left_elevator_talon_->Disable();
- right_elevator_talon_->Disable();
- }
-
- ::std::unique_ptr<Talon> left_arm_talon_;
- ::std::unique_ptr<Talon> right_arm_talon_;
- ::std::unique_ptr<Talon> left_elevator_talon_;
- ::std::unique_ptr<Talon> right_elevator_talon_;
-};
-
-class ClawWriter : public LoopOutputHandler {
- public:
- void set_left_intake_talon(::std::unique_ptr<Talon> t) {
- left_intake_talon_ = ::std::move(t);
- }
-
- void set_right_intake_talon(::std::unique_ptr<Talon> t) {
- right_intake_talon_ = ::std::move(t);
- }
-
- void set_wrist_talon(::std::unique_ptr<Talon> t) {
- wrist_talon_ = ::std::move(t);
- }
-
- private:
- virtual void Read() override {
- ::frc971::control_loops::claw_queue.output.FetchAnother();
- }
-
- virtual void Write() override {
- auto &queue = ::frc971::control_loops::claw_queue.output;
- LOG_STRUCT(DEBUG, "will output", *queue);
- left_intake_talon_->Set(queue->intake_voltage / 12.0);
- right_intake_talon_->Set(-queue->intake_voltage / 12.0);
- wrist_talon_->Set(-queue->voltage / 12.0);
- }
-
- virtual void Stop() override {
- LOG(WARNING, "Claw output too old.\n");
- left_intake_talon_->Disable();
- right_intake_talon_->Disable();
- wrist_talon_->Disable();
- }
-
- ::std::unique_ptr<Talon> left_intake_talon_;
- ::std::unique_ptr<Talon> right_intake_talon_;
- ::std::unique_ptr<Talon> wrist_talon_;
-};
-
-// TODO(brian): Replace this with ::std::make_unique once all our toolchains
-// have support.
-template <class T, class... U>
-std::unique_ptr<T> make_unique(U &&... u) {
- return std::unique_ptr<T>(new T(std::forward<U>(u)...));
-}
-
-class WPILibRobot : public RobotBase {
- public:
- ::std::unique_ptr<Encoder> encoder(int index) {
- return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
- Encoder::k4X);
- }
- virtual void StartCompetition() {
- ::aos::InitNRT();
- ::aos::SetCurrentThreadName("StartCompetition");
-
- JoystickSender joystick_sender;
- ::std::thread joystick_thread(::std::ref(joystick_sender));
- // TODO(austin): Compressor needs to use a spike.
-
- SensorReader reader;
- LOG(INFO, "Creating the reader\n");
- reader.set_arm_left_encoder(encoder(1));
- reader.set_arm_left_index(make_unique<DigitalInput>(1));
- reader.set_arm_left_potentiometer(make_unique<AnalogInput>(1));
-
- reader.set_arm_right_encoder(encoder(5));
- reader.set_arm_right_index(make_unique<DigitalInput>(5));
- reader.set_arm_right_potentiometer(make_unique<AnalogInput>(5));
-
- reader.set_elevator_left_encoder(encoder(0));
- reader.set_elevator_left_index(make_unique<DigitalInput>(0));
- reader.set_elevator_left_potentiometer(make_unique<AnalogInput>(0));
-
- reader.set_elevator_right_encoder(encoder(4));
- reader.set_elevator_right_index(make_unique<DigitalInput>(4));
- reader.set_elevator_right_potentiometer(make_unique<AnalogInput>(4));
-
- reader.set_wrist_encoder(encoder(6));
- reader.set_wrist_index(make_unique<DigitalInput>(6));
- reader.set_wrist_potentiometer(make_unique<AnalogInput>(6));
-
- reader.set_left_encoder(encoder(2));
- reader.set_right_encoder(encoder(3));
- reader.set_dma(make_unique<DMA>());
- ::std::thread reader_thread(::std::ref(reader));
- GyroSender gyro_sender;
- ::std::thread gyro_thread(::std::ref(gyro_sender));
-
- DrivetrainWriter drivetrain_writer;
- drivetrain_writer.set_left_drivetrain_talon(
- ::std::unique_ptr<Talon>(new Talon(8)));
- drivetrain_writer.set_right_drivetrain_talon(
- ::std::unique_ptr<Talon>(new Talon(0)));
- ::std::thread drivetrain_writer_thread(::std::ref(drivetrain_writer));
-
- // TODO(sensors): Get real PWM output and relay numbers for the fridge and
- // claw.
- FridgeWriter fridge_writer;
- fridge_writer.set_left_arm_talon(
- ::std::unique_ptr<Talon>(new Talon(6)));
- fridge_writer.set_right_arm_talon(
- ::std::unique_ptr<Talon>(new Talon(2)));
- fridge_writer.set_left_elevator_talon(
- ::std::unique_ptr<Talon>(new Talon(7)));
- fridge_writer.set_right_elevator_talon(
- ::std::unique_ptr<Talon>(new Talon(1)));
- ::std::thread fridge_writer_thread(::std::ref(fridge_writer));
-
- ClawWriter claw_writer;
- claw_writer.set_left_intake_talon(
- ::std::unique_ptr<Talon>(new Talon(5)));
- claw_writer.set_right_intake_talon(
- ::std::unique_ptr<Talon>(new Talon(3)));
- claw_writer.set_wrist_talon(
- ::std::unique_ptr<Talon>(new Talon(4)));
- ::std::thread claw_writer_thread(::std::ref(claw_writer));
-
- ::std::unique_ptr<::frc971::wpilib::BufferedPcm> pcm(
- new ::frc971::wpilib::BufferedPcm());
- SolenoidWriter solenoid_writer(pcm);
- solenoid_writer.set_fridge_grabbers_top_front(pcm->MakeSolenoid(0));
- solenoid_writer.set_fridge_grabbers_top_back(pcm->MakeSolenoid(0));
- solenoid_writer.set_fridge_grabbers_bottom_front(pcm->MakeSolenoid(2));
- solenoid_writer.set_fridge_grabbers_bottom_back(pcm->MakeSolenoid(1));
- solenoid_writer.set_claw_pinchers(pcm->MakeSolenoid(4));
- solenoid_writer.set_grabber_latch_release(pcm->MakeSolenoid(7));
- solenoid_writer.set_grabber_fold_up(pcm->MakeSolenoid(5));
-
- solenoid_writer.set_pressure_switch(make_unique<DigitalInput>(9));
- solenoid_writer.set_compressor_relay(make_unique<Relay>(0));
- ::std::thread solenoid_thread(::std::ref(solenoid_writer));
-
- // Wait forever. Not much else to do...
- PCHECK(select(0, nullptr, nullptr, nullptr, nullptr));
-
- LOG(ERROR, "Exiting WPILibRobot\n");
-
- joystick_sender.Quit();
- joystick_thread.join();
- reader.Quit();
- reader_thread.join();
- gyro_sender.Quit();
- gyro_thread.join();
-
- drivetrain_writer.Quit();
- drivetrain_writer_thread.join();
- solenoid_writer.Quit();
- solenoid_thread.join();
-
- ::aos::Cleanup();
- }
-};
-
-} // namespace wpilib
-} // namespace frc971
-
-
-START_ROBOT_CLASS(::frc971::wpilib::WPILibRobot);
diff --git a/frc971/zeroing/zeroing.cc b/frc971/zeroing/zeroing.cc
index d8c77e8..e54446a 100644
--- a/frc971/zeroing/zeroing.cc
+++ b/frc971/zeroing/zeroing.cc
@@ -1,6 +1,6 @@
#include "frc971/zeroing/zeroing.h"
-#include <math.h>
+#include <cmath>
#include <vector>
namespace frc971 {
@@ -14,7 +14,7 @@
}
ZeroingEstimator::ZeroingEstimator(
- const constants::Values::ZeroingConstants& constants) {
+ const constants::ZeroingConstants& constants) {
index_diff_ = constants.index_difference;
max_sample_count_ = constants.average_filter_size;
known_index_pos_ = constants.measured_index_position;
diff --git a/frc971/zeroing/zeroing.gyp b/frc971/zeroing/zeroing.gyp
index a868e19..0a7a2fc 100644
--- a/frc971/zeroing/zeroing.gyp
+++ b/frc971/zeroing/zeroing.gyp
@@ -8,10 +8,8 @@
],
'dependencies': [
'<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
- '<(DEPTH)/frc971/frc971.gyp:constants',
],
'export_dependent_settings': [
- '<(DEPTH)/frc971/frc971.gyp:constants',
'<(DEPTH)/frc971/control_loops/control_loops.gyp:queues',
],
},
diff --git a/frc971/zeroing/zeroing.h b/frc971/zeroing/zeroing.h
index 08911ac..4176f48 100644
--- a/frc971/zeroing/zeroing.h
+++ b/frc971/zeroing/zeroing.h
@@ -23,7 +23,7 @@
// the pot and the indices.
class ZeroingEstimator {
public:
- ZeroingEstimator(const constants::Values::ZeroingConstants &constants);
+ ZeroingEstimator(const constants::ZeroingConstants &constants);
// Update the internal logic with the next sensor values.
void UpdateEstimate(const PotAndIndexPosition &info);
diff --git a/frc971/zeroing/zeroing_test.cc b/frc971/zeroing/zeroing_test.cc
index 404b0e0..4a82e04 100644
--- a/frc971/zeroing/zeroing_test.cc
+++ b/frc971/zeroing/zeroing_test.cc
@@ -16,7 +16,7 @@
namespace zeroing {
using control_loops::PositionSensorSimulator;
-using constants::Values;
+using constants::ZeroingConstants;
static const size_t kSampleSize = 30;
static const double kAcceptableUnzeroedError = 0.2;
@@ -41,7 +41,7 @@
const double index_diff = 1.0;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.6 * index_diff, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
// The zeroing code is supposed to perform some filtering on the difference
@@ -65,7 +65,7 @@
double position = 3.6 * index_diff;
PositionSensorSimulator sim(index_diff);
sim.Initialize(position, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
// Make sure that the zeroing code does not consider itself zeroed until we
@@ -84,7 +84,7 @@
double index_diff = 1.0;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.6, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
// The zeroing code is supposed to perform some filtering on the difference
@@ -117,7 +117,7 @@
double index_diff = 0.89;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.5 * index_diff, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
// The zeroing code is supposed to perform some filtering on the difference
@@ -151,7 +151,7 @@
double index_diff = 0.89;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.5 * index_diff, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
for (unsigned int i = 0; i < kSampleSize / 2; i++) {
@@ -164,7 +164,7 @@
double index_diff = 0.89;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.1 * index_diff, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
MoveTo(&sim, &estimator, 3.1 * index_diff);
@@ -180,7 +180,7 @@
double index_diff = 0.6;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.1 * index_diff, index_diff / 3.0);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
// Make sure to fill up the averaging filter with samples.
@@ -215,7 +215,7 @@
const double known_index_pos = 3.5 * index_diff;
PositionSensorSimulator sim(index_diff);
sim.Initialize(3.3 * index_diff, index_diff / 3.0, known_index_pos);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, known_index_pos, kIndexErrorFraction});
// Make sure to fill up the averaging filter with samples.
@@ -240,7 +240,7 @@
TEST_F(ZeroingTest, BasicErrorAPITest) {
const double index_diff = 1.0;
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
kSampleSize, index_diff, 0.0, kIndexErrorFraction});
PositionSensorSimulator sim(index_diff);
sim.Initialize(1.5 * index_diff, index_diff / 3.0, 0.0);
@@ -276,7 +276,7 @@
int sample_size = 30;
PositionSensorSimulator sim(index_diff);
sim.Initialize(10 * index_diff, index_diff / 3.0, known_index_pos);
- ZeroingEstimator estimator(Values::ZeroingConstants{
+ ZeroingEstimator estimator(ZeroingConstants{
sample_size, index_diff, known_index_pos, kIndexErrorFraction});
for (int i = 0; i < sample_size; i++) {