From e99de206779724df0e6ee82d21a83debed53b53a Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 28 Jan 2020 18:26:35 -0600 Subject: [PATCH 01/31] Made new files for auton and pathfinder --- src/Autonomous/Actions/PathFinder.cpp | 0 src/Autonomous/Actions/PathFinder.h | 0 src/Autonomous/TestAuton.cpp | 0 src/Autonomous/TestAuton.h | 0 4 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 src/Autonomous/Actions/PathFinder.cpp create mode 100644 src/Autonomous/Actions/PathFinder.h create mode 100644 src/Autonomous/TestAuton.cpp create mode 100644 src/Autonomous/TestAuton.h diff --git a/src/Autonomous/Actions/PathFinder.cpp b/src/Autonomous/Actions/PathFinder.cpp new file mode 100644 index 0000000..e69de29 diff --git a/src/Autonomous/Actions/PathFinder.h b/src/Autonomous/Actions/PathFinder.h new file mode 100644 index 0000000..e69de29 diff --git a/src/Autonomous/TestAuton.cpp b/src/Autonomous/TestAuton.cpp new file mode 100644 index 0000000..e69de29 diff --git a/src/Autonomous/TestAuton.h b/src/Autonomous/TestAuton.h new file mode 100644 index 0000000..e69de29 From d842d4f002ac92d7339ce3371732ac1356440efb Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 28 Jan 2020 19:10:56 -0600 Subject: [PATCH 02/31] Changes --- src/Autonomous/Actions/PathFinder.h | 12 ++++++++++++ src/DriveSubsystem.cpp | 17 ++++++++++++++++- src/DriveSubsystem.h | 7 ++++++- 3 files changed, 34 insertions(+), 2 deletions(-) diff --git a/src/Autonomous/Actions/PathFinder.h b/src/Autonomous/Actions/PathFinder.h index e69de29..c292be5 100644 --- a/src/Autonomous/Actions/PathFinder.h +++ b/src/Autonomous/Actions/PathFinder.h @@ -0,0 +1,12 @@ +#include +#include +#include +#include + +wpi::SmallString<64> deployDirectory; +frc::filesystem::GetDeployDirectory(deployDirectory); +wpi::sys::path::append(deployDirectory, "paths"); +wpi::sys::path::append(deployDirectory, "YourPath.wpilib.json"); + +frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); + diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 9b10657..f6d17b4 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -3,7 +3,7 @@ #include "Robot.h" DriveSubsystem::DriveSubsystem() : - m_pursuit(0, 0, .1, Path(), false, 0), + m_odometry(), m_lookAhead("Path Lookahead", 24.0), m_driveTurnkP("Drive Turn P Value", .05), m_leftMaster(LEFT_FRONT_PORT), @@ -127,4 +127,19 @@ void DriveSubsystem::toggleGear() { m_leftDriveShifter.Set(DoubleSolenoid::kReverse); m_highGear = true; } +} + +void DriveSubsystem::resetEncoders() { + m_leftMaster.SetSelectedSensorPosition(0); + m_leftSlave.SetSelectedSensorPosition(0); + m_rightMaster.SetSelectedSensorPosition(0); + m_rightSlave.SetSelectedSensorPosition(0); +} + +void DriveSubsystem::resetOdometry(Pose2d pose) { + +} + +Pose2d DriveSubsystem::getPose() { + return m_odometry.GetPose(); } \ No newline at end of file diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 05a5a81..53817db 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -8,6 +8,8 @@ #include #include +#include +#include #include "WaypointFollower/WaypointFollower.h" #include "COREUtilities/CORETimer.h" @@ -29,7 +31,10 @@ class DriveSubsystem : public CORESubsystem, public CORETask { void setMotorSpeed(double leftPercent, double rightPercent); void fillCompressor(); void toggleGear(); - AdaptivePursuit m_pursuit; + void resetEncoders(); + void resetOdometry(Pose2d pose); + Pose2d getPose(); + m_odometry = Rotation2d(units::degree_t(GetHeading())); COREConstant m_lookAhead, m_driveTurnkP; COREVector path; TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; From 472e8d2fb69164b7d7348f4639a0ef229c5417fa Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 28 Jan 2020 20:41:51 -0600 Subject: [PATCH 03/31] Added files for using pathfinder --- src/Constants.h | 64 +++++++++++++++++++++++++++++ src/DriveSubsystem.cpp | 25 +++++++++++- src/DriveSubsystem.h | 14 +++++-- src/RobotContainer.cpp | 91 ++++++++++++++++++++++++++++++++++++++++++ src/RobotContainer.h | 53 ++++++++++++++++++++++++ 5 files changed, 242 insertions(+), 5 deletions(-) create mode 100644 src/Constants.h create mode 100644 src/RobotContainer.cpp create mode 100644 src/RobotContainer.h diff --git a/src/Constants.h b/src/Constants.h new file mode 100644 index 0000000..32488de --- /dev/null +++ b/src/Constants.h @@ -0,0 +1,64 @@ +#include +#include +#include +#include + +#pragma once + +/** + * The Constants header provides a convenient place for teams to hold robot-wide + * numerical or bool constants. This should not be used for any other purpose. + * + * It is generally a good idea to place constants into subsystem- or + * command-specific namespaces within this header, which can then be used where + * they are needed. + */ + +namespace DriveConstants { +constexpr int kLeftMotor1Port = 0; +constexpr int kLeftMotor2Port = 1; +constexpr int kRightMotor1Port = 2; +constexpr int kRightMotor2Port = 3; + +constexpr int kLeftEncoderPorts[]{0, 1}; +constexpr int kRightEncoderPorts[]{2, 3}; +constexpr bool kLeftEncoderReversed = false; +constexpr bool kRightEncoderReversed = true; + +constexpr auto kTrackwidth = 0.69_m; +extern const frc::DifferentialDriveKinematics kDriveKinematics; + +constexpr int kEncoderCPR = 1024; +constexpr double kWheelDiameterInches = 6; +constexpr double kEncoderDistancePerPulse = + // Assumes the encoders are directly mounted on the wheel shafts + (kWheelDiameterInches * wpi::math::pi) / static_cast(kEncoderCPR); + +constexpr bool kGyroReversed = true; + +// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT! +// These characterization values MUST be determined either experimentally or +// theoretically for *your* robot's drive. The Robot Characterization +// Toolsuite provides a convenient tool for obtaining these values for your +// robot. +constexpr auto ks = 0.22_V; +constexpr auto kv = 1.98 * 1_V * 1_s / 1_m; +constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m; + +// Example value only - as above, this must be tuned for your drive! +constexpr double kPDriveVel = 8.5; +} // namespace DriveConstants + +namespace AutoConstants { +constexpr auto kMaxSpeed = 3_mps; +constexpr auto kMaxAcceleration = 3_mps_sq; + +// Reasonable baseline values for a RAMSETE follower in units of meters and +// seconds +constexpr double kRamseteB = 2; +constexpr double kRamseteZeta = 0.7; +} // namespace AutoConstants + +namespace OIConstants { +constexpr int kDriverControllerPort = 1; +} // namespace OIConstants \ No newline at end of file diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index f6d17b4..e22cf6b 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -33,6 +33,16 @@ void DriveSubsystem::robotInit() { // resetTracker(Position2d(Translation2d(), Rotation2d())); } +void DriveSubsystem::autonInit() { + +} + +void DriveSubsystem::auton() { + m_odometry.Update(frc::Rotation2d(units::degree_t(getHeading())), + units::meter_t(m_leftMaster.GetSelectedSensorPosition(0)), + units::meter_t(m_rightMaster.GetSelectedSensorPosition(0))); +} + void DriveSubsystem::teleopInit() { COREEtherDrive::setAB(m_etherAValue.Get(), m_etherBValue.Get()); COREEtherDrive::setQuickturn(m_etherQuickTurnValue.Get()); @@ -142,4 +152,17 @@ void DriveSubsystem::resetOdometry(Pose2d pose) { Pose2d DriveSubsystem::getPose() { return m_odometry.GetPose(); -} \ No newline at end of file +} + +double DriveSubsystem::getHeading() { + return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0); +} + +double DriveSubsystem::getTurnRate() { + return m_gyro.GetRate() * (kGyroReversed ? -1.0 : 1.0); +} + +double DriveSubsystem::getAverageEncoderDistance() { + return m_leftMaster.GetSelectedSensorPosition(0) + m_rightMaster.GetSelectedSensorPosition(0) / 2.0; +} + diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 53817db..0f332b1 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -10,8 +10,7 @@ #include #include #include -#include "WaypointFollower/WaypointFollower.h" -#include "COREUtilities/CORETimer.h" +#include enum class DriveSide{LEFT = 1, RIGHT = 2, BOTH = 3}; @@ -21,6 +20,8 @@ class DriveSubsystem : public CORESubsystem, public CORETask { void robotInit() override; void teleopInit() override; void teleop() override; + void autonInit() override; + void auton(); void teleopEnd() override; void preLoopTask() override; @@ -34,7 +35,12 @@ class DriveSubsystem : public CORESubsystem, public CORETask { void resetEncoders(); void resetOdometry(Pose2d pose); Pose2d getPose(); - m_odometry = Rotation2d(units::degree_t(GetHeading())); + double getHeading(); + double getTurnRate(); + void setMaxOutput(double maxOutput); + double getAverageEncoderDistance(); + + m_odometry = Rotation2d(units::degree_t(getHeading())); COREConstant m_lookAhead, m_driveTurnkP; COREVector path; TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; @@ -46,6 +52,6 @@ class DriveSubsystem : public CORESubsystem, public CORETask { bool m_highGear; double m_wheelbase = 20.8; double m_trackwidth = 25.881; - AHRS *m_gyro; + AHRS m_gyro; int count = 0; }; \ No newline at end of file diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp new file mode 100644 index 0000000..e40e422 --- /dev/null +++ b/src/RobotContainer.cpp @@ -0,0 +1,91 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +#include "RobotContainer.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "Constants.h" + +RobotContainer::RobotContainer() { + // Initialize all of your commands and subsystems here + + // Configure the button bindings + ConfigureButtonBindings(); + + // Set up default drive command + m_drive.SetDefaultCommand(frc2::RunCommand( + [this] { + m_drive.ArcadeDrive( + m_driverController.GetY(frc::GenericHID::kLeftHand), + m_driverController.GetX(frc::GenericHID::kRightHand)); + }, + {&m_drive})); +} + +void RobotContainer::ConfigureButtonBindings() { + // Configure your button bindings here + + // While holding the shoulder button, drive at half speed + frc2::JoystickButton(&m_driverController, 6) + .WhenPressed(&m_driveHalfSpeed) + .WhenReleased(&m_driveFullSpeed); +} + +frc2::Command* RobotContainer::GetAutonomousCommand() { + // Create a voltage constraint to ensure we don't accelerate too fast + frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( + frc::SimpleMotorFeedforward( + DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), + DriveConstants::kDriveKinematics, 10_V); + + // Set up config for trajectory + frc::TrajectoryConfig config(AutoConstants::kMaxSpeed, + AutoConstants::kMaxAcceleration); + // Add kinematics to ensure max speed is actually obeyed + config.SetKinematics(DriveConstants::kDriveKinematics); + // Apply the voltage constraint + config.AddConstraint(autoVoltageConstraint); + + // An example trajectory to follow. All units in meters. + auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory( + // Start at the origin facing the +X direction + frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)), + // Pass through these two interior waypoints, making an 's' curve path + {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)}, + // End 3 meters straight ahead of where we started, facing forward + frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)), + // Pass the config + config); + + frc2::RamseteCommand ramseteCommand( + exampleTrajectory, [this]() { return m_drive.GetPose(); }, + frc::RamseteController(AutoConstants::kRamseteB, + AutoConstants::kRamseteZeta), + frc::SimpleMotorFeedforward( + DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), + DriveConstants::kDriveKinematics, + [this] { return m_drive.GetWheelSpeeds(); }, + frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), + frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), + [this](auto left, auto right) { m_drive.TankDriveVolts(left, right); }, + {&m_drive}); + + // no auto + return new frc2::SequentialCommandGroup( + std::move(ramseteCommand), + frc2::InstantCommand([this] { m_drive.TankDriveVolts(0_V, 0_V); }, {})); +} \ No newline at end of file diff --git a/src/RobotContainer.h b/src/RobotContainer.h new file mode 100644 index 0000000..3efc908 --- /dev/null +++ b/src/RobotContainer.h @@ -0,0 +1,53 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include + +#include "Constants.h" +#include "subsystems/DriveSubsystem.h" + +/** + * This class is where the bulk of the robot should be declared. Since + * Command-based is a "declarative" paradigm, very little robot logic should + * actually be handled in the {@link Robot} periodic methods (other than the + * scheduler calls). Instead, the structure of the robot (including subsystems, + * commands, and button mappings) should be declared here. + */ +class RobotContainer { + public: + RobotContainer(); + + frc2::Command* GetAutonomousCommand(); + + private: + // The driver's controller + frc::XboxController m_driverController{OIConstants::kDriverControllerPort}; + + // The robot's subsystems and commands are defined here... + + // The robot's subsystems + DriveSubsystem m_drive; + + frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); }, + {}}; + frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); }, + {}}; + + // The chooser for the autonomous routines + frc::SendableChooser m_chooser; + + void ConfigureButtonBindings(); +}; \ No newline at end of file From d32c1e532bd398ec2f1561d0ac3ab839fd9e2c65 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 1 Feb 2020 13:16:25 -0600 Subject: [PATCH 04/31] Made edits to start on ramsete control --- .vscode/settings.json | 5 ++- src/Autonomous/Actions/PathFinder.h | 1 + src/DriveSubsystem.cpp | 54 +++++++++++++++++++++++------ src/DriveSubsystem.h | 23 ++++++++++-- src/RobotContainer.cpp | 36 +++---------------- src/RobotContainer.h | 20 +++-------- 6 files changed, 78 insertions(+), 61 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 01fb922..4eaa37c 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -13,5 +13,8 @@ "**/.settings": true, "**/.factorypath": true }, - "C_Cpp.default.configurationProvider": "vscode-wpilib" + "C_Cpp.default.configurationProvider": "vscode-wpilib", + "files.associations": { + "functional": "cpp" + } } diff --git a/src/Autonomous/Actions/PathFinder.h b/src/Autonomous/Actions/PathFinder.h index c292be5..869d3fa 100644 --- a/src/Autonomous/Actions/PathFinder.h +++ b/src/Autonomous/Actions/PathFinder.h @@ -1,5 +1,6 @@ #include #include +#include #include #include diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index e22cf6b..ddc5b48 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -16,7 +16,8 @@ DriveSubsystem::DriveSubsystem() : m_ticksPerInch("Ticks Per Inch", (4 * 3.1415) / 1024), compressor(COMPRESSOR_PCM), m_leftDriveShifter(LEFT_DRIVE_SHIFTER_PCM, LEFT_DRIVE_SHIFTER_HIGH_GEAR_PORT, LEFT_DRIVE_SHIFTER_LOW_GEAR_PORT), - m_rightDriveShifter(RIGHT_DRIVE_SHIFTER_PCM, RIGHT_DRIVE_SHIFTER_HIGH_GEAR_PORT, RIGHT_DRIVE_SHIFTER_LOW_GEAR_PORT) { + m_rightDriveShifter(RIGHT_DRIVE_SHIFTER_PCM, RIGHT_DRIVE_SHIFTER_HIGH_GEAR_PORT, RIGHT_DRIVE_SHIFTER_LOW_GEAR_PORT), + m_odometry{frc::Rotation2d(units::degree_t(getHeading()))} { try { m_gyro = new AHRS(SPI::Port::kMXP); @@ -33,10 +34,6 @@ void DriveSubsystem::robotInit() { // resetTracker(Position2d(Translation2d(), Rotation2d())); } -void DriveSubsystem::autonInit() { - -} - void DriveSubsystem::auton() { m_odometry.Update(frc::Rotation2d(units::degree_t(getHeading())), units::meter_t(m_leftMaster.GetSelectedSensorPosition(0)), @@ -146,18 +143,19 @@ void DriveSubsystem::resetEncoders() { m_rightSlave.SetSelectedSensorPosition(0); } -void DriveSubsystem::resetOdometry(Pose2d pose) { +double DriveSubsystem::getHeading() { + return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0); +} +void DriveSubsystem::resetOdometry(Pose2d pose) { + resetEncoders(); + m_odometry.ResetPosition(pose, Rotation2d(units::degree_t(getHeading()))); } Pose2d DriveSubsystem::getPose() { return m_odometry.GetPose(); } -double DriveSubsystem::getHeading() { - return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0); -} - double DriveSubsystem::getTurnRate() { return m_gyro.GetRate() * (kGyroReversed ? -1.0 : 1.0); } @@ -166,3 +164,39 @@ double DriveSubsystem::getAverageEncoderDistance() { return m_leftMaster.GetSelectedSensorPosition(0) + m_rightMaster.GetSelectedSensorPosition(0) / 2.0; } +TalonSRX& DriveSubsystem::getRightMaster() { + return m_rightMaster; +} + +TalonSRX& DriveSubsystem::getRightSlave() { + return m_rightSlave; +} + +TalonSRX& DriveSubsystem::getLeftMaster() { + return m_leftMaster; +} + +TalonSRX& DriveSubsystem::getLeftSlave() { + return m_leftSlave; +} + + +void DriveSubsystem::tankDriveVolts(units::volt_t l, units::volt_t r) { + +} + +void DriveSubsystem::setVelocity(double leftVelocity, double rightVelocity) { + m_leftMaster.Set(ControlMode::Velocity, leftVelocity); + m_leftSlave.Set(ControlMode::Velocity, leftVelocity); + m_rightMaster.Set(ControlMode::Velocity, rightVelocity); + m_rightSlave.Set(ControlMode::Velocity, rightVelocity); +} + +kinematics::DifferentialWheelSpeeds DriveSubsystem::getWheelSpeeds() { + return {units::meters_per_second_t(m_leftMaster.), + units::meters_per_second_t(m_rightEncoder.GetRate())}; +} + +void DriveSubsystem::setMaxOutput(double maxOutput) { + m_drive.SetMaxOutput(maxOutput); +} \ No newline at end of file diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 0f332b1..77d797c 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -10,8 +10,17 @@ #include #include #include +#include +#include +#include +#include +#include +#include +#define WHEEL_CIRCUMFERENCE_METERS +#define SENSOR_UNITS_PER_ROTATION + enum class DriveSide{LEFT = 1, RIGHT = 2, BOTH = 3}; class DriveSubsystem : public CORESubsystem, public CORETask { @@ -20,7 +29,6 @@ class DriveSubsystem : public CORESubsystem, public CORETask { void robotInit() override; void teleopInit() override; void teleop() override; - void autonInit() override; void auton(); void teleopEnd() override; void preLoopTask() override; @@ -39,8 +47,19 @@ class DriveSubsystem : public CORESubsystem, public CORETask { double getTurnRate(); void setMaxOutput(double maxOutput); double getAverageEncoderDistance(); + void tankDriveVolts(units::volt_t l, units::volt_t r); + TalonSRX& getRightMaster(); + TalonSRX& getLeftMaster(); + TalonSRX& getRightSlave(); + TalonSRX& getLeftSlave(); + void setVelocity(double leftVelocity, double rightVelocity); + kinematics::DifferentialDriveWheelSpeeds getWheelSpeeds(); + SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; + SpeedControllerGroup m_rightMotors{m_rightSlave, m_leftMaster}; + drive::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + void setMaxOutput(double maxOutput); - m_odometry = Rotation2d(units::degree_t(getHeading())); + DifferentialDriveOdometry m_odometry; COREConstant m_lookAhead, m_driveTurnkP; COREVector path; TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index e40e422..3e9fe0b 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -1,10 +1,3 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 FIRST. All Rights Reserved. */ -/* Open Source Software - may be modified and shared by FRC teams. The code */ -/* must be accompanied by the FIRST BSD license file in the root directory of */ -/* the project. */ -/*----------------------------------------------------------------------------*/ - #include "RobotContainer.h" #include @@ -21,28 +14,7 @@ #include "Constants.h" RobotContainer::RobotContainer() { - // Initialize all of your commands and subsystems here - - // Configure the button bindings - ConfigureButtonBindings(); - - // Set up default drive command - m_drive.SetDefaultCommand(frc2::RunCommand( - [this] { - m_drive.ArcadeDrive( - m_driverController.GetY(frc::GenericHID::kLeftHand), - m_driverController.GetX(frc::GenericHID::kRightHand)); - }, - {&m_drive})); -} - -void RobotContainer::ConfigureButtonBindings() { - // Configure your button bindings here - // While holding the shoulder button, drive at half speed - frc2::JoystickButton(&m_driverController, 6) - .WhenPressed(&m_driveHalfSpeed) - .WhenReleased(&m_driveFullSpeed); } frc2::Command* RobotContainer::GetAutonomousCommand() { @@ -72,20 +44,20 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { config); frc2::RamseteCommand ramseteCommand( - exampleTrajectory, [this]() { return m_drive.GetPose(); }, + exampleTrajectory, [this]() { return m_drive.getPose(); }, frc::RamseteController(AutoConstants::kRamseteB, AutoConstants::kRamseteZeta), frc::SimpleMotorFeedforward( DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), DriveConstants::kDriveKinematics, - [this] { return m_drive.GetWheelSpeeds(); }, + [this] { return m_drive.getWheelSpeeds(); }, frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), - [this](auto left, auto right) { m_drive.TankDriveVolts(left, right); }, + [this](auto left, auto right) { m_drive.tankDriveVolts(left, right); }, {&m_drive}); // no auto return new frc2::SequentialCommandGroup( std::move(ramseteCommand), - frc2::InstantCommand([this] { m_drive.TankDriveVolts(0_V, 0_V); }, {})); + frc2::InstantCommand([this] { m_drive.tankDriveVolts(0_V, 0_V); }, {})); } \ No newline at end of file diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 3efc908..608b801 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -7,7 +7,7 @@ #pragma once -#include +#include #include #include #include @@ -17,7 +17,7 @@ #include #include "Constants.h" -#include "subsystems/DriveSubsystem.h" +#include "DriveSubsystem.h" /** * This class is where the bulk of the robot should be declared. Since @@ -31,21 +31,9 @@ class RobotContainer { RobotContainer(); frc2::Command* GetAutonomousCommand(); - - private: - // The driver's controller - frc::XboxController m_driverController{OIConstants::kDriverControllerPort}; - - // The robot's subsystems and commands are defined here... - - // The robot's subsystems DriveSubsystem m_drive; - - frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); }, - {}}; - frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); }, - {}}; - + private: + static Trajectory loadTrajectory(String trajectoryName); // The chooser for the autonomous routines frc::SendableChooser m_chooser; From 1b0e0a1d0f77d7148dd4e42ace527652431448dc Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 1 Feb 2020 14:07:20 -0600 Subject: [PATCH 05/31] changes for pathfinder --- src/DriveSubsystem.cpp | 4 ++-- src/DriveSubsystem.h | 7 +++---- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index ddc5b48..f42d718 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -144,7 +144,7 @@ void DriveSubsystem::resetEncoders() { } double DriveSubsystem::getHeading() { - return std::remainder(m_gyro.GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0); + return std::remainder(m_gyro->GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0); } void DriveSubsystem::resetOdometry(Pose2d pose) { @@ -157,7 +157,7 @@ Pose2d DriveSubsystem::getPose() { } double DriveSubsystem::getTurnRate() { - return m_gyro.GetRate() * (kGyroReversed ? -1.0 : 1.0); + return m_gyro->GetRate() * (kGyroReversed ? -1.0 : 1.0); } double DriveSubsystem::getAverageEncoderDistance() { diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 77d797c..b214549 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -15,7 +15,6 @@ #include #include #include -#include #define WHEEL_CIRCUMFERENCE_METERS @@ -53,10 +52,10 @@ class DriveSubsystem : public CORESubsystem, public CORETask { TalonSRX& getRightSlave(); TalonSRX& getLeftSlave(); void setVelocity(double leftVelocity, double rightVelocity); - kinematics::DifferentialDriveWheelSpeeds getWheelSpeeds(); + DifferentialDriveWheelSpeeds getWheelSpeeds(); SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; SpeedControllerGroup m_rightMotors{m_rightSlave, m_leftMaster}; - drive::DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; + DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; void setMaxOutput(double maxOutput); DifferentialDriveOdometry m_odometry; @@ -71,6 +70,6 @@ class DriveSubsystem : public CORESubsystem, public CORETask { bool m_highGear; double m_wheelbase = 20.8; double m_trackwidth = 25.881; - AHRS m_gyro; + AHRS * m_gyro; int count = 0; }; \ No newline at end of file From 69ce8c8cd31023adc044ce7e5e8f36508a3f6f1e Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 1 Feb 2020 14:17:04 -0600 Subject: [PATCH 06/31] Fixed basic merge errors --- src/DriveSubsystem.h | 2 -- src/LauncherSubsystem.cpp | 1 - 2 files changed, 3 deletions(-) diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 421f484..1921111 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -65,8 +65,6 @@ class DriveSubsystem : public CORESubsystem { DoubleSolenoid m_leftDriveShifter, m_rightDriveShifter; bool m_highGear; Compressor compressor; - DoubleSolenoid m_leftDriveShifter, m_rightDriveShifter; - bool m_highGear; double m_wheelbase = 20.8; double m_trackwidth = 25.881; AHRS * m_gyro; diff --git a/src/LauncherSubsystem.cpp b/src/LauncherSubsystem.cpp index 8da7b80..573dc2e 100644 --- a/src/LauncherSubsystem.cpp +++ b/src/LauncherSubsystem.cpp @@ -1,6 +1,5 @@ #include #include -#include using namespace CORE; From 5a10a29792144cf7357be6fc2ed2ab532fe87259 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 1 Feb 2020 16:34:00 -0600 Subject: [PATCH 07/31] Fixing more errors in the 2020 project --- src/ControlPanelSubsystem.cpp | 64 ----------------------------------- src/ControlPanelSubsystem.h | 15 -------- src/DriveSubsystem.cpp | 5 ++- src/DriveSubsystem.h | 2 +- src/Robot.h | 2 +- src/autonomous/Auton.cpp | 2 +- 6 files changed, 5 insertions(+), 85 deletions(-) delete mode 100644 src/ControlPanelSubsystem.cpp delete mode 100644 src/ControlPanelSubsystem.h diff --git a/src/ControlPanelSubsystem.cpp b/src/ControlPanelSubsystem.cpp deleted file mode 100644 index 91b8dad..0000000 --- a/src/ControlPanelSubsystem.cpp +++ /dev/null @@ -1,64 +0,0 @@ -#include -#include -#include - -void ControlPanelSubsystem::robotInit() { - -} - -void ControlPanelSubsystem::teleopInit() { - -} - -void ControlPanelSubsystem::teleop() { - - /** - * The method GetColor() returns a normalized color value from the sensor and can be - * useful if outputting the color to an RGB LED or similar. To - * read the raw color, use GetRawColor(). - * - * The color sensor works best when within a few inches from an object in - * well lit conditions (the built in LED is a big help here!). The farther - * an object is the more light from the surroundings will bleed into the - * measurements and make it difficult to accurately determine its color. - */ - frc::9890-p;;l/.Color detectedColor = m_colorSensor.GetColor(); - - /** - * The sensor returns a raw IR value of the infrared light detected. - */ - double IR = m_colorSensor.GetIR(); - - /** - * Open Smart Dashboard or Shuffleboard to see the color detected by the - * sensor. - */ - frc::SmartDashboard::PutNumber("Red", detectedColor.red); - frc::SmartDashboard::PutNumber("Green", detectedColor.green); - frc::SmartDashboard::PutNumber("Blue", detectedColor.blue); - frc::SmartDashboard::PutNumber("IR", IR); - if((detectedColor.red > 0.29) & (detectedColor.green > 0.5)){ - frc::SmartDashboard::PutString("Color", "Yellow"); - } - else if(detectedColor.red > 0.29){ - frc::SmartDashboard::PutString("Color", "Red"); - } - else if(detectedColor.green > 0.5){ - frc::SmartDashboard::PutString("Color", "Green"); - } - else if(detectedColor.blue > 0.235){ - frc::SmartDashboard::PutString("Color", "Blue"); - } - - uint32_t proximity = m_colorSensor.GetProximity(); - - frc::SmartDashboard::PutNumber("Proximity", proximity); - } - - -#ifndef RUNNING_FRC_TESTS -int main() { return frc::StartRobot(); } -#endif -void Robot::TestPeriodic() {} - -} diff --git a/src/ControlPanelSubsystem.h b/src/ControlPanelSubsystem.h deleted file mode 100644 index 987b90b..0000000 --- a/src/ControlPanelSubsystem.h +++ /dev/null @@ -1,15 +0,0 @@ -#pragma once - -#include -#include - -using namespace CORE; - -class ControlPanelSubsystem : public CORESubsystem { -public: - ControlPanelSubsystem(); - void robotInit() override; - void teleopInit() override; - void teleop() override; -private: -}; \ No newline at end of file diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 70474bc..9d4f6a3 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -3,7 +3,7 @@ #include DriveSubsystem::DriveSubsystem() : - m_lookAhead("Path Lookahead", 24.0), + m_odometry{frc::Rotation2d(units::degree_t(getHeading()))}, m_driveTurnkP("Drive Turn P Value", .05), m_leftMaster(LEFT_FRONT_PORT), m_rightMaster(RIGHT_FRONT_PORT), @@ -14,8 +14,7 @@ DriveSubsystem::DriveSubsystem() : m_etherQuickTurnValue("Ether Quick Turn Value", 1.0), m_ticksPerInch("Ticks Per Inch", (4 * 3.1415) / 1024), m_leftDriveShifter(LEFT_DRIVE_SHIFTER_PCM, LEFT_DRIVE_SHIFTER_HIGH_GEAR_PORT, LEFT_DRIVE_SHIFTER_LOW_GEAR_PORT), - m_rightDriveShifter(RIGHT_DRIVE_SHIFTER_PCM, RIGHT_DRIVE_SHIFTER_HIGH_GEAR_PORT, RIGHT_DRIVE_SHIFTER_LOW_GEAR_PORT), - m_odometry{frc::Rotation2d(units::degree_t(getHeading()))} { + m_rightDriveShifter(RIGHT_DRIVE_SHIFTER_PCM, RIGHT_DRIVE_SHIFTER_HIGH_GEAR_PORT, RIGHT_DRIVE_SHIFTER_LOW_GEAR_PORT) { try { m_gyro = new AHRS(SPI::Port::kMXP); diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index cec24fe..7196e51 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -57,7 +57,7 @@ class DriveSubsystem : public CORESubsystem { void setMaxOutput(double maxOutput); DifferentialDriveOdometry m_odometry; - COREConstant m_lookAhead, m_driveTurnkP; + COREConstant m_driveTurnkP; COREVector path; private: TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; diff --git a/src/Robot.h b/src/Robot.h index 28e69ad..1757b63 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -10,7 +10,7 @@ #include #include #include -#include +#include #include /* Drive ports */ diff --git a/src/autonomous/Auton.cpp b/src/autonomous/Auton.cpp index 2cef856..e496395 100644 --- a/src/autonomous/Auton.cpp +++ b/src/autonomous/Auton.cpp @@ -1,4 +1,4 @@ -#include +#include Autonomous::Autonomous() : COREAuton("Test Auto") {} From 2680960648694a87261bc43b147061f712bb456c Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Thu, 6 Feb 2020 20:17:47 -0600 Subject: [PATCH 08/31] Fixed some errors. Still looking at the speedmotorcontroller errors --- src/DriveSubsystem.cpp | 6 +++--- src/DriveSubsystem.h | 11 +++++------ src/RobotContainer.h | 3 ++- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 9d4f6a3..e4cc36c 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -19,7 +19,7 @@ DriveSubsystem::DriveSubsystem() : try { m_gyro = new AHRS(SPI::Port::kMXP); } catch (std::exception ex) { - CORELog::logError("Error initializing gyro: " + string(ex.what())); + CORELog::LogError("Error initializing gyro: " + string(ex.what())); } } @@ -135,7 +135,7 @@ void DriveSubsystem::resetEncoders() { } double DriveSubsystem::getHeading() { - return std::remainder(m_gyro->GetAngle(), 360) * (kGyroReversed ? -1.0 : 1.0); + return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } void DriveSubsystem::resetOdometry(Pose2d pose) { @@ -148,7 +148,7 @@ Pose2d DriveSubsystem::getPose() { } double DriveSubsystem::getTurnRate() { - return m_gyro->GetRate() * (kGyroReversed ? -1.0 : 1.0); + return m_gyro->GetRate() * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } double DriveSubsystem::getAverageEncoderDistance() { diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 7196e51..eae9a5c 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -45,16 +45,15 @@ class DriveSubsystem : public CORESubsystem { void setMaxOutput(double maxOutput); double getAverageEncoderDistance(); void tankDriveVolts(units::volt_t l, units::volt_t r); - TalonSRX& getRightMaster(); - TalonSRX& getLeftMaster(); - TalonSRX& getRightSlave(); - TalonSRX& getLeftSlave(); + WPI_TalonSRX& getRightMaster(); + WPI_TalonSRX& getLeftMaster(); + WPI_TalonSRX& getRightSlave(); + WPI_TalonSRX& getLeftSlave(); void setVelocity(double leftVelocity, double rightVelocity); DifferentialDriveWheelSpeeds getWheelSpeeds(); SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; - SpeedControllerGroup m_rightMotors{m_rightSlave, m_leftMaster}; + SpeedControllerGroup m_rightMotors{m_rightSlave, m_rightMaster}; DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; - void setMaxOutput(double maxOutput); DifferentialDriveOdometry m_odometry; COREConstant m_driveTurnkP; diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 608b801..1740d73 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -18,6 +18,7 @@ #include "Constants.h" #include "DriveSubsystem.h" +#include /** * This class is where the bulk of the robot should be declared. Since @@ -33,7 +34,7 @@ class RobotContainer { frc2::Command* GetAutonomousCommand(); DriveSubsystem m_drive; private: - static Trajectory loadTrajectory(String trajectoryName); + static Trajectory loadTrajectory(std::string trajectoryName); // The chooser for the autonomous routines frc::SendableChooser m_chooser; From 86fa5156ec59fd6292917d9bf4fa0d99a8cb24a7 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Mon, 10 Feb 2020 19:58:40 -0600 Subject: [PATCH 09/31] Fixed a couple of the errors in pathfinder --- src/DriveSubsystem.cpp | 18 ++++++++++-------- src/DriveSubsystem.h | 6 ++---- 2 files changed, 12 insertions(+), 12 deletions(-) diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index e4cc36c..9f171c9 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -105,7 +105,9 @@ void DriveSubsystem::initTalons() { m_rightSlave.SetInverted(true); } -void DriveSubsystem::teleopEnd() {} +void DriveSubsystem::teleopEnd() { + +} void DriveSubsystem::fillCompressor() { // Code to run the compressor. Maybe should be moved to Robot? @@ -155,19 +157,19 @@ double DriveSubsystem::getAverageEncoderDistance() { return m_leftMaster.GetSelectedSensorPosition(0) + m_rightMaster.GetSelectedSensorPosition(0) / 2.0; } -TalonSRX& DriveSubsystem::getRightMaster() { +WPI_TalonSRX& DriveSubsystem::getRightMaster() { return m_rightMaster; } -TalonSRX& DriveSubsystem::getRightSlave() { +WPI_TalonSRX& DriveSubsystem::getRightSlave() { return m_rightSlave; } -TalonSRX& DriveSubsystem::getLeftMaster() { +WPI_TalonSRX& DriveSubsystem::getLeftMaster() { return m_leftMaster; } -TalonSRX& DriveSubsystem::getLeftSlave() { +WPI_TalonSRX& DriveSubsystem::getLeftSlave() { return m_leftSlave; } @@ -183,9 +185,9 @@ void DriveSubsystem::setVelocity(double leftVelocity, double rightVelocity) { m_rightSlave.Set(ControlMode::Velocity, rightVelocity); } -kinematics::DifferentialWheelSpeeds DriveSubsystem::getWheelSpeeds() { - return {units::meters_per_second_t(m_leftMaster.), - units::meters_per_second_t(m_rightEncoder.GetRate())}; +frc::DifferentialDriveWheelSpeeds DriveSubsystem::getWheelSpeeds() { + return {units::meters_per_second_t(m_leftMaster.GetSelectedSensorVelocity(0) * (10.0 / 4096) * m_wheelCircumference), + units::meters_per_second_t(m_rightMaster.GetSelectedSensorVelocity(0) * (10.0 / 4096) * m_wheelCircumference)}; } void DriveSubsystem::setMaxOutput(double maxOutput) { diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index eae9a5c..766db37 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -17,9 +17,6 @@ #include #include -#define WHEEL_CIRCUMFERENCE_METERS -#define SENSOR_UNITS_PER_ROTATION - enum class DriveSide{LEFT = 1, RIGHT = 2, BOTH = 3}; class DriveSubsystem : public CORESubsystem { @@ -59,7 +56,8 @@ class DriveSubsystem : public CORESubsystem { COREConstant m_driveTurnkP; COREVector path; private: - TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; + double m_wheelCircumference = 0.4787787204; + WPI_TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; COREConstant m_etherAValue, m_etherBValue, m_etherQuickTurnValue, m_ticksPerInch; DoubleSolenoid m_leftDriveShifter, m_rightDriveShifter; bool m_highGear; From 031828089ce940a3e17a159b595e0829af70ada0 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 11 Feb 2020 19:59:10 -0600 Subject: [PATCH 10/31] Made everything build, crashed on deploy --- src/Constants.cpp | 6 ++++++ src/DriveSubsystem.h | 3 ++- src/RobotContainer.cpp | 15 +++++++++++---- src/RobotContainer.h | 24 +++++++++--------------- 4 files changed, 28 insertions(+), 20 deletions(-) create mode 100644 src/Constants.cpp diff --git a/src/Constants.cpp b/src/Constants.cpp new file mode 100644 index 0000000..b24c514 --- /dev/null +++ b/src/Constants.cpp @@ -0,0 +1,6 @@ +#include "Constants.h" + +using namespace DriveConstants; + +const frc::DifferentialDriveKinematics DriveConstants::kDriveKinematics( + kTrackwidth); diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 766db37..030b882 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -15,11 +15,12 @@ #include #include #include +#include #include enum class DriveSide{LEFT = 1, RIGHT = 2, BOTH = 3}; -class DriveSubsystem : public CORESubsystem { +class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { public: DriveSubsystem(); void robotInit() override; diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 3e9fe0b..4dd9744 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -1,3 +1,10 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + #include "RobotContainer.h" #include @@ -22,13 +29,13 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( frc::SimpleMotorFeedforward( DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), - DriveConstants::kDriveKinematics, 10_V); + kDriveKinematics, 10_V); // Set up config for trajectory frc::TrajectoryConfig config(AutoConstants::kMaxSpeed, AutoConstants::kMaxAcceleration); // Add kinematics to ensure max speed is actually obeyed - config.SetKinematics(DriveConstants::kDriveKinematics); + config.SetKinematics(kDriveKinematics); // Apply the voltage constraint config.AddConstraint(autoVoltageConstraint); @@ -49,7 +56,7 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { AutoConstants::kRamseteZeta), frc::SimpleMotorFeedforward( DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), - DriveConstants::kDriveKinematics, + kDriveKinematics, [this] { return m_drive.getWheelSpeeds(); }, frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), @@ -60,4 +67,4 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { return new frc2::SequentialCommandGroup( std::move(ramseteCommand), frc2::InstantCommand([this] { m_drive.tankDriveVolts(0_V, 0_V); }, {})); -} \ No newline at end of file +} diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 1740d73..9b2f189 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -7,7 +7,7 @@ #pragma once -#include +#include #include #include #include @@ -18,25 +18,19 @@ #include "Constants.h" #include "DriveSubsystem.h" -#include - -/** - * This class is where the bulk of the robot should be declared. Since - * Command-based is a "declarative" paradigm, very little robot logic should - * actually be handled in the {@link Robot} periodic methods (other than the - * scheduler calls). Instead, the structure of the robot (including subsystems, - * commands, and button mappings) should be declared here. - */ + +using namespace DriveConstants; + class RobotContainer { public: RobotContainer(); frc2::Command* GetAutonomousCommand(); - DriveSubsystem m_drive; + private: - static Trajectory loadTrajectory(std::string trajectoryName); + + DriveSubsystem m_drive; + // The chooser for the autonomous routines frc::SendableChooser m_chooser; - - void ConfigureButtonBindings(); -}; \ No newline at end of file +}; From 358bd18b89d331cffa3614ddc5d5fe7bb620f31e Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 15 Feb 2020 09:40:49 -0600 Subject: [PATCH 11/31] Added try catch statements so that the gyro doesn't keep crashing --- src/DriveSubsystem.cpp | 29 ++++++++++++++++++++++------- src/DriveSubsystem.h | 5 ++++- 2 files changed, 26 insertions(+), 8 deletions(-) diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 9f171c9..aded5e4 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -16,14 +16,15 @@ DriveSubsystem::DriveSubsystem() : m_leftDriveShifter(LEFT_DRIVE_SHIFTER_PCM, LEFT_DRIVE_SHIFTER_HIGH_GEAR_PORT, LEFT_DRIVE_SHIFTER_LOW_GEAR_PORT), m_rightDriveShifter(RIGHT_DRIVE_SHIFTER_PCM, RIGHT_DRIVE_SHIFTER_HIGH_GEAR_PORT, RIGHT_DRIVE_SHIFTER_LOW_GEAR_PORT) { - try { - m_gyro = new AHRS(SPI::Port::kMXP); - } catch (std::exception ex) { - CORELog::LogError("Error initializing gyro: " + string(ex.what())); - } + // try { + // m_gyro = new AHRS(SPI::Port::kMXP); + // } catch (std::exception ex) { + // CORELog::LogError("Error initializing gyro: " + string(ex.what())); + // } } void DriveSubsystem::robotInit() { + cout << "Drive Subsystem" << endl; // Registers joystick axis and buttons, does inital setup for talons driverJoystick->RegisterAxis(CORE::COREJoystick::LEFT_STICK_Y); driverJoystick->RegisterAxis(CORE::COREJoystick::RIGHT_STICK_X); @@ -137,7 +138,12 @@ void DriveSubsystem::resetEncoders() { } double DriveSubsystem::getHeading() { - return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + try { + return std::remainder(m_gyro.GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + } catch (std::exception ex) { + std::cout << "Gyro isn't working in get heading!" << endl; + return 0; + } } void DriveSubsystem::resetOdometry(Pose2d pose) { @@ -150,7 +156,12 @@ Pose2d DriveSubsystem::getPose() { } double DriveSubsystem::getTurnRate() { - return m_gyro->GetRate() * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + try { + return m_gyro.GetRate() * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + } catch (std::exception ex) { + std::cout << "Gyro isn't working in get turn rate!" << endl; + return 0; + } } double DriveSubsystem::getAverageEncoderDistance() { @@ -175,6 +186,10 @@ WPI_TalonSRX& DriveSubsystem::getLeftSlave() { void DriveSubsystem::tankDriveVolts(units::volt_t l, units::volt_t r) { + m_leftMaster.SetVoltage(l); + m_leftSlave.SetVoltage(r); + m_rightMaster.SetVoltage(l); + m_rightSlave.SetVoltage(r); } diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 030b882..4785ede 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -12,11 +12,13 @@ #include #include #include +#include #include #include #include #include #include +#include enum class DriveSide{LEFT = 1, RIGHT = 2, BOTH = 3}; @@ -65,6 +67,7 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { Compressor compressor; double m_wheelbase = 20.8; double m_trackwidth = 25.881; - AHRS * m_gyro; + // AHRS * m_gyro; + frc::ADXRS450_Gyro m_gyro; int count = 0; }; From 9493b98219adab2f46e8ccee45092cd1f2b848dc Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sun, 23 Feb 2020 12:39:47 -0600 Subject: [PATCH 12/31] Added robot container stuff - crashes --- .vscode/settings.json | 3 +- src/ClimberSubsystem.cpp | 14 ++--- src/ClimberSubsystem.h | 24 ++++---- src/Constants.h | 16 +---- src/ConveyorSubsystem.cpp | 58 +++++++++--------- src/ConveyorSubsystem.h | 30 ++++----- src/DriveSubsystem.cpp | 26 +++++--- src/DriveSubsystem.h | 4 +- src/IntakeSubsystem.cpp | 86 +++++++++++++------------- src/IntakeSubsystem.h | 42 ++++++------- src/LauncherSubsystem.cpp | 118 ++++++++++++++++++------------------ src/LauncherSubsystem.h | 30 ++++----- src/RobotContainer.cpp | 20 +++--- src/RobotContainer.h | 15 ++--- src/TurretSubsystem.cpp | 124 +++++++++++++++++++------------------- src/TurretSubsystem.h | 44 +++++++------- 16 files changed, 324 insertions(+), 330 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index e31a0a0..18e5137 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -77,6 +77,7 @@ "complex": "cpp", "typeinfo": "cpp", "valarray": "cpp", - "*.inc": "cpp" + "*.inc": "cpp", + "future": "cpp" } } diff --git a/src/ClimberSubsystem.cpp b/src/ClimberSubsystem.cpp index 037a973..17ed69e 100644 --- a/src/ClimberSubsystem.cpp +++ b/src/ClimberSubsystem.cpp @@ -1,13 +1,13 @@ -#include +// #include -void ClimberSubsystem::robotInit() { +// void ClimberSubsystem::robotInit() { -} +// } -void ClimberSubsystem::teleopInit() { +// void ClimberSubsystem::teleopInit() { -} +// } -void ClimberSubsystem::teleop() { +// void ClimberSubsystem::teleop() { -} +// } diff --git a/src/ClimberSubsystem.h b/src/ClimberSubsystem.h index 8526df6..c3bb6e8 100644 --- a/src/ClimberSubsystem.h +++ b/src/ClimberSubsystem.h @@ -1,15 +1,15 @@ -#pragma once +// #pragma once -#include -#include +// #include +// #include -using namespace CORE; +// using namespace CORE; -class ClimberSubsystem : public CORESubsystem { -public: - ClimberSubsystem(); - void robotInit() override; - void teleopInit() override; - void teleop() override; -private: -}; +// class ClimberSubsystem : public CORESubsystem { +// public: +// ClimberSubsystem(); +// void robotInit() override; +// void teleopInit() override; +// void teleop() override; +// private: +// }; diff --git a/src/Constants.h b/src/Constants.h index 32488de..35ee25b 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -2,18 +2,9 @@ #include #include #include - +// All of these values should be updated according to what works with the characterization tool #pragma once -/** - * The Constants header provides a convenient place for teams to hold robot-wide - * numerical or bool constants. This should not be used for any other purpose. - * - * It is generally a good idea to place constants into subsystem- or - * command-specific namespaces within this header, which can then be used where - * they are needed. - */ - namespace DriveConstants { constexpr int kLeftMotor1Port = 0; constexpr int kLeftMotor2Port = 1; @@ -36,11 +27,6 @@ constexpr double kEncoderDistancePerPulse = constexpr bool kGyroReversed = true; -// These are example values only - DO NOT USE THESE FOR YOUR OWN ROBOT! -// These characterization values MUST be determined either experimentally or -// theoretically for *your* robot's drive. The Robot Characterization -// Toolsuite provides a convenient tool for obtaining these values for your -// robot. constexpr auto ks = 0.22_V; constexpr auto kv = 1.98 * 1_V * 1_s / 1_m; constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m; diff --git a/src/ConveyorSubsystem.cpp b/src/ConveyorSubsystem.cpp index e28788a..ec2a8ed 100644 --- a/src/ConveyorSubsystem.cpp +++ b/src/ConveyorSubsystem.cpp @@ -1,37 +1,37 @@ -#include +// #include -using namespace CORE; +// using namespace CORE; -ConveyorSubsystem::ConveyorSubsystem() : m_conveyorMotor1(CONVEYOR_1_PORT), - m_conveyorMotor2(CONVEYOR_2_PORT), - m_conveyorSpeed("Conveyor Speed", 0){ +// ConveyorSubsystem::ConveyorSubsystem() : m_conveyorMotor1(CONVEYOR_1_PORT), +// m_conveyorMotor2(CONVEYOR_2_PORT), +// m_conveyorSpeed("Conveyor Speed", 0){ -} +// } -void ConveyorSubsystem::robotInit(){ - m_conveyorMotor1.Set(ControlMode::PercentOutput, 0); - m_conveyorMotor2.Set(ControlMode::PercentOutput, 0); - m_conveyorMotor1.SetInverted(true); - m_conveyorMotor2.SetInverted(false); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_BUTTON); -} +// void ConveyorSubsystem::robotInit(){ +// m_conveyorMotor1.Set(ControlMode::PercentOutput, 0); +// m_conveyorMotor2.Set(ControlMode::PercentOutput, 0); +// m_conveyorMotor1.SetInverted(true); +// m_conveyorMotor2.SetInverted(false); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_BUTTON); +// } -void ConveyorSubsystem::teleopInit(){ +// void ConveyorSubsystem::teleopInit(){ -} +// } -void ConveyorSubsystem::teleop(){ - if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { - setMotor(m_conveyorSpeed.Get()); - } else if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::RIGHT_BUTTON)) { - setMotor(-m_conveyorSpeed.Get()); - } else { - setMotor(0.0); - } -} +// void ConveyorSubsystem::teleop(){ +// if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { +// setMotor(m_conveyorSpeed.Get()); +// } else if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::RIGHT_BUTTON)) { +// setMotor(-m_conveyorSpeed.Get()); +// } else { +// setMotor(0.0); +// } +// } -void ConveyorSubsystem::setMotor(double conveyorSpeed){ - m_conveyorMotor1.Set(ControlMode::PercentOutput, conveyorSpeed); - m_conveyorMotor2.Set(ControlMode::PercentOutput, conveyorSpeed); -} +// void ConveyorSubsystem::setMotor(double conveyorSpeed){ +// m_conveyorMotor1.Set(ControlMode::PercentOutput, conveyorSpeed); +// m_conveyorMotor2.Set(ControlMode::PercentOutput, conveyorSpeed); +// } diff --git a/src/ConveyorSubsystem.h b/src/ConveyorSubsystem.h index 5715fec..64fa7f9 100644 --- a/src/ConveyorSubsystem.h +++ b/src/ConveyorSubsystem.h @@ -1,19 +1,19 @@ -#pragma once +// #pragma once -#include -#include -#include +// #include +// #include +// #include -class ConveyorSubsystem : public CORESubsystem { -public: - ConveyorSubsystem(); - void robotInit() override; - void teleopInit() override; - void teleop() override; - void setMotor(double conveyorSpeed); +// class ConveyorSubsystem : public CORESubsystem { +// public: +// ConveyorSubsystem(); +// void robotInit() override; +// void teleopInit() override; +// void teleop() override; +// void setMotor(double conveyorSpeed); -private: - TalonSRX m_conveyorMotor1, m_conveyorMotor2; - COREConstant m_conveyorSpeed; -}; +// private: +// TalonSRX m_conveyorMotor1, m_conveyorMotor2; +// COREConstant m_conveyorSpeed; +// }; diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index aded5e4..e244f76 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -3,7 +3,7 @@ #include DriveSubsystem::DriveSubsystem() : - m_odometry{frc::Rotation2d(units::degree_t(getHeading()))}, + m_odometry{frc::Rotation2d(units::degree_t(getStartHeading()))}, m_driveTurnkP("Drive Turn P Value", .05), m_leftMaster(LEFT_FRONT_PORT), m_rightMaster(RIGHT_FRONT_PORT), @@ -16,11 +16,6 @@ DriveSubsystem::DriveSubsystem() : m_leftDriveShifter(LEFT_DRIVE_SHIFTER_PCM, LEFT_DRIVE_SHIFTER_HIGH_GEAR_PORT, LEFT_DRIVE_SHIFTER_LOW_GEAR_PORT), m_rightDriveShifter(RIGHT_DRIVE_SHIFTER_PCM, RIGHT_DRIVE_SHIFTER_HIGH_GEAR_PORT, RIGHT_DRIVE_SHIFTER_LOW_GEAR_PORT) { - // try { - // m_gyro = new AHRS(SPI::Port::kMXP); - // } catch (std::exception ex) { - // CORELog::LogError("Error initializing gyro: " + string(ex.what())); - // } } void DriveSubsystem::robotInit() { @@ -32,7 +27,7 @@ void DriveSubsystem::robotInit() { initTalons(); } -void DriveSubsystem::auton() { +void DriveSubsystem::auton() { // Need to get the units in terms of meters instead of ticks m_odometry.Update(frc::Rotation2d(units::degree_t(getHeading())), units::meter_t(m_leftMaster.GetSelectedSensorPosition(0)), units::meter_t(m_rightMaster.GetSelectedSensorPosition(0))); @@ -137,9 +132,21 @@ void DriveSubsystem::resetEncoders() { m_rightSlave.SetSelectedSensorPosition(0); } +double DriveSubsystem::getStartHeading() { + try { + m_gyro = new AHRS(SPI::Port::kMXP); + SmartDashboard::PutNumber("Gyro value", std::remainder(m_gyro->GetAngle(), 360)); + return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + } catch (std::exception ex) { + std::cout << "Gyro isn't working in get heading!" << endl; + return 0; + } +} + double DriveSubsystem::getHeading() { try { - return std::remainder(m_gyro.GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + SmartDashboard::PutNumber("Gyro Heading", std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0)); + return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } catch (std::exception ex) { std::cout << "Gyro isn't working in get heading!" << endl; return 0; @@ -157,7 +164,7 @@ Pose2d DriveSubsystem::getPose() { double DriveSubsystem::getTurnRate() { try { - return m_gyro.GetRate() * (DriveConstants::kGyroReversed ? -1.0 : 1.0); + return m_gyro->GetRate() * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } catch (std::exception ex) { std::cout << "Gyro isn't working in get turn rate!" << endl; return 0; @@ -190,6 +197,7 @@ void DriveSubsystem::tankDriveVolts(units::volt_t l, units::volt_t r) { m_leftSlave.SetVoltage(r); m_rightMaster.SetVoltage(l); m_rightSlave.SetVoltage(r); + m_drive.Feed(); } diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 4785ede..5babdcb 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -40,6 +40,7 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { void resetEncoders(); void resetOdometry(Pose2d pose); Pose2d getPose(); + double getStartHeading(); double getHeading(); double getTurnRate(); void setMaxOutput(double maxOutput); @@ -67,7 +68,6 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { Compressor compressor; double m_wheelbase = 20.8; double m_trackwidth = 25.881; - // AHRS * m_gyro; - frc::ADXRS450_Gyro m_gyro; + AHRS * m_gyro; int count = 0; }; diff --git a/src/IntakeSubsystem.cpp b/src/IntakeSubsystem.cpp index 878beb4..c10fd3a 100644 --- a/src/IntakeSubsystem.cpp +++ b/src/IntakeSubsystem.cpp @@ -1,43 +1,43 @@ -#include - -IntakeSubsystem::IntakeSubsystem() : m_intakeMotor(INTAKE_PORT), - m_intakeSolenoid(LEFT_DRIVE_SHIFTER_PCM, INTAKE_DOWN_PORT, INTAKE_UP_PORT), - m_intakeSpeed("Intake Speed", 0){ - -} - -void IntakeSubsystem::robotInit(){ - m_intakeMotor.Set(ControlMode::PercentOutput, 0); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::LEFT_TRIGGER); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::LEFT_BUTTON); - m_isIntakeDown = false; -} - -void IntakeSubsystem::teleopInit(){ - -} - -void IntakeSubsystem::teleop(){ - if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::LEFT_TRIGGER)){ - SetIntake(m_intakeSpeed.Get()); - } - else{ - SetIntake(0.0); - } - if (operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::LEFT_BUTTON)) { - ToggleIntake(); - } -} - -void IntakeSubsystem::SetIntake(double intakeSpeed) { - m_intakeMotor.Set(ControlMode::PercentOutput, intakeSpeed); -} -void IntakeSubsystem::ToggleIntake() { - if(m_isIntakeDown) { - m_intakeSolenoid.Set(frc::DoubleSolenoid::kForward); - } else { - m_intakeSolenoid.Set(frc::DoubleSolenoid::kReverse); - } -} - -using namespace CORE; +// #include + +// IntakeSubsystem::IntakeSubsystem() : m_intakeMotor(INTAKE_PORT), +// m_intakeSolenoid(LEFT_DRIVE_SHIFTER_PCM, INTAKE_DOWN_PORT, INTAKE_UP_PORT), +// m_intakeSpeed("Intake Speed", 0){ + +// } + +// void IntakeSubsystem::robotInit(){ +// m_intakeMotor.Set(ControlMode::PercentOutput, 0); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::LEFT_TRIGGER); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::LEFT_BUTTON); +// m_isIntakeDown = false; +// } + +// void IntakeSubsystem::teleopInit(){ + +// } + +// void IntakeSubsystem::teleop(){ +// if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::LEFT_TRIGGER)){ +// SetIntake(m_intakeSpeed.Get()); +// } +// else{ +// SetIntake(0.0); +// } +// if (operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::LEFT_BUTTON)) { +// ToggleIntake(); +// } +// } + +// void IntakeSubsystem::SetIntake(double intakeSpeed) { +// m_intakeMotor.Set(ControlMode::PercentOutput, intakeSpeed); +// } +// void IntakeSubsystem::ToggleIntake() { +// if(m_isIntakeDown) { +// m_intakeSolenoid.Set(frc::DoubleSolenoid::kForward); +// } else { +// m_intakeSolenoid.Set(frc::DoubleSolenoid::kReverse); +// } +// } + +// using namespace CORE; diff --git a/src/IntakeSubsystem.h b/src/IntakeSubsystem.h index 1c03805..e0765aa 100644 --- a/src/IntakeSubsystem.h +++ b/src/IntakeSubsystem.h @@ -1,24 +1,24 @@ -#pragma once +// #pragma once -#include -#include -#include -#include +// #include +// #include +// #include +// #include -using namespace CORE; -using namespace frc; +// using namespace CORE; +// using namespace frc; -class IntakeSubsystem : public CORESubsystem { -public: - IntakeSubsystem(); - void robotInit() override; - void teleopInit() override; - void teleop() override; - void SetIntake(double intakeSpeed); - void ToggleIntake(); -private: - TalonSRX m_intakeMotor; - DoubleSolenoid m_intakeSolenoid; - COREConstant m_intakeSpeed; - bool m_isIntakeDown; -}; \ No newline at end of file +// class IntakeSubsystem : public CORESubsystem { +// public: +// IntakeSubsystem(); +// void robotInit() override; +// void teleopInit() override; +// void teleop() override; +// void SetIntake(double intakeSpeed); +// void ToggleIntake(); +// private: +// TalonSRX m_intakeMotor; +// DoubleSolenoid m_intakeSolenoid; +// COREConstant m_intakeSpeed; +// bool m_isIntakeDown; +// }; \ No newline at end of file diff --git a/src/LauncherSubsystem.cpp b/src/LauncherSubsystem.cpp index 573dc2e..8fc24c4 100644 --- a/src/LauncherSubsystem.cpp +++ b/src/LauncherSubsystem.cpp @@ -1,68 +1,68 @@ -#include -#include +// #include +// #include -using namespace CORE; +// using namespace CORE; -LauncherSubsystem::LauncherSubsystem() : m_topMotor(TOP_LAUNCHER_MOTOR_PORT), - m_bottomMotor(BOTTOM_LAUNCHER_MOTOR_PORT) { -} +// LauncherSubsystem::LauncherSubsystem() : m_topMotor(TOP_LAUNCHER_MOTOR_PORT), +// m_bottomMotor(BOTTOM_LAUNCHER_MOTOR_PORT) { +// } -void LauncherSubsystem::robotInit() { - // Registers joystick axis and buttons, does inital setup for talons - // speed adustment code start #1 - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::A_BUTTON); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::B_BUTTON); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::X_BUTTON); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::Y_BUTTON); - // speed adustment code end #1 - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER); -} +// void LauncherSubsystem::robotInit() { +// // Registers joystick axis and buttons, does inital setup for talons +// // speed adustment code start #1 +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::A_BUTTON); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::B_BUTTON); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::X_BUTTON); +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::Y_BUTTON); +// // speed adustment code end #1 +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER); +// } -void LauncherSubsystem::teleopInit() { - m_topMotorSpeed = 0.50; - m_bottomMotorSpeed = 0.50; -} +// void LauncherSubsystem::teleopInit() { +// m_topMotorSpeed = 0.50; +// m_bottomMotorSpeed = 0.50; +// } -void LauncherSubsystem::teleop() { - bool launcherOn = false; - // speed adustment code start #2 - bool m_yButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::Y_BUTTON); - bool m_aButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::A_BUTTON); - bool m_xButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::X_BUTTON); - bool m_bButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::B_BUTTON); - // speed adustment code end #2 +// void LauncherSubsystem::teleop() { +// bool launcherOn = false; +// // speed adustment code start #2 +// bool m_yButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::Y_BUTTON); +// bool m_aButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::A_BUTTON); +// bool m_xButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::X_BUTTON); +// bool m_bButtonPressed = operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::B_BUTTON); +// // speed adustment code end #2 - if (!launcherOn && operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { - launcherOn = true; - } else if (launcherOn && operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { - launcherOn = false; - } +// if (!launcherOn && operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { +// launcherOn = true; +// } else if (launcherOn && operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { +// launcherOn = false; +// } - // speed adustment code start #3 - // Changes motor speeds - if (m_yButtonPressed && m_topMotorSpeed < 1) { - // Increases top motor speed by 1 percent - m_topMotorSpeed = m_topMotorSpeed + 0.05; - } else if (m_aButtonPressed && (m_topMotorSpeed > -1)) { - // Decreases top motor speed by 1 percent - m_topMotorSpeed = m_topMotorSpeed - 0.05; - } else if (m_xButtonPressed && (m_bottomMotorSpeed < 1)) { - // Increases top motor speed by 1 percent - m_bottomMotorSpeed = m_bottomMotorSpeed + 0.05; - } else if (m_bButtonPressed && (m_bottomMotorSpeed > -1)) { - // Decreases top motor speed by 1 percent - m_bottomMotorSpeed = m_bottomMotorSpeed - 0.05; - } - // speed adustment code end #3 +// // speed adustment code start #3 +// // Changes motor speeds +// if (m_yButtonPressed && m_topMotorSpeed < 1) { +// // Increases top motor speed by 1 percent +// m_topMotorSpeed = m_topMotorSpeed + 0.05; +// } else if (m_aButtonPressed && (m_topMotorSpeed > -1)) { +// // Decreases top motor speed by 1 percent +// m_topMotorSpeed = m_topMotorSpeed - 0.05; +// } else if (m_xButtonPressed && (m_bottomMotorSpeed < 1)) { +// // Increases top motor speed by 1 percent +// m_bottomMotorSpeed = m_bottomMotorSpeed + 0.05; +// } else if (m_bButtonPressed && (m_bottomMotorSpeed > -1)) { +// // Decreases top motor speed by 1 percent +// m_bottomMotorSpeed = m_bottomMotorSpeed - 0.05; +// } +// // speed adustment code end #3 - if (launcherOn) { - m_topMotor.Set(ControlMode::PercentOutput, m_topMotorSpeed); - m_bottomMotor.Set(ControlMode::PercentOutput, m_bottomMotorSpeed); - } else { - m_topMotor.Set(ControlMode::PercentOutput, 0.0); - m_bottomMotor.Set(ControlMode::PercentOutput, 0.0); - } +// if (launcherOn) { +// m_topMotor.Set(ControlMode::PercentOutput, m_topMotorSpeed); +// m_bottomMotor.Set(ControlMode::PercentOutput, m_bottomMotorSpeed); +// } else { +// m_topMotor.Set(ControlMode::PercentOutput, 0.0); +// m_bottomMotor.Set(ControlMode::PercentOutput, 0.0); +// } - SmartDashboard::PutNumber("Top Motor Percent Speed", m_topMotorSpeed); - SmartDashboard::PutNumber("Bottom Motor Percent Speed", m_bottomMotorSpeed); -} +// SmartDashboard::PutNumber("Top Motor Percent Speed", m_topMotorSpeed); +// SmartDashboard::PutNumber("Bottom Motor Percent Speed", m_bottomMotorSpeed); +// } diff --git a/src/LauncherSubsystem.h b/src/LauncherSubsystem.h index 8d3f104..9074187 100644 --- a/src/LauncherSubsystem.h +++ b/src/LauncherSubsystem.h @@ -1,18 +1,18 @@ -#pragma once +// #pragma once -#include -#include -#include +// #include +// #include +// #include -using namespace frc; +// using namespace frc; -class LauncherSubsystem : public CORESubsystem { -public: - LauncherSubsystem(); - void robotInit() override; - void teleopInit() override; - void teleop() override; -private: - TalonSRX m_topMotor, m_bottomMotor; - double m_topMotorSpeed, m_bottomMotorSpeed; -}; \ No newline at end of file +// class LauncherSubsystem : public CORESubsystem { +// public: +// LauncherSubsystem(); +// void robotInit() override; +// void teleopInit() override; +// void teleop() override; +// private: +// TalonSRX m_topMotor, m_bottomMotor; +// double m_topMotorSpeed, m_bottomMotorSpeed; +// }; \ No newline at end of file diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 4dd9744..09f616f 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -1,9 +1,3 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 FIRST. All Rights Reserved. */ -/* Open Source Software - may be modified and shared by FRC teams. The code */ -/* must be accompanied by the FIRST BSD license file in the root directory of */ -/* the project. */ -/*----------------------------------------------------------------------------*/ #include "RobotContainer.h" @@ -21,7 +15,15 @@ #include "Constants.h" RobotContainer::RobotContainer() { + // Initialize all of your commands and subsystems here + // Set up default drive command + m_drive.SetDefaultCommand(frc2::RunCommand( + [this] { + m_drive.driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::LEFT_STICK_Y); + m_drive.driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::RIGHT_STICK_X); + }, + {&m_drive})); } frc2::Command* RobotContainer::GetAutonomousCommand() { @@ -29,13 +31,13 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( frc::SimpleMotorFeedforward( DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), - kDriveKinematics, 10_V); + DriveConstants::kDriveKinematics, 10_V); // Set up config for trajectory frc::TrajectoryConfig config(AutoConstants::kMaxSpeed, AutoConstants::kMaxAcceleration); // Add kinematics to ensure max speed is actually obeyed - config.SetKinematics(kDriveKinematics); + config.SetKinematics(DriveConstants::kDriveKinematics); // Apply the voltage constraint config.AddConstraint(autoVoltageConstraint); @@ -56,7 +58,7 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { AutoConstants::kRamseteZeta), frc::SimpleMotorFeedforward( DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), - kDriveKinematics, + DriveConstants::kDriveKinematics, [this] { return m_drive.getWheelSpeeds(); }, frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), diff --git a/src/RobotContainer.h b/src/RobotContainer.h index 9b2f189..fa610ab 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -1,13 +1,6 @@ -/*----------------------------------------------------------------------------*/ -/* Copyright (c) 2019 FIRST. All Rights Reserved. */ -/* Open Source Software - may be modified and shared by FRC teams. The code */ -/* must be accompanied by the FIRST BSD license file in the root directory of */ -/* the project. */ -/*----------------------------------------------------------------------------*/ #pragma once -#include #include #include #include @@ -18,8 +11,9 @@ #include "Constants.h" #include "DriveSubsystem.h" +#include "CORERobotLib.h" -using namespace DriveConstants; +using namespace CORE; class RobotContainer { public: @@ -28,7 +22,10 @@ class RobotContainer { frc2::Command* GetAutonomousCommand(); private: - + + // The robot's subsystems and commands are defined here... + + // The robot's subsystems DriveSubsystem m_drive; // The chooser for the autonomous routines diff --git a/src/TurretSubsystem.cpp b/src/TurretSubsystem.cpp index 42b4b47..6dd879e 100644 --- a/src/TurretSubsystem.cpp +++ b/src/TurretSubsystem.cpp @@ -1,62 +1,62 @@ -#include - -TurretSubsystem::TurretSubsystem(): m_turret(TURRET_PORT), - m_KP("KP", 0.0005), - m_KI("KI", 0), - m_KD("KD",0), - m_KF("KF",0), - corePID(0, 0, 0, 0) { - std::cout << "Turret Subsystem constructer called" << std::endl; -} - -void TurretSubsystem::robotInit() { - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::X_BUTTON); - InitTalons(); - // start NetworkTables - ntinst = nt::NetworkTableInstance::GetDefault(); - ntinst.StartClientTeam(2062); - -} - -void TurretSubsystem::teleopInit() { - m_startupTurretPosition = m_turret.GetSelectedSensorPosition(0); -} - -void TurretSubsystem::teleop() { - corePID.SetDerivativeConstant(m_KD.Get()); - corePID.SetFeedForwardConstant(m_KF.Get()); - corePID.SetIntegralConstant(m_KI.Get()); - corePID.SetProportionalConstant(m_KP.Get()); - auto table = ntinst.GetTable("limelight"); - bool hasCenterX = table->GetNumber("tv", 0.0) == 1; - double conversion = 4096 / -360; // convert degrees to ticks - // calculate center error as a percent output for the motor - double centerError = table->GetNumber("tx", 0.0) * conversion; - double motorPercent = corePID.Calculate(centerError); - bool atLeftStop = m_turret.GetSelectedSensorPosition(0) < (m_startupTurretPosition - 468.0); - bool atRightStop = m_turret.GetSelectedSensorPosition(0) > (m_startupTurretPosition + 468.0); - bool xButtonPressed = operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::X_BUTTON); - if (hasCenterX && xButtonPressed && ((!atRightStop && centerError < 0) || (!atLeftStop && centerError > 0))) { - SetTurret(motorPercent); - } else { - SetTurret(0.0); - } - - SmartDashboard::PutNumber("Turret position", m_turret.GetSelectedSensorPosition(0)); - SmartDashboard::PutNumber("Center Error", centerError); - SmartDashboard::PutBoolean("HasTable", hasCenterX); - SmartDashboard::PutBoolean("At Left Stop", atLeftStop); - SmartDashboard::PutBoolean("At Right Stop", atRightStop); - SmartDashboard::PutBoolean("X Button Pressed", operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::X_BUTTON)); -} - -void TurretSubsystem::SetTurret(double turretPercent) { - m_turret.Set(ControlMode::PercentOutput, turretPercent); -} - -void TurretSubsystem::InitTalons() { - // Sets up talons - m_turret.Set(ControlMode::PercentOutput, 0); - // Zero the sensor - m_turret.SetSelectedSensorPosition(0, 0, 10); -} +// #include + +// TurretSubsystem::TurretSubsystem(): m_turret(TURRET_PORT), +// m_KP("KP", 0.0005), +// m_KI("KI", 0), +// m_KD("KD",0), +// m_KF("KF",0), +// corePID(0, 0, 0, 0) { +// std::cout << "Turret Subsystem constructer called" << std::endl; +// } + +// void TurretSubsystem::robotInit() { +// operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::X_BUTTON); +// InitTalons(); +// // start NetworkTables +// ntinst = nt::NetworkTableInstance::GetDefault(); +// ntinst.StartClientTeam(2062); + +// } + +// void TurretSubsystem::teleopInit() { +// m_startupTurretPosition = m_turret.GetSelectedSensorPosition(0); +// } + +// void TurretSubsystem::teleop() { +// corePID.SetDerivativeConstant(m_KD.Get()); +// corePID.SetFeedForwardConstant(m_KF.Get()); +// corePID.SetIntegralConstant(m_KI.Get()); +// corePID.SetProportionalConstant(m_KP.Get()); +// auto table = ntinst.GetTable("limelight"); +// bool hasCenterX = table->GetNumber("tv", 0.0) == 1; +// double conversion = 4096 / -360; // convert degrees to ticks +// // calculate center error as a percent output for the motor +// double centerError = table->GetNumber("tx", 0.0) * conversion; +// double motorPercent = corePID.Calculate(centerError); +// bool atLeftStop = m_turret.GetSelectedSensorPosition(0) < (m_startupTurretPosition - 468.0); +// bool atRightStop = m_turret.GetSelectedSensorPosition(0) > (m_startupTurretPosition + 468.0); +// bool xButtonPressed = operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::X_BUTTON); +// if (hasCenterX && xButtonPressed && ((!atRightStop && centerError < 0) || (!atLeftStop && centerError > 0))) { +// SetTurret(motorPercent); +// } else { +// SetTurret(0.0); +// } + +// SmartDashboard::PutNumber("Turret position", m_turret.GetSelectedSensorPosition(0)); +// SmartDashboard::PutNumber("Center Error", centerError); +// SmartDashboard::PutBoolean("HasTable", hasCenterX); +// SmartDashboard::PutBoolean("At Left Stop", atLeftStop); +// SmartDashboard::PutBoolean("At Right Stop", atRightStop); +// SmartDashboard::PutBoolean("X Button Pressed", operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::X_BUTTON)); +// } + +// void TurretSubsystem::SetTurret(double turretPercent) { +// m_turret.Set(ControlMode::PercentOutput, turretPercent); +// } + +// void TurretSubsystem::InitTalons() { +// // Sets up talons +// m_turret.Set(ControlMode::PercentOutput, 0); +// // Zero the sensor +// m_turret.SetSelectedSensorPosition(0, 0, 10); +// } diff --git a/src/TurretSubsystem.h b/src/TurretSubsystem.h index c791319..ce2842f 100644 --- a/src/TurretSubsystem.h +++ b/src/TurretSubsystem.h @@ -1,26 +1,26 @@ -#pragma once +// #pragma once -#include -#include -#include -#include -#include +// #include +// #include +// #include +// #include +// #include -using namespace CORE; +// using namespace CORE; -class TurretSubsystem : public CORESubsystem { -private: - TalonSRX m_turret; - double m_startupTurretPosition; - nt::NetworkTableInstance ntinst; - COREConstant m_KP, m_KI, m_KD, m_KF; - COREPID corePID; +// class TurretSubsystem : public CORESubsystem { +// private: +// TalonSRX m_turret; +// double m_startupTurretPosition; +// nt::NetworkTableInstance ntinst; +// COREConstant m_KP, m_KI, m_KD, m_KF; +// COREPID corePID; -public: - TurretSubsystem(); - void robotInit() override; - void teleopInit() override; - void teleop() override; - void InitTalons(); - void SetTurret(double turretPercent); -}; +// public: +// TurretSubsystem(); +// void robotInit() override; +// void teleopInit() override; +// void teleop() override; +// void InitTalons(); +// void SetTurret(double turretPercent); +// }; From b72705d3dabdd59cbf21971ca40ec54882eeb381 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sun, 23 Feb 2020 15:05:03 -0600 Subject: [PATCH 13/31] Code doesn't crash - teleop works but diff drive isn't fed fast enough --- PathWeaver/Paths/example.path | 3 + PathWeaver/output/example.wpilib.json | 1 + PathWeaver/pathweaver.json | 8 +++ src/AutonActionTest.cpp | 40 ++++++------- src/AutonActionTest.h | 36 ++++++------ src/Autonomous/Actions/PathFinder.cpp | 70 +++++++++++++++++++++++ src/Autonomous/Actions/PathFinder.h | 22 +++---- src/Autonomous/TestAuton.cpp | 0 src/Autonomous/TestAuton.h | 0 src/DriveSubsystem.cpp | 6 +- src/DriveSubsystem.h | 8 +-- src/Robot.cpp | 5 ++ src/Robot.h | 14 +++-- src/autonomous/Auton.cpp | 16 +++--- src/autonomous/Auton.h | 28 ++++----- src/main/deploy/paths/example.wpilib.json | 1 + 16 files changed, 177 insertions(+), 81 deletions(-) create mode 100644 PathWeaver/Paths/example.path create mode 100644 PathWeaver/output/example.wpilib.json create mode 100644 PathWeaver/pathweaver.json delete mode 100644 src/Autonomous/TestAuton.cpp delete mode 100644 src/Autonomous/TestAuton.h create mode 100644 src/main/deploy/paths/example.wpilib.json diff --git a/PathWeaver/Paths/example.path b/PathWeaver/Paths/example.path new file mode 100644 index 0000000..ccf8475 --- /dev/null +++ b/PathWeaver/Paths/example.path @@ -0,0 +1,3 @@ +X,Y,Tangent X,Tangent Y,Fixed Theta,Name +0.0,0.0,3.048,0.0,true, +3.048,-3.048,1.5970701000629752,0.08586483241200771,true, diff --git a/PathWeaver/output/example.wpilib.json b/PathWeaver/output/example.wpilib.json new file mode 100644 index 0000000..cb6be5b --- /dev/null +++ b/PathWeaver/output/example.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":71.81853462273233,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.05154902732371937,"velocity":3.7021756036167144,"acceleration":-14.570586583617095,"pose":{"translation":{"x":0.0954175591874795,"y":-8.970348306178012E-4},"rotation":{"radians":-0.027650615332535523}},"curvature":-0.5555721590079611},{"time":0.07911903361344792,"velocity":3.3004644398613565,"acceleration":-7.210458670385726,"pose":{"translation":{"x":0.19176609884113538,"y":-0.006836141893059719},"rotation":{"radians":-0.10181937409911292}},"curvature":-0.9490656990275671},{"time":0.09426195644257385,"velocity":3.1912770206531036,"acceleration":-3.8275391053665806,"pose":{"translation":{"x":0.24052673799069652,"y":-0.013026151812177424},"rotation":{"radians":-0.15174007207787038}},"curvature":-1.0731419939317515},{"time":0.11009725577470761,"velocity":3.1306667932141763,"acceleration":-1.1455564555144113,"pose":{"translation":{"x":0.28977907417078114,"y":-0.02195386324792068},"rotation":{"radians":-0.20750053729514634}},"curvature":-1.1457526465583436},{"time":0.12651322391898032,"velocity":3.1118613749329858,"acceleration":0.9880141343238242,"pose":{"translation":{"x":0.3395834530119897,"y":-0.03399193143522784},"rotation":{"radians":-0.2670122588274609}},"curvature":-1.1688563545650115},{"time":0.14341110021863882,"velocity":3.128556715557104,"acceleration":2.6456659292549394,"pose":{"translation":{"x":0.389988609914771,"y":-0.049459184600208664},"rotation":{"radians":-0.32827964422324374}},"curvature":-1.148331183382902},{"time":0.16071185073581556,"velocity":3.174328721750938,"acceleration":3.8639398380608503,"pose":{"translation":{"x":0.441032156511579,"y":-0.0686226965918421},"rotation":{"radians":-0.38952006570031844}},"curvature":-1.0931666695325097},{"time":0.17836062833768684,"velocity":3.2425225366198847,"acceleration":4.672338159109252,"pose":{"translation":{"x":0.4927410671290303,"y":-0.09169985951367407},"rotation":{"radians":-0.44925799963162055}},"curvature":-1.0138680069811143},{"time":0.19632774121794166,"velocity":3.3264709637393226,"acceleration":5.110317311095119,"pose":{"translation":{"x":0.5451321652500615,"y":-0.11886045635551529},"rotation":{"radians":-0.5063736770642954}},"curvature":-0.9207139869212123},{"time":0.21460616461634946,"velocity":3.419879507251732,"acceleration":5.233210546194306,"pose":{"translation":{"x":0.5982126099760859,"y":-0.15022873362513905},"rotation":{"radians":-0.5601030251974476}},"curvature":-0.8224379042703561},{"time":0.23320658618430956,"velocity":3.517219429564841,"acceleration":5.109065552075489,"pose":{"translation":{"x":0.6519803824891512,"y":-0.18588547397997904},"rotation":{"radians":-0.6099993845273901}},"curvature":-0.7255796794556587},{"time":0.2521513382713219,"velocity":3.614009409845206,"acceleration":4.810311089326068,"pose":{"translation":{"x":0.7064247725140964,"y":-0.225870068858827},"rotation":{"radians":-0.6558736580963799}},"curvature":-0.6344421110814962},{"time":0.2714684065329755,"velocity":3.706930517517507,"acceleration":4.404711130561586,"pose":{"translation":{"x":0.7615268647807092,"y":-0.2701825911135307},"rotation":{"radians":-0.6977285910792212}},"curvature":-0.5514252264221119},{"time":0.29118628283685577,"velocity":3.793782066744245,"acceleration":3.9488070643090403,"pose":{"translation":{"x":0.8172600254858828,"y":-0.3187858676406917},"rotation":{"radians":-0.7356980906193501}},"curvature":-0.4775078535713296},{"time":0.3113299982726776,"velocity":3.8733257125586493,"acceleration":3.4850043042255767,"pose":{"translation":{"x":0.8735903887557737,"y":-0.37160755201336304},"rotation":{"radians":-0.7699971388185597}},"curvature":-0.4127183171142323},{"time":0.3319183569834702,"velocity":3.9450762312827017,"acceleration":3.041814848512116,"pose":{"translation":{"x":0.9304773431079583,"y":-0.42854219711274705},"rotation":{"radians":-0.8008837421565934}},"curvature":-0.35651765850700873},{"time":0.3529622164440334,"velocity":4.009087755459845,"acceleration":2.6360324587810537,"pose":{"translation":{"x":0.9878740179135905,"y":-0.48945332775989314},"rotation":{"radians":-0.8286319356988368}},"curvature":-0.30807667140802825},{"time":0.3744635940778765,"velocity":4.065766084811164,"acceleration":2.2756390699688773,"pose":{"translation":{"x":1.045727769859559,"y":-0.554175513347396},"rotation":{"radians":-0.8535138107447635}},"curvature":-0.26645832053513274},{"time":0.3964153808599162,"velocity":4.115720428468,"acceleration":1.9626199435440872,"pose":{"translation":{"x":1.103980669410644,"y":-0.6225164404710924},"rotation":{"radians":-0.8757883499385072}},"curvature":-0.23072768177274236},{"time":0.4188014748101557,"velocity":4.159655822912792,"acceleration":1.69527930582718,"pose":{"translation":{"x":1.1625699872716748,"y":-0.6942589855617601},"rotation":{"radians":-0.8956951014436992}},"curvature":-0.20001151310088602},{"time":0.4415971888007184,"velocity":4.198300925102548,"acceleration":1.4699484357724757,"pose":{"translation":{"x":1.2214286808496868,"y":-0.7691632875168153},"rotation":{"radians":-0.9134511227235513}},"curvature":-0.17352533617146237},{"time":0.4647698263131177,"velocity":4.232363507366622,"acceleration":1.2821427428554832,"pose":{"translation":{"x":1.2804858807160786,"y":-0.8469688203320094},"rotation":{"radians":-0.9292500252615125}},"curvature":-0.1505809300594235},{"time":0.4882793510791383,"velocity":4.2625060739333565,"acceleration":1.1272878683827954,"pose":{"translation":{"x":1.3396673770687697,"y":-0.927396465733129},"rotation":{"radians":-0.9432622910059878}},"curvature":-0.13058286232681732},{"time":0.5120791010832051,"velocity":4.289335243383484,"acceleration":1.0011404901357241,"pose":{"translation":{"x":1.3988961061943574,"y":-1.010150585807691},"rotation":{"radians":-0.9556362936086461}},"curvature":-0.1130194860810929},{"time":0.5361165150646032,"velocity":4.313400071798417,"acceleration":0.9000098271463499,"pose":{"translation":{"x":1.4580926369302736,"y":-1.0949210956366426},"rotation":{"radians":-0.966499648626333}},"curvature":-0.09745162972922349},{"time":0.5603338518432681,"velocity":4.335195912886528,"acceleration":0.8208598473160442,"pose":{"translation":{"x":1.5171756571269421,"y":-1.181385535926058},"rotation":{"radians":-0.9759606502724327}},"curvature":-0.08350077098730027},{"time":0.5846688908967251,"velocity":4.355171569328379,"acceleration":0.7613488359955657,"pose":{"translation":{"x":1.5760624601099376,"y":-1.269211145638837},"rotation":{"radians":-0.9841096421884397}},"curvature":-0.07083758920433708},{"time":0.6090556078020036,"velocity":4.373738367857966,"acceleration":0.7198453794943244,"pose":{"translation":{"x":1.6346694311421397,"y":-1.3580569346264015},"rotation":{"radians":-0.9910202281418624}},"curvature":-0.05917124638340661},{"time":0.6334248213148449,"velocity":4.391280433607095,"acceleration":0.6954482609667484,"pose":{"translation":{"x":1.6929125338858921,"y":-1.447575756260394},"rotation":{"radians":-0.9967502648754831}},"curvature":-0.048239424685084},{"time":0.6577048106319545,"velocity":4.40816590995397,"acceleration":0.6880316153597182,"pose":{"translation":{"x":1.7507077968651603,"y":-1.5374163800643763},"rotation":{"radians":-1.00134260031699}},"curvature":-0.0377989561052516},{"time":0.6818219022155111,"velocity":4.424759231433983,"acceleration":0.6983353154572598,"pose":{"translation":{"x":1.807971799927687,"y":-1.6272255643455256},"rotation":{"radians":-1.004825530716281}},"curvature":-0.02761675829336551},{"time":0.7057010257488948,"velocity":4.441434866699511,"acceleration":0.7281238420974316,"pose":{"translation":{"x":1.8646221607071505,"y":-1.7166501288263332},"rotation":{"radians":-1.0072129531455787}},"curvature":-0.017460699081779364},{"time":0.7292662385270009,"velocity":4.4585932599673495,"acceleration":0.23889919002521667,"pose":{"translation":{"x":1.9205780210853223,"y":-1.8053390272763021},"rotation":{"radians":-1.008504187157782}},"curvature":-0.007089923341650348},{"time":0.7524737936799106,"velocity":4.464137526095845,"acceleration":-0.8418057704981504,"pose":{"translation":{"x":1.9757605336542223,"y":-1.8929454201436466},"rotation":{"radians":-1.0086834324076666}},"curvature":0.0037559323176499996},{"time":0.7753450862975656,"velocity":4.444884339991551,"acceleration":-0.9276777489993119,"pose":{"translation":{"x":2.030093348178279,"y":-1.979128747186985},"rotation":{"radians":-1.0077188182728354}},"curvature":0.015369358317897666},{"time":0.7978741011542355,"velocity":4.423984674202144,"acceleration":-1.0466704059158933,"pose":{"translation":{"x":2.0835030980564837,"y":-2.063556800107043},"rotation":{"radians":-1.0055609871508069}},"curvature":0.028090352121107495},{"time":0.8199975497641668,"velocity":4.400828715265328,"acceleration":-1.2066809299530705,"pose":{"translation":{"x":2.13591988678455,"y":-2.145907795178352},"rotation":{"radians":-1.0021411351255256}},"curvature":0.04232577816829033},{"time":0.8416570536654623,"velocity":4.37469260495539,"acceleration":-1.418413476156303,"pose":{"translation":{"x":2.18727777441707,"y":-2.2258724458809374},"rotation":{"radians":-0.9973684120631896}},"curvature":0.058574332428376834},{"time":0.8627999817275045,"velocity":4.344703190866786,"acceleration":-1.696131586806757,"pose":{"translation":{"x":2.2375152640296703,"y":-2.3031560355320284},"rotation":{"radians":-0.9911265582240422}},"curvature":0.07745929395032254},{"time":0.8833803741956509,"velocity":4.309796137132683,"acceleration":-2.0585371487899393,"pose":{"translation":{"x":2.286575788181171,"y":-2.377480489917751},"rotation":{"radians":-0.9832696274112916}},"curvature":0.09977199426284837},{"time":0.9033599711776307,"velocity":4.2686673945274265,"acceleration":-2.5296668683770758,"pose":{"translation":{"x":2.334408195375744,"y":-2.448586449924819},"rotation":{"radians":-0.9736166208148695}},"curvature":0.126529902884793},{"time":0.9227093650443854,"velocity":4.2197198739395185,"acceleration":-3.13953191681287,"pose":{"translation":{"x":2.3809672365250667,"y":-2.516235344172248},"rotation":{"radians":-0.9619448384531385}},"curvature":0.1590543960728061},{"time":0.9414092958496307,"velocity":4.161010844334259,"acceleration":-3.923919629505293,"pose":{"translation":{"x":2.426214051410481,"y":-2.580211461643035},"rotation":{"radians":-0.9479817617955386}},"curvature":0.19907449993361534},{"time":0.9594521036665412,"velocity":4.090212316570092,"acceleration":-4.922264584156884,"pose":{"translation":{"x":2.470116655145152,"y":-2.64032402431587},"rotation":{"radians":-0.9313953419033538}},"curvature":0.24886371793784065},{"time":0.976843336659243,"velocity":4.004608066335296,"acceleration":-6.17176774912248,"pose":{"translation":{"x":2.5126504246362225,"y":-2.6964092597968197},"rotation":{"radians":-0.9117827393816472}},"curvature":0.31141629925925174},{"time":0.9936034797059252,"velocity":3.9011683560091024,"acceleration":-8.55718066284625,"pose":{"translation":{"x":2.553798585046971,"y":-2.748332473951045},"rotation":{"radians":-0.8886579503447547}},"curvature":0.3906643088738414},{"time":1.0254537904752927,"velocity":3.628619492587828,"acceleration":-12.39662532879157,"pose":{"translation":{"x":2.631913139334245,"y":-2.8393118888255486},"rotation":{"radians":-0.8294412165109983}},"curvature":0.6211075800749466},{"time":1.0554677982545575,"velocity":3.2565470835328463,"acceleration":-15.10365161937661,"pose":{"translation":{"x":2.7045015699979063,"y":-2.9128450410468005},"rotation":{"radians":-0.7478462937091639}},"curvature":0.9979714067421676},{"time":1.069996742378132,"velocity":3.0371069730929885,"acceleration":-16.121922307845313,"pose":{"translation":{"x":2.7387788037720053,"y":-2.943100559831496},"rotation":{"radians":-0.696449348504947}},"curvature":1.263526319883902},{"time":1.08437649814755,"velocity":2.805277667772641,"acceleration":-16.100629398551472,"pose":{"translation":{"x":2.7717618347051216,"y":-2.969112603296221},"rotation":{"radians":-0.6368349398617001}},"curvature":1.5892041297400166},{"time":1.098711758885972,"velocity":2.5744709472917022,"acceleration":-14.800160225656162,"pose":{"translation":{"x":2.803502446693888,"y":-2.991008058807253},"rotation":{"radians":-0.5684342434947216}},"curvature":1.9717120030565085},{"time":1.113071966199183,"velocity":2.36193757818254,"acceleration":-12.189730557682944,"pose":{"translation":{"x":2.834064163588331,"y":-3.0089594730435323},"rotation":{"radians":-0.4912701719368094}},"curvature":2.390049211507602},{"time":1.1274565781948793,"velocity":2.1865930337781876,"acceleration":-9.452729526839338,"pose":{"translation":{"x":2.8635227356540307,"y":-3.0231871246283717},"rotation":{"radians":-0.40636987322213675}},"curvature":2.796409874573135},{"time":1.1346436226350656,"velocity":2.1186558465877323,"acceleration":-7.261194760818502,"pose":{"translation":{"x":2.877865477209893,"y":-3.0289869382615286},"rotation":{"radians":-0.36171741909431643}},"curvature":2.971933250793703},{"time":1.1417887663201607,"velocity":2.066773566696225,"acceleration":-4.773090124541358,"pose":{"translation":{"x":2.8919666260342733,"y":-3.0339610967611286},"rotation":{"radians":-0.31617091433168876}},"curvature":3.1137480375494775},{"time":1.148858246984371,"velocity":2.033030298352247,"acceleration":-1.9397716793931767,"pose":{"translation":{"x":2.905839306217418,"y":-3.0381514825332516},"rotation":{"radians":-0.2702880476444087}},"curvature":3.2098663582418205},{"time":1.1558106862534079,"velocity":2.019544153555468,"acceleration":1.3391284277157562,"pose":{"translation":{"x":2.919497497212209,"y":-3.0416033498489305},"rotation":{"radians":-0.22471642031179453}},"curvature":3.2491802821627607},{"time":1.162598455705074,"velocity":2.0286338485889748,"acceleration":5.241105012252983,"pose":{"translation":{"x":2.932956049036088,"y":-3.044365389613901},"rotation":{"radians":-0.18017420926151867}},"curvature":3.222625174251699},{"time":1.1691695815568548,"velocity":2.0630738092268883,"acceleration":13.159857369971245,"pose":{"translation":{"x":2.9462306974730144,"y":-3.046489794138356},"rotation":{"radians":-0.13742445513049514}},"curvature":3.1241333931057906},{"time":1.1813884049609846,"velocity":2.2238717824541028,"acceleration":30.872761161060968,"pose":{"translation":{"x":2.9722957473660427,"y":-3.0490523623471475},"rotation":{"radians":-0.060405926038590844}},"curvature":2.704652833577455},{"time":1.192083993719446,"velocity":2.5540741396710116,"acceleration":-64.97980757793125,"pose":{"translation":{"x":2.997836826166983,"y":-3.0497810822958833},"rotation":{"radians":3.9174549638033244E-4}},"curvature":2.008839569414959},{"time":1.2313896524290056,"velocity":0.0,"acceleration":-64.97980757793125,"pose":{"translation":{"x":3.048000000000002,"y":-3.048000000000002},"rotation":{"radians":0.05371225908084613}},"curvature":-1.1691366233348565E-14}] \ No newline at end of file diff --git a/PathWeaver/pathweaver.json b/PathWeaver/pathweaver.json new file mode 100644 index 0000000..934fa17 --- /dev/null +++ b/PathWeaver/pathweaver.json @@ -0,0 +1,8 @@ +{ + "lengthUnit": "Meter", + "maxVelocity": 4.4704, + "maxAcceleration": 90.0, + "wheelBase": 0.747, + "gameName": "Destination: Deep Space", + "outputDir": "" +} \ No newline at end of file diff --git a/src/AutonActionTest.cpp b/src/AutonActionTest.cpp index d4ffe68..db2e039 100644 --- a/src/AutonActionTest.cpp +++ b/src/AutonActionTest.cpp @@ -1,28 +1,28 @@ -#include -#include +// #include +// #include -AutonomousAction1::AutonomousAction1() {} +// AutonomousAction1::AutonomousAction1() {} -void AutonomousAction1::ActionInit() { - COREScheduler::teleopInit(); -} +// void AutonomousAction1::ActionInit() { +// COREScheduler::teleopInit(); +// } -CORE::COREAutonAction::actionStatus AutonomousAction1::Action() { - Robot::GetInstance()->driveSubsystem.setMotorSpeed(0.2, 0.2); - return COREAutonAction::actionStatus::CONTINUE; -} +// CORE::COREAutonAction::actionStatus AutonomousAction1::Action() { +// Robot::GetInstance()->driveSubsystem.setMotorSpeed(0.2, 0.2); +// return COREAutonAction::actionStatus::CONTINUE; +// } -void AutonomousAction1::ActionEnd() {} +// void AutonomousAction1::ActionEnd() {} -AutonomousAction2::AutonomousAction2() {} +// AutonomousAction2::AutonomousAction2() {} -void AutonomousAction2::ActionInit() { - COREScheduler::teleopInit(); -} +// void AutonomousAction2::ActionInit() { +// COREScheduler::teleopInit(); +// } -CORE::COREAutonAction::actionStatus AutonomousAction2::Action() { - Robot::GetInstance()->driveSubsystem.setMotorSpeed(-0.2, -0.2); - return COREAutonAction::actionStatus::CONTINUE; -} +// CORE::COREAutonAction::actionStatus AutonomousAction2::Action() { +// Robot::GetInstance()->driveSubsystem.setMotorSpeed(-0.2, -0.2); +// return COREAutonAction::actionStatus::CONTINUE; +// } -void AutonomousAction2::ActionEnd() {} +// void AutonomousAction2::ActionEnd() {} diff --git a/src/AutonActionTest.h b/src/AutonActionTest.h index 64765be..3a67593 100644 --- a/src/AutonActionTest.h +++ b/src/AutonActionTest.h @@ -1,23 +1,23 @@ -#pragma once +// #pragma once -#include -#include +// #include +// #include -using namespace CORE; +// using namespace CORE; -class AutonomousAction1 : public COREAutonAction { -public: - AutonomousAction1(); - void ActionInit() override; - CORE::COREAutonAction::actionStatus Action() override; - void ActionEnd() override; -}; +// class AutonomousAction1 : public COREAutonAction { +// public: +// AutonomousAction1(); +// void ActionInit() override; +// CORE::COREAutonAction::actionStatus Action() override; +// void ActionEnd() override; +// }; -class AutonomousAction2 : public COREAutonAction { -public: - AutonomousAction2(); - void ActionInit() override; - CORE::COREAutonAction::actionStatus Action() override; - void ActionEnd() override; -}; +// class AutonomousAction2 : public COREAutonAction { +// public: +// AutonomousAction2(); +// void ActionInit() override; +// CORE::COREAutonAction::actionStatus Action() override; +// void ActionEnd() override; +// }; diff --git a/src/Autonomous/Actions/PathFinder.cpp b/src/Autonomous/Actions/PathFinder.cpp index e69de29..e202f18 100644 --- a/src/Autonomous/Actions/PathFinder.cpp +++ b/src/Autonomous/Actions/PathFinder.cpp @@ -0,0 +1,70 @@ +#include "PathFinder.h" +// #include +// #include +// #include +// #include +// #include + +// wpi::SmallString<64> deployDirectory; +// frc::filesystem::GetDeployDirectory(deployDirectory); +// wpi::sys::path::append(deployDirectory, "paths"); +// wpi::sys::path::append(deployDirectory, "YourPath.wpilib.json"); + +// frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); + +void PathFinderAction::ActionInit() { + +} + +CORE::COREAutonAction::actionStatus PathFinderAction::Action() { + +} + +void PathFinderAction::ActionEnd() { + +} + +// frc2::Command* RobotContainer::GetAutonomousCommand() { +// // Create a voltage constraint to ensure we don't accelerate too fast +// frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( +// frc::SimpleMotorFeedforward( +// DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), +// DriveConstants::kDriveKinematics, 10_V); + +// // Set up config for trajectory +// frc::TrajectoryConfig config(AutoConstants::kMaxSpeed, +// AutoConstants::kMaxAcceleration); +// // Add kinematics to ensure max speed is actually obeyed +// config.SetKinematics(DriveConstants::kDriveKinematics); +// // Apply the voltage constraint +// config.AddConstraint(autoVoltageConstraint); + +// // An example trajectory to follow. All units in meters. +// auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory( +// // Start at the origin facing the +X direction +// frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)), +// // Pass through these two interior waypoints, making an 's' curve path +// {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)}, +// // End 3 meters straight ahead of where we started, facing forward +// frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)), +// // Pass the config +// config); + +// frc2::RamseteCommand ramseteCommand( +// exampleTrajectory, [this]() { return m_drive.getPose(); }, +// frc::RamseteController(AutoConstants::kRamseteB, +// AutoConstants::kRamseteZeta), +// frc::SimpleMotorFeedforward( +// DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), +// DriveConstants::kDriveKinematics, +// [this] { return m_drive.getWheelSpeeds(); }, +// frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), +// frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), +// [this](auto left, auto right) { m_drive.tankDriveVolts(left, right); }, +// {&m_drive}); + +// // no auto +// return new frc2::SequentialCommandGroup( +// std::move(ramseteCommand), +// frc2::InstantCommand([this] { m_drive.tankDriveVolts(0_V, 0_V); }, {})); +// } diff --git a/src/Autonomous/Actions/PathFinder.h b/src/Autonomous/Actions/PathFinder.h index 869d3fa..86f9596 100644 --- a/src/Autonomous/Actions/PathFinder.h +++ b/src/Autonomous/Actions/PathFinder.h @@ -1,13 +1,15 @@ -#include -#include -#include -#include -#include -wpi::SmallString<64> deployDirectory; -frc::filesystem::GetDeployDirectory(deployDirectory); -wpi::sys::path::append(deployDirectory, "paths"); -wpi::sys::path::append(deployDirectory, "YourPath.wpilib.json"); +#pragma once -frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); +#include "CORERobotLib.h" +using namespace CORE; + +class PathFinderAction : public COREAutonAction { +public: + explicit PathFinderAction(); + void ActionInit() override; + actionStatus Action() override; + void ActionEnd() override; +private: +}; \ No newline at end of file diff --git a/src/Autonomous/TestAuton.cpp b/src/Autonomous/TestAuton.cpp deleted file mode 100644 index e69de29..0000000 diff --git a/src/Autonomous/TestAuton.h b/src/Autonomous/TestAuton.h deleted file mode 100644 index e69de29..0000000 diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index e244f76..1685c29 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -209,8 +209,10 @@ void DriveSubsystem::setVelocity(double leftVelocity, double rightVelocity) { } frc::DifferentialDriveWheelSpeeds DriveSubsystem::getWheelSpeeds() { - return {units::meters_per_second_t(m_leftMaster.GetSelectedSensorVelocity(0) * (10.0 / 4096) * m_wheelCircumference), - units::meters_per_second_t(m_rightMaster.GetSelectedSensorVelocity(0) * (10.0 / 4096) * m_wheelCircumference)}; + double right = m_rightMaster.GetSelectedSensorVelocity(0) * (10.0 / 4096) * m_wheelCircumference; + double left = m_leftMaster.GetSelectedSensorVelocity(0) * (10.0 / 4096) * m_wheelCircumference; + return {units::meters_per_second_t(left), + units::meters_per_second_t(right)}; } void DriveSubsystem::setMaxOutput(double maxOutput) { diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 5babdcb..3372e63 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -52,16 +52,16 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { WPI_TalonSRX& getLeftSlave(); void setVelocity(double leftVelocity, double rightVelocity); DifferentialDriveWheelSpeeds getWheelSpeeds(); - SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; - SpeedControllerGroup m_rightMotors{m_rightSlave, m_rightMaster}; - DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; DifferentialDriveOdometry m_odometry; COREConstant m_driveTurnkP; COREVector path; private: double m_wheelCircumference = 0.4787787204; - WPI_TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; + WPI_TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; + SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; + SpeedControllerGroup m_rightMotors{m_rightSlave, m_rightMaster}; + DifferentialDrive m_drive{m_leftMotors, m_rightMotors}; COREConstant m_etherAValue, m_etherBValue, m_etherQuickTurnValue, m_ticksPerInch; DoubleSolenoid m_leftDriveShifter, m_rightDriveShifter; bool m_highGear; diff --git a/src/Robot.cpp b/src/Robot.cpp index bb0ef22..1a174a5 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -11,6 +11,11 @@ void Robot::teleop() { } void Robot::robotInit() { + wpi::SmallString<64> deployDirectory; + frc::filesystem::GetDeployDirectory(deployDirectory); + wpi::sys::path::append(deployDirectory, "paths"); + wpi::sys::path::append(deployDirectory, "example.wpilib.json"); + frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); } diff --git a/src/Robot.h b/src/Robot.h index 1757b63..c4b4196 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -11,13 +11,17 @@ #include #include #include +#include +#include +#include +#include #include /* Drive ports */ -#define RIGHT_FRONT_PORT 20 -#define RIGHT_BACK_PORT 1 -#define LEFT_FRONT_PORT 19 -#define LEFT_BACK_PORT 32 +#define LEFT_FRONT_PORT 11 +#define LEFT_BACK_PORT 10 +#define RIGHT_FRONT_PORT 12 +#define RIGHT_BACK_PORT 13 #define INTAKE_PORT 14 #define CONVEYOR_1_PORT 15 #define CONVEYOR_2_PORT 16 @@ -53,7 +57,7 @@ class Robot : public CORERobot { void testInit() override; static Robot * GetInstance(); DriveSubsystem driveSubsystem; - Autonomous controlledAutonomous; + // Autonomous controlledAutonomous; private: static Robot * m_instance; }; \ No newline at end of file diff --git a/src/autonomous/Auton.cpp b/src/autonomous/Auton.cpp index e496395..92a045d 100644 --- a/src/autonomous/Auton.cpp +++ b/src/autonomous/Auton.cpp @@ -1,10 +1,10 @@ -#include +// #include -Autonomous::Autonomous() : COREAuton("Test Auto") {} +// Autonomous::Autonomous() : COREAuton("Test Auto") {} -void Autonomous::AddNodes() { - autonNode1 = new Node(5, new AutonomousAction1()); - autonNode2 = new Node(5, new AutonomousAction2()); - AddFirstNode(autonNode1); - autonNode1->AddNext(autonNode2); -} +// void Autonomous::AddNodes() { +// autonNode1 = new Node(5, new AutonomousAction1()); +// autonNode2 = new Node(5, new AutonomousAction2()); +// AddFirstNode(autonNode1); +// autonNode1->AddNext(autonNode2); +// } diff --git a/src/autonomous/Auton.h b/src/autonomous/Auton.h index 5efd415..c2ef152 100644 --- a/src/autonomous/Auton.h +++ b/src/autonomous/Auton.h @@ -1,17 +1,17 @@ -#pragma once +// #pragma once -#include -#include -#include +// #include +// #include +// #include -using namespace CORE; -using namespace std; +// using namespace CORE; +// using namespace std; -class Autonomous: public COREAuton { -public: - Autonomous(); - void AddNodes() override; -private: - Node * autonNode1; - Node * autonNode2; -}; +// class Autonomous: public COREAuton { +// public: +// Autonomous(); +// void AddNodes() override; +// private: +// Node * autonNode1; +// Node * autonNode2; +// }; diff --git a/src/main/deploy/paths/example.wpilib.json b/src/main/deploy/paths/example.wpilib.json new file mode 100644 index 0000000..cb6be5b --- /dev/null +++ b/src/main/deploy/paths/example.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":71.81853462273233,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.05154902732371937,"velocity":3.7021756036167144,"acceleration":-14.570586583617095,"pose":{"translation":{"x":0.0954175591874795,"y":-8.970348306178012E-4},"rotation":{"radians":-0.027650615332535523}},"curvature":-0.5555721590079611},{"time":0.07911903361344792,"velocity":3.3004644398613565,"acceleration":-7.210458670385726,"pose":{"translation":{"x":0.19176609884113538,"y":-0.006836141893059719},"rotation":{"radians":-0.10181937409911292}},"curvature":-0.9490656990275671},{"time":0.09426195644257385,"velocity":3.1912770206531036,"acceleration":-3.8275391053665806,"pose":{"translation":{"x":0.24052673799069652,"y":-0.013026151812177424},"rotation":{"radians":-0.15174007207787038}},"curvature":-1.0731419939317515},{"time":0.11009725577470761,"velocity":3.1306667932141763,"acceleration":-1.1455564555144113,"pose":{"translation":{"x":0.28977907417078114,"y":-0.02195386324792068},"rotation":{"radians":-0.20750053729514634}},"curvature":-1.1457526465583436},{"time":0.12651322391898032,"velocity":3.1118613749329858,"acceleration":0.9880141343238242,"pose":{"translation":{"x":0.3395834530119897,"y":-0.03399193143522784},"rotation":{"radians":-0.2670122588274609}},"curvature":-1.1688563545650115},{"time":0.14341110021863882,"velocity":3.128556715557104,"acceleration":2.6456659292549394,"pose":{"translation":{"x":0.389988609914771,"y":-0.049459184600208664},"rotation":{"radians":-0.32827964422324374}},"curvature":-1.148331183382902},{"time":0.16071185073581556,"velocity":3.174328721750938,"acceleration":3.8639398380608503,"pose":{"translation":{"x":0.441032156511579,"y":-0.0686226965918421},"rotation":{"radians":-0.38952006570031844}},"curvature":-1.0931666695325097},{"time":0.17836062833768684,"velocity":3.2425225366198847,"acceleration":4.672338159109252,"pose":{"translation":{"x":0.4927410671290303,"y":-0.09169985951367407},"rotation":{"radians":-0.44925799963162055}},"curvature":-1.0138680069811143},{"time":0.19632774121794166,"velocity":3.3264709637393226,"acceleration":5.110317311095119,"pose":{"translation":{"x":0.5451321652500615,"y":-0.11886045635551529},"rotation":{"radians":-0.5063736770642954}},"curvature":-0.9207139869212123},{"time":0.21460616461634946,"velocity":3.419879507251732,"acceleration":5.233210546194306,"pose":{"translation":{"x":0.5982126099760859,"y":-0.15022873362513905},"rotation":{"radians":-0.5601030251974476}},"curvature":-0.8224379042703561},{"time":0.23320658618430956,"velocity":3.517219429564841,"acceleration":5.109065552075489,"pose":{"translation":{"x":0.6519803824891512,"y":-0.18588547397997904},"rotation":{"radians":-0.6099993845273901}},"curvature":-0.7255796794556587},{"time":0.2521513382713219,"velocity":3.614009409845206,"acceleration":4.810311089326068,"pose":{"translation":{"x":0.7064247725140964,"y":-0.225870068858827},"rotation":{"radians":-0.6558736580963799}},"curvature":-0.6344421110814962},{"time":0.2714684065329755,"velocity":3.706930517517507,"acceleration":4.404711130561586,"pose":{"translation":{"x":0.7615268647807092,"y":-0.2701825911135307},"rotation":{"radians":-0.6977285910792212}},"curvature":-0.5514252264221119},{"time":0.29118628283685577,"velocity":3.793782066744245,"acceleration":3.9488070643090403,"pose":{"translation":{"x":0.8172600254858828,"y":-0.3187858676406917},"rotation":{"radians":-0.7356980906193501}},"curvature":-0.4775078535713296},{"time":0.3113299982726776,"velocity":3.8733257125586493,"acceleration":3.4850043042255767,"pose":{"translation":{"x":0.8735903887557737,"y":-0.37160755201336304},"rotation":{"radians":-0.7699971388185597}},"curvature":-0.4127183171142323},{"time":0.3319183569834702,"velocity":3.9450762312827017,"acceleration":3.041814848512116,"pose":{"translation":{"x":0.9304773431079583,"y":-0.42854219711274705},"rotation":{"radians":-0.8008837421565934}},"curvature":-0.35651765850700873},{"time":0.3529622164440334,"velocity":4.009087755459845,"acceleration":2.6360324587810537,"pose":{"translation":{"x":0.9878740179135905,"y":-0.48945332775989314},"rotation":{"radians":-0.8286319356988368}},"curvature":-0.30807667140802825},{"time":0.3744635940778765,"velocity":4.065766084811164,"acceleration":2.2756390699688773,"pose":{"translation":{"x":1.045727769859559,"y":-0.554175513347396},"rotation":{"radians":-0.8535138107447635}},"curvature":-0.26645832053513274},{"time":0.3964153808599162,"velocity":4.115720428468,"acceleration":1.9626199435440872,"pose":{"translation":{"x":1.103980669410644,"y":-0.6225164404710924},"rotation":{"radians":-0.8757883499385072}},"curvature":-0.23072768177274236},{"time":0.4188014748101557,"velocity":4.159655822912792,"acceleration":1.69527930582718,"pose":{"translation":{"x":1.1625699872716748,"y":-0.6942589855617601},"rotation":{"radians":-0.8956951014436992}},"curvature":-0.20001151310088602},{"time":0.4415971888007184,"velocity":4.198300925102548,"acceleration":1.4699484357724757,"pose":{"translation":{"x":1.2214286808496868,"y":-0.7691632875168153},"rotation":{"radians":-0.9134511227235513}},"curvature":-0.17352533617146237},{"time":0.4647698263131177,"velocity":4.232363507366622,"acceleration":1.2821427428554832,"pose":{"translation":{"x":1.2804858807160786,"y":-0.8469688203320094},"rotation":{"radians":-0.9292500252615125}},"curvature":-0.1505809300594235},{"time":0.4882793510791383,"velocity":4.2625060739333565,"acceleration":1.1272878683827954,"pose":{"translation":{"x":1.3396673770687697,"y":-0.927396465733129},"rotation":{"radians":-0.9432622910059878}},"curvature":-0.13058286232681732},{"time":0.5120791010832051,"velocity":4.289335243383484,"acceleration":1.0011404901357241,"pose":{"translation":{"x":1.3988961061943574,"y":-1.010150585807691},"rotation":{"radians":-0.9556362936086461}},"curvature":-0.1130194860810929},{"time":0.5361165150646032,"velocity":4.313400071798417,"acceleration":0.9000098271463499,"pose":{"translation":{"x":1.4580926369302736,"y":-1.0949210956366426},"rotation":{"radians":-0.966499648626333}},"curvature":-0.09745162972922349},{"time":0.5603338518432681,"velocity":4.335195912886528,"acceleration":0.8208598473160442,"pose":{"translation":{"x":1.5171756571269421,"y":-1.181385535926058},"rotation":{"radians":-0.9759606502724327}},"curvature":-0.08350077098730027},{"time":0.5846688908967251,"velocity":4.355171569328379,"acceleration":0.7613488359955657,"pose":{"translation":{"x":1.5760624601099376,"y":-1.269211145638837},"rotation":{"radians":-0.9841096421884397}},"curvature":-0.07083758920433708},{"time":0.6090556078020036,"velocity":4.373738367857966,"acceleration":0.7198453794943244,"pose":{"translation":{"x":1.6346694311421397,"y":-1.3580569346264015},"rotation":{"radians":-0.9910202281418624}},"curvature":-0.05917124638340661},{"time":0.6334248213148449,"velocity":4.391280433607095,"acceleration":0.6954482609667484,"pose":{"translation":{"x":1.6929125338858921,"y":-1.447575756260394},"rotation":{"radians":-0.9967502648754831}},"curvature":-0.048239424685084},{"time":0.6577048106319545,"velocity":4.40816590995397,"acceleration":0.6880316153597182,"pose":{"translation":{"x":1.7507077968651603,"y":-1.5374163800643763},"rotation":{"radians":-1.00134260031699}},"curvature":-0.0377989561052516},{"time":0.6818219022155111,"velocity":4.424759231433983,"acceleration":0.6983353154572598,"pose":{"translation":{"x":1.807971799927687,"y":-1.6272255643455256},"rotation":{"radians":-1.004825530716281}},"curvature":-0.02761675829336551},{"time":0.7057010257488948,"velocity":4.441434866699511,"acceleration":0.7281238420974316,"pose":{"translation":{"x":1.8646221607071505,"y":-1.7166501288263332},"rotation":{"radians":-1.0072129531455787}},"curvature":-0.017460699081779364},{"time":0.7292662385270009,"velocity":4.4585932599673495,"acceleration":0.23889919002521667,"pose":{"translation":{"x":1.9205780210853223,"y":-1.8053390272763021},"rotation":{"radians":-1.008504187157782}},"curvature":-0.007089923341650348},{"time":0.7524737936799106,"velocity":4.464137526095845,"acceleration":-0.8418057704981504,"pose":{"translation":{"x":1.9757605336542223,"y":-1.8929454201436466},"rotation":{"radians":-1.0086834324076666}},"curvature":0.0037559323176499996},{"time":0.7753450862975656,"velocity":4.444884339991551,"acceleration":-0.9276777489993119,"pose":{"translation":{"x":2.030093348178279,"y":-1.979128747186985},"rotation":{"radians":-1.0077188182728354}},"curvature":0.015369358317897666},{"time":0.7978741011542355,"velocity":4.423984674202144,"acceleration":-1.0466704059158933,"pose":{"translation":{"x":2.0835030980564837,"y":-2.063556800107043},"rotation":{"radians":-1.0055609871508069}},"curvature":0.028090352121107495},{"time":0.8199975497641668,"velocity":4.400828715265328,"acceleration":-1.2066809299530705,"pose":{"translation":{"x":2.13591988678455,"y":-2.145907795178352},"rotation":{"radians":-1.0021411351255256}},"curvature":0.04232577816829033},{"time":0.8416570536654623,"velocity":4.37469260495539,"acceleration":-1.418413476156303,"pose":{"translation":{"x":2.18727777441707,"y":-2.2258724458809374},"rotation":{"radians":-0.9973684120631896}},"curvature":0.058574332428376834},{"time":0.8627999817275045,"velocity":4.344703190866786,"acceleration":-1.696131586806757,"pose":{"translation":{"x":2.2375152640296703,"y":-2.3031560355320284},"rotation":{"radians":-0.9911265582240422}},"curvature":0.07745929395032254},{"time":0.8833803741956509,"velocity":4.309796137132683,"acceleration":-2.0585371487899393,"pose":{"translation":{"x":2.286575788181171,"y":-2.377480489917751},"rotation":{"radians":-0.9832696274112916}},"curvature":0.09977199426284837},{"time":0.9033599711776307,"velocity":4.2686673945274265,"acceleration":-2.5296668683770758,"pose":{"translation":{"x":2.334408195375744,"y":-2.448586449924819},"rotation":{"radians":-0.9736166208148695}},"curvature":0.126529902884793},{"time":0.9227093650443854,"velocity":4.2197198739395185,"acceleration":-3.13953191681287,"pose":{"translation":{"x":2.3809672365250667,"y":-2.516235344172248},"rotation":{"radians":-0.9619448384531385}},"curvature":0.1590543960728061},{"time":0.9414092958496307,"velocity":4.161010844334259,"acceleration":-3.923919629505293,"pose":{"translation":{"x":2.426214051410481,"y":-2.580211461643035},"rotation":{"radians":-0.9479817617955386}},"curvature":0.19907449993361534},{"time":0.9594521036665412,"velocity":4.090212316570092,"acceleration":-4.922264584156884,"pose":{"translation":{"x":2.470116655145152,"y":-2.64032402431587},"rotation":{"radians":-0.9313953419033538}},"curvature":0.24886371793784065},{"time":0.976843336659243,"velocity":4.004608066335296,"acceleration":-6.17176774912248,"pose":{"translation":{"x":2.5126504246362225,"y":-2.6964092597968197},"rotation":{"radians":-0.9117827393816472}},"curvature":0.31141629925925174},{"time":0.9936034797059252,"velocity":3.9011683560091024,"acceleration":-8.55718066284625,"pose":{"translation":{"x":2.553798585046971,"y":-2.748332473951045},"rotation":{"radians":-0.8886579503447547}},"curvature":0.3906643088738414},{"time":1.0254537904752927,"velocity":3.628619492587828,"acceleration":-12.39662532879157,"pose":{"translation":{"x":2.631913139334245,"y":-2.8393118888255486},"rotation":{"radians":-0.8294412165109983}},"curvature":0.6211075800749466},{"time":1.0554677982545575,"velocity":3.2565470835328463,"acceleration":-15.10365161937661,"pose":{"translation":{"x":2.7045015699979063,"y":-2.9128450410468005},"rotation":{"radians":-0.7478462937091639}},"curvature":0.9979714067421676},{"time":1.069996742378132,"velocity":3.0371069730929885,"acceleration":-16.121922307845313,"pose":{"translation":{"x":2.7387788037720053,"y":-2.943100559831496},"rotation":{"radians":-0.696449348504947}},"curvature":1.263526319883902},{"time":1.08437649814755,"velocity":2.805277667772641,"acceleration":-16.100629398551472,"pose":{"translation":{"x":2.7717618347051216,"y":-2.969112603296221},"rotation":{"radians":-0.6368349398617001}},"curvature":1.5892041297400166},{"time":1.098711758885972,"velocity":2.5744709472917022,"acceleration":-14.800160225656162,"pose":{"translation":{"x":2.803502446693888,"y":-2.991008058807253},"rotation":{"radians":-0.5684342434947216}},"curvature":1.9717120030565085},{"time":1.113071966199183,"velocity":2.36193757818254,"acceleration":-12.189730557682944,"pose":{"translation":{"x":2.834064163588331,"y":-3.0089594730435323},"rotation":{"radians":-0.4912701719368094}},"curvature":2.390049211507602},{"time":1.1274565781948793,"velocity":2.1865930337781876,"acceleration":-9.452729526839338,"pose":{"translation":{"x":2.8635227356540307,"y":-3.0231871246283717},"rotation":{"radians":-0.40636987322213675}},"curvature":2.796409874573135},{"time":1.1346436226350656,"velocity":2.1186558465877323,"acceleration":-7.261194760818502,"pose":{"translation":{"x":2.877865477209893,"y":-3.0289869382615286},"rotation":{"radians":-0.36171741909431643}},"curvature":2.971933250793703},{"time":1.1417887663201607,"velocity":2.066773566696225,"acceleration":-4.773090124541358,"pose":{"translation":{"x":2.8919666260342733,"y":-3.0339610967611286},"rotation":{"radians":-0.31617091433168876}},"curvature":3.1137480375494775},{"time":1.148858246984371,"velocity":2.033030298352247,"acceleration":-1.9397716793931767,"pose":{"translation":{"x":2.905839306217418,"y":-3.0381514825332516},"rotation":{"radians":-0.2702880476444087}},"curvature":3.2098663582418205},{"time":1.1558106862534079,"velocity":2.019544153555468,"acceleration":1.3391284277157562,"pose":{"translation":{"x":2.919497497212209,"y":-3.0416033498489305},"rotation":{"radians":-0.22471642031179453}},"curvature":3.2491802821627607},{"time":1.162598455705074,"velocity":2.0286338485889748,"acceleration":5.241105012252983,"pose":{"translation":{"x":2.932956049036088,"y":-3.044365389613901},"rotation":{"radians":-0.18017420926151867}},"curvature":3.222625174251699},{"time":1.1691695815568548,"velocity":2.0630738092268883,"acceleration":13.159857369971245,"pose":{"translation":{"x":2.9462306974730144,"y":-3.046489794138356},"rotation":{"radians":-0.13742445513049514}},"curvature":3.1241333931057906},{"time":1.1813884049609846,"velocity":2.2238717824541028,"acceleration":30.872761161060968,"pose":{"translation":{"x":2.9722957473660427,"y":-3.0490523623471475},"rotation":{"radians":-0.060405926038590844}},"curvature":2.704652833577455},{"time":1.192083993719446,"velocity":2.5540741396710116,"acceleration":-64.97980757793125,"pose":{"translation":{"x":2.997836826166983,"y":-3.0497810822958833},"rotation":{"radians":3.9174549638033244E-4}},"curvature":2.008839569414959},{"time":1.2313896524290056,"velocity":0.0,"acceleration":-64.97980757793125,"pose":{"translation":{"x":3.048000000000002,"y":-3.048000000000002},"rotation":{"radians":0.05371225908084613}},"curvature":-1.1691366233348565E-14}] \ No newline at end of file From 7f414cb20a702ecd9103ae45886c860457082191 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sun, 23 Feb 2020 15:40:59 -0600 Subject: [PATCH 14/31] still having timeout problem --- PathWeaver/Paths/example.path | 4 ++-- src/DriveSubsystem.cpp | 7 ++----- src/Robot.cpp | 9 +++++++++ src/Robot.h | 5 +++++ 4 files changed, 18 insertions(+), 7 deletions(-) diff --git a/PathWeaver/Paths/example.path b/PathWeaver/Paths/example.path index ccf8475..d6ee0ad 100644 --- a/PathWeaver/Paths/example.path +++ b/PathWeaver/Paths/example.path @@ -1,3 +1,3 @@ X,Y,Tangent X,Tangent Y,Fixed Theta,Name -0.0,0.0,3.048,0.0,true, -3.048,-3.048,1.5970701000629752,0.08586483241200771,true, +0.0,0.0,3.096751790637463,0.01226579525575619,true, +3.5653218053320264,-2.7176638555734374,2.6688118228255537,0.06111782800363885,true, diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 1685c29..7944586 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -193,12 +193,9 @@ WPI_TalonSRX& DriveSubsystem::getLeftSlave() { void DriveSubsystem::tankDriveVolts(units::volt_t l, units::volt_t r) { - m_leftMaster.SetVoltage(l); - m_leftSlave.SetVoltage(r); - m_rightMaster.SetVoltage(l); - m_rightSlave.SetVoltage(r); + m_leftMotors.SetVoltage(l); + m_rightMotors.SetVoltage(r); m_drive.Feed(); - } void DriveSubsystem::setVelocity(double leftVelocity, double rightVelocity) { diff --git a/src/Robot.cpp b/src/Robot.cpp index 1a174a5..74cca23 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -19,6 +19,15 @@ void Robot::robotInit() { } +void Robot::AutonomousInit() { + CORERobot::AutonomousInit(); + m_autonomousCommand = m_container.GetAutonomousCommand(); + + if (m_autonomousCommand != nullptr) { + m_autonomousCommand->Schedule(); + } +} + void Robot::teleopInit() { } diff --git a/src/Robot.h b/src/Robot.h index c4b4196..0f0db82 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -13,6 +13,8 @@ #include #include #include +#include +#include #include #include #include @@ -50,6 +52,7 @@ using namespace std; class Robot : public CORERobot { public: Robot(); + void AutonomousInit() override; void robotInit() override; void teleopInit() override; void teleop() override; @@ -57,7 +60,9 @@ class Robot : public CORERobot { void testInit() override; static Robot * GetInstance(); DriveSubsystem driveSubsystem; + RobotContainer m_container; // Autonomous controlledAutonomous; private: + frc2::Command* m_autonomousCommand = nullptr; static Robot * m_instance; }; \ No newline at end of file From d6e9b960576f7a87bbdce63c927071820585f80c Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 25 Feb 2020 20:15:01 -0600 Subject: [PATCH 15/31] Got the paths to run in autonomous with an auton action --- src/Autonomous/Actions/PathFinder.cpp | 67 ++++----------------------- src/Autonomous/Actions/PathFinder.h | 4 ++ src/Robot.cpp | 9 +--- src/Robot.h | 7 +-- src/autonomous/Auton.cpp | 14 +++--- src/autonomous/Auton.h | 27 ++++++----- 6 files changed, 39 insertions(+), 89 deletions(-) diff --git a/src/Autonomous/Actions/PathFinder.cpp b/src/Autonomous/Actions/PathFinder.cpp index e202f18..4865b02 100644 --- a/src/Autonomous/Actions/PathFinder.cpp +++ b/src/Autonomous/Actions/PathFinder.cpp @@ -1,70 +1,23 @@ #include "PathFinder.h" -// #include -// #include -// #include -// #include -// #include +#include "Robot.h" -// wpi::SmallString<64> deployDirectory; -// frc::filesystem::GetDeployDirectory(deployDirectory); -// wpi::sys::path::append(deployDirectory, "paths"); -// wpi::sys::path::append(deployDirectory, "YourPath.wpilib.json"); - -// frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); +PathFinderAction::PathFinderAction() { + // m_path = path; +} void PathFinderAction::ActionInit() { } CORE::COREAutonAction::actionStatus PathFinderAction::Action() { - + Robot::GetInstance()->m_driveSubsystem.auton(); + m_autonomousCommand = Robot::GetInstance()->m_container.GetAutonomousCommand(); + if (m_autonomousCommand != nullptr) { + m_autonomousCommand->Schedule(); + } + return COREAutonAction::actionStatus::END; } void PathFinderAction::ActionEnd() { } - -// frc2::Command* RobotContainer::GetAutonomousCommand() { -// // Create a voltage constraint to ensure we don't accelerate too fast -// frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( -// frc::SimpleMotorFeedforward( -// DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), -// DriveConstants::kDriveKinematics, 10_V); - -// // Set up config for trajectory -// frc::TrajectoryConfig config(AutoConstants::kMaxSpeed, -// AutoConstants::kMaxAcceleration); -// // Add kinematics to ensure max speed is actually obeyed -// config.SetKinematics(DriveConstants::kDriveKinematics); -// // Apply the voltage constraint -// config.AddConstraint(autoVoltageConstraint); - -// // An example trajectory to follow. All units in meters. -// auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory( -// // Start at the origin facing the +X direction -// frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)), -// // Pass through these two interior waypoints, making an 's' curve path -// {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)}, -// // End 3 meters straight ahead of where we started, facing forward -// frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)), -// // Pass the config -// config); - -// frc2::RamseteCommand ramseteCommand( -// exampleTrajectory, [this]() { return m_drive.getPose(); }, -// frc::RamseteController(AutoConstants::kRamseteB, -// AutoConstants::kRamseteZeta), -// frc::SimpleMotorFeedforward( -// DriveConstants::ks, DriveConstants::kv, DriveConstants::ka), -// DriveConstants::kDriveKinematics, -// [this] { return m_drive.getWheelSpeeds(); }, -// frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), -// frc2::PIDController(DriveConstants::kPDriveVel, 0, 0), -// [this](auto left, auto right) { m_drive.tankDriveVolts(left, right); }, -// {&m_drive}); - -// // no auto -// return new frc2::SequentialCommandGroup( -// std::move(ramseteCommand), -// frc2::InstantCommand([this] { m_drive.tankDriveVolts(0_V, 0_V); }, {})); -// } diff --git a/src/Autonomous/Actions/PathFinder.h b/src/Autonomous/Actions/PathFinder.h index 86f9596..9cb5593 100644 --- a/src/Autonomous/Actions/PathFinder.h +++ b/src/Autonomous/Actions/PathFinder.h @@ -2,6 +2,8 @@ #pragma once #include "CORERobotLib.h" +#include +#include using namespace CORE; @@ -12,4 +14,6 @@ class PathFinderAction : public COREAutonAction { actionStatus Action() override; void ActionEnd() override; private: + std::string m_path; + frc2::Command* m_autonomousCommand = nullptr; }; \ No newline at end of file diff --git a/src/Robot.cpp b/src/Robot.cpp index 74cca23..c899bc0 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -19,13 +19,8 @@ void Robot::robotInit() { } -void Robot::AutonomousInit() { - CORERobot::AutonomousInit(); - m_autonomousCommand = m_container.GetAutonomousCommand(); - - if (m_autonomousCommand != nullptr) { - m_autonomousCommand->Schedule(); - } +void Robot::RobotPeriodic() { + frc2::CommandScheduler::GetInstance().Run(); } void Robot::teleopInit() { diff --git a/src/Robot.h b/src/Robot.h index 0f0db82..b51c7a3 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -4,6 +4,7 @@ #include #include +#include #include #include #include @@ -52,16 +53,16 @@ using namespace std; class Robot : public CORERobot { public: Robot(); - void AutonomousInit() override; + void RobotPeriodic() override; void robotInit() override; void teleopInit() override; void teleop() override; void test() override; void testInit() override; static Robot * GetInstance(); - DriveSubsystem driveSubsystem; + DriveSubsystem m_driveSubsystem; RobotContainer m_container; - // Autonomous controlledAutonomous; + Autonomous driveAuto; private: frc2::Command* m_autonomousCommand = nullptr; static Robot * m_instance; diff --git a/src/autonomous/Auton.cpp b/src/autonomous/Auton.cpp index 92a045d..a7300f3 100644 --- a/src/autonomous/Auton.cpp +++ b/src/autonomous/Auton.cpp @@ -1,10 +1,8 @@ -// #include +#include -// Autonomous::Autonomous() : COREAuton("Test Auto") {} +Autonomous::Autonomous() : COREAuton("Test Auto") {} -// void Autonomous::AddNodes() { -// autonNode1 = new Node(5, new AutonomousAction1()); -// autonNode2 = new Node(5, new AutonomousAction2()); -// AddFirstNode(autonNode1); -// autonNode1->AddNext(autonNode2); -// } +void Autonomous::AddNodes() { + m_drivePath = new Node(5, new PathFinderAction()); + AddFirstNode(m_drivePath); +} diff --git a/src/autonomous/Auton.h b/src/autonomous/Auton.h index c2ef152..4eaf872 100644 --- a/src/autonomous/Auton.h +++ b/src/autonomous/Auton.h @@ -1,17 +1,16 @@ -// #pragma once +#pragma once -// #include -// #include -// #include +#include +#include +#include -// using namespace CORE; -// using namespace std; +using namespace CORE; +using namespace std; -// class Autonomous: public COREAuton { -// public: -// Autonomous(); -// void AddNodes() override; -// private: -// Node * autonNode1; -// Node * autonNode2; -// }; +class Autonomous: public COREAuton { +public: + Autonomous(); + void AddNodes() override; +private: + Node * m_drivePath; +}; From 4a493217063bdebfa3f1eea4b059f52e056c47b6 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Thu, 27 Feb 2020 18:30:12 -0600 Subject: [PATCH 16/31] Updated version to 2020 --- build.gradle | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/build.gradle b/build.gradle index ded6a12..f5ecfb0 100644 --- a/build.gradle +++ b/build.gradle @@ -1,7 +1,7 @@ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2020.1.2" + id "edu.wpi.first.GradleRIO" version "2020.3.2" } // Define my targets (RoboRIO) and artifacts (deployable files) @@ -60,7 +60,7 @@ model { include '**/*.cpp', '**/*.cc' } exportedHeaders { - srcDir 'src' + srcDir 'src'x srcDirs '../CORERobotLib/src' srcDir "../CORERobotLib/3rdparty/json/src/" if (includeSrcInIncludeRoot) { From 8f4b742bd94c53821c9304573286d68a08726736 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Fri, 28 Feb 2020 19:55:05 -0600 Subject: [PATCH 17/31] Testing for making the drive subsystem work. Doesn't work --- build.gradle | 2 +- src/DriveSubsystem.cpp | 21 +++++++++++++++------ src/DriveSubsystem.h | 4 ++-- src/Robot.cpp | 14 ++++++++++---- src/Robot.h | 3 +++ src/RobotContainer.cpp | 7 +++++-- src/RobotContainer.h | 1 + 7 files changed, 37 insertions(+), 15 deletions(-) diff --git a/build.gradle b/build.gradle index f5ecfb0..c2af389 100644 --- a/build.gradle +++ b/build.gradle @@ -60,7 +60,7 @@ model { include '**/*.cpp', '**/*.cc' } exportedHeaders { - srcDir 'src'x + srcDir 'src' srcDirs '../CORERobotLib/src' srcDir "../CORERobotLib/3rdparty/json/src/" if (includeSrcInIncludeRoot) { diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 7944586..2367ee6 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -27,12 +27,6 @@ void DriveSubsystem::robotInit() { initTalons(); } -void DriveSubsystem::auton() { // Need to get the units in terms of meters instead of ticks - m_odometry.Update(frc::Rotation2d(units::degree_t(getHeading())), - units::meter_t(m_leftMaster.GetSelectedSensorPosition(0)), - units::meter_t(m_rightMaster.GetSelectedSensorPosition(0))); -} - void DriveSubsystem::teleopInit() { // Sets ether drive values, inits talons COREEtherDrive::SetAB(m_etherAValue.Get(), m_etherBValue.Get()); @@ -40,11 +34,26 @@ void DriveSubsystem::teleopInit() { initTalons(); } +void DriveSubsystem::auton() { + m_odometry.Update(frc::Rotation2d(units::degree_t(getHeading())), + units::meter_t(m_leftMaster.GetSelectedSensorPosition(0)), + units::meter_t(m_rightMaster.GetSelectedSensorPosition(0))); +} + +void DriveSubsystem::Periodic() { + m_odometry.Update(frc::Rotation2d(units::degree_t(getHeading())), + units::meter_t(m_leftMaster.GetSelectedSensorPosition(0)), + units::meter_t(m_rightMaster.GetSelectedSensorPosition(0))); +} + void DriveSubsystem::teleop() { // Code for teleop. Sets motor speed based on the values for the joystick, runs compressor, // toggles gears double mag = -driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::LEFT_STICK_Y); + SmartDashboard::PutNumber("mag", mag); + std::cout << "mag" << endl; double rot = driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::RIGHT_STICK_X); + SmartDashboard::PutNumber("rot", rot); VelocityPair speeds = COREEtherDrive::Calculate(mag, rot, .1); setMotorSpeed(speeds.left, speeds.right); diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 3372e63..40c458f 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -28,9 +28,9 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { void robotInit() override; void teleopInit() override; void teleop() override; - void auton(); + void Periodic() override; void teleopEnd() override; - + void auton(); void initTalons(); void setMotorSpeed(double speedInFraction, DriveSide whichSide); diff --git a/src/Robot.cpp b/src/Robot.cpp index c899bc0..50baa8f 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -6,10 +6,6 @@ Robot::Robot() { m_instance = this; } -void Robot::teleop() { - -} - void Robot::robotInit() { wpi::SmallString<64> deployDirectory; frc::filesystem::GetDeployDirectory(deployDirectory); @@ -23,6 +19,11 @@ void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); } +void Robot::TeleopPeriodic() { + std::cout << "running teleop periodic" << endl; + m_driveSubsystem.teleop(); +} + void Robot::teleopInit() { } @@ -31,6 +32,11 @@ void Robot::test() { } +void Robot::teleop() { + std::cout << "running teleop" << endl; + m_driveSubsystem.teleop(); +} + void Robot::testInit() { } diff --git a/src/Robot.h b/src/Robot.h index b51c7a3..e37af9b 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -13,12 +13,14 @@ #include #include #include +#include #include #include #include #include #include #include +#include /* Drive ports */ #define LEFT_FRONT_PORT 11 @@ -54,6 +56,7 @@ class Robot : public CORERobot { public: Robot(); void RobotPeriodic() override; + void TeleopPeriodic() override; void robotInit() override; void teleopInit() override; void teleop() override; diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 09f616f..a31db4f 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -20,12 +20,15 @@ RobotContainer::RobotContainer() { // Set up default drive command m_drive.SetDefaultCommand(frc2::RunCommand( [this] { - m_drive.driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::LEFT_STICK_Y); - m_drive.driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::RIGHT_STICK_X); + m_drive.teleop(); }, {&m_drive})); } +frc2::Command* RobotContainer::GetTeleopDriveCommand() { + m_drive.teleop(); +} + frc2::Command* RobotContainer::GetAutonomousCommand() { // Create a voltage constraint to ensure we don't accelerate too fast frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( diff --git a/src/RobotContainer.h b/src/RobotContainer.h index fa610ab..b362c29 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -20,6 +20,7 @@ class RobotContainer { RobotContainer(); frc2::Command* GetAutonomousCommand(); + frc2::Command* GetTeleopDriveCommand(); private: From a29d727038a6abb15c126cb10f0c33e81146e5e2 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 29 Feb 2020 09:24:21 -0600 Subject: [PATCH 18/31] Got a WPILib joystick to work with the pathfinder --- src/Constants.h | 6 +----- src/DriveSubsystem.cpp | 6 +++--- src/DriveSubsystem.h | 2 ++ 3 files changed, 6 insertions(+), 8 deletions(-) diff --git a/src/Constants.h b/src/Constants.h index 35ee25b..a1ad24c 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -43,8 +43,4 @@ constexpr auto kMaxAcceleration = 3_mps_sq; // seconds constexpr double kRamseteB = 2; constexpr double kRamseteZeta = 0.7; -} // namespace AutoConstants - -namespace OIConstants { -constexpr int kDriverControllerPort = 1; -} // namespace OIConstants \ No newline at end of file +} // namespace AutoConstants \ No newline at end of file diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 2367ee6..cfd86e4 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -49,10 +49,10 @@ void DriveSubsystem::Periodic() { void DriveSubsystem::teleop() { // Code for teleop. Sets motor speed based on the values for the joystick, runs compressor, // toggles gears - double mag = -driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::LEFT_STICK_Y); + double mag = -m_controller.GetY(frc::GenericHID::kLeftHand); SmartDashboard::PutNumber("mag", mag); - std::cout << "mag" << endl; - double rot = driverJoystick->GetAxis(CORE::COREJoystick::JoystickAxis::RIGHT_STICK_X); + std::cout << mag << endl; + double rot = m_controller.GetX(frc::GenericHID::kRightHand); SmartDashboard::PutNumber("rot", rot); VelocityPair speeds = COREEtherDrive::Calculate(mag, rot, .1); diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 40c458f..699d886 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -57,6 +58,7 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { COREConstant m_driveTurnkP; COREVector path; private: + XboxController m_controller{0}; double m_wheelCircumference = 0.4787787204; WPI_TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; From 24331eea351992580da5abb6aa32fd3d70a52503 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 29 Feb 2020 14:38:55 -0600 Subject: [PATCH 19/31] Changed pathweaver to 2020 field version --- PathWeaver/output/example.wpilib.json | 2 +- PathWeaver/pathweaver.json | 5 +++-- src/DriveSubsystem.cpp | 3 ++- src/main/deploy/paths/example.wpilib.json | 2 +- 4 files changed, 7 insertions(+), 5 deletions(-) diff --git a/PathWeaver/output/example.wpilib.json b/PathWeaver/output/example.wpilib.json index cb6be5b..667ae69 100644 --- a/PathWeaver/output/example.wpilib.json +++ b/PathWeaver/output/example.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":71.81853462273233,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.05154902732371937,"velocity":3.7021756036167144,"acceleration":-14.570586583617095,"pose":{"translation":{"x":0.0954175591874795,"y":-8.970348306178012E-4},"rotation":{"radians":-0.027650615332535523}},"curvature":-0.5555721590079611},{"time":0.07911903361344792,"velocity":3.3004644398613565,"acceleration":-7.210458670385726,"pose":{"translation":{"x":0.19176609884113538,"y":-0.006836141893059719},"rotation":{"radians":-0.10181937409911292}},"curvature":-0.9490656990275671},{"time":0.09426195644257385,"velocity":3.1912770206531036,"acceleration":-3.8275391053665806,"pose":{"translation":{"x":0.24052673799069652,"y":-0.013026151812177424},"rotation":{"radians":-0.15174007207787038}},"curvature":-1.0731419939317515},{"time":0.11009725577470761,"velocity":3.1306667932141763,"acceleration":-1.1455564555144113,"pose":{"translation":{"x":0.28977907417078114,"y":-0.02195386324792068},"rotation":{"radians":-0.20750053729514634}},"curvature":-1.1457526465583436},{"time":0.12651322391898032,"velocity":3.1118613749329858,"acceleration":0.9880141343238242,"pose":{"translation":{"x":0.3395834530119897,"y":-0.03399193143522784},"rotation":{"radians":-0.2670122588274609}},"curvature":-1.1688563545650115},{"time":0.14341110021863882,"velocity":3.128556715557104,"acceleration":2.6456659292549394,"pose":{"translation":{"x":0.389988609914771,"y":-0.049459184600208664},"rotation":{"radians":-0.32827964422324374}},"curvature":-1.148331183382902},{"time":0.16071185073581556,"velocity":3.174328721750938,"acceleration":3.8639398380608503,"pose":{"translation":{"x":0.441032156511579,"y":-0.0686226965918421},"rotation":{"radians":-0.38952006570031844}},"curvature":-1.0931666695325097},{"time":0.17836062833768684,"velocity":3.2425225366198847,"acceleration":4.672338159109252,"pose":{"translation":{"x":0.4927410671290303,"y":-0.09169985951367407},"rotation":{"radians":-0.44925799963162055}},"curvature":-1.0138680069811143},{"time":0.19632774121794166,"velocity":3.3264709637393226,"acceleration":5.110317311095119,"pose":{"translation":{"x":0.5451321652500615,"y":-0.11886045635551529},"rotation":{"radians":-0.5063736770642954}},"curvature":-0.9207139869212123},{"time":0.21460616461634946,"velocity":3.419879507251732,"acceleration":5.233210546194306,"pose":{"translation":{"x":0.5982126099760859,"y":-0.15022873362513905},"rotation":{"radians":-0.5601030251974476}},"curvature":-0.8224379042703561},{"time":0.23320658618430956,"velocity":3.517219429564841,"acceleration":5.109065552075489,"pose":{"translation":{"x":0.6519803824891512,"y":-0.18588547397997904},"rotation":{"radians":-0.6099993845273901}},"curvature":-0.7255796794556587},{"time":0.2521513382713219,"velocity":3.614009409845206,"acceleration":4.810311089326068,"pose":{"translation":{"x":0.7064247725140964,"y":-0.225870068858827},"rotation":{"radians":-0.6558736580963799}},"curvature":-0.6344421110814962},{"time":0.2714684065329755,"velocity":3.706930517517507,"acceleration":4.404711130561586,"pose":{"translation":{"x":0.7615268647807092,"y":-0.2701825911135307},"rotation":{"radians":-0.6977285910792212}},"curvature":-0.5514252264221119},{"time":0.29118628283685577,"velocity":3.793782066744245,"acceleration":3.9488070643090403,"pose":{"translation":{"x":0.8172600254858828,"y":-0.3187858676406917},"rotation":{"radians":-0.7356980906193501}},"curvature":-0.4775078535713296},{"time":0.3113299982726776,"velocity":3.8733257125586493,"acceleration":3.4850043042255767,"pose":{"translation":{"x":0.8735903887557737,"y":-0.37160755201336304},"rotation":{"radians":-0.7699971388185597}},"curvature":-0.4127183171142323},{"time":0.3319183569834702,"velocity":3.9450762312827017,"acceleration":3.041814848512116,"pose":{"translation":{"x":0.9304773431079583,"y":-0.42854219711274705},"rotation":{"radians":-0.8008837421565934}},"curvature":-0.35651765850700873},{"time":0.3529622164440334,"velocity":4.009087755459845,"acceleration":2.6360324587810537,"pose":{"translation":{"x":0.9878740179135905,"y":-0.48945332775989314},"rotation":{"radians":-0.8286319356988368}},"curvature":-0.30807667140802825},{"time":0.3744635940778765,"velocity":4.065766084811164,"acceleration":2.2756390699688773,"pose":{"translation":{"x":1.045727769859559,"y":-0.554175513347396},"rotation":{"radians":-0.8535138107447635}},"curvature":-0.26645832053513274},{"time":0.3964153808599162,"velocity":4.115720428468,"acceleration":1.9626199435440872,"pose":{"translation":{"x":1.103980669410644,"y":-0.6225164404710924},"rotation":{"radians":-0.8757883499385072}},"curvature":-0.23072768177274236},{"time":0.4188014748101557,"velocity":4.159655822912792,"acceleration":1.69527930582718,"pose":{"translation":{"x":1.1625699872716748,"y":-0.6942589855617601},"rotation":{"radians":-0.8956951014436992}},"curvature":-0.20001151310088602},{"time":0.4415971888007184,"velocity":4.198300925102548,"acceleration":1.4699484357724757,"pose":{"translation":{"x":1.2214286808496868,"y":-0.7691632875168153},"rotation":{"radians":-0.9134511227235513}},"curvature":-0.17352533617146237},{"time":0.4647698263131177,"velocity":4.232363507366622,"acceleration":1.2821427428554832,"pose":{"translation":{"x":1.2804858807160786,"y":-0.8469688203320094},"rotation":{"radians":-0.9292500252615125}},"curvature":-0.1505809300594235},{"time":0.4882793510791383,"velocity":4.2625060739333565,"acceleration":1.1272878683827954,"pose":{"translation":{"x":1.3396673770687697,"y":-0.927396465733129},"rotation":{"radians":-0.9432622910059878}},"curvature":-0.13058286232681732},{"time":0.5120791010832051,"velocity":4.289335243383484,"acceleration":1.0011404901357241,"pose":{"translation":{"x":1.3988961061943574,"y":-1.010150585807691},"rotation":{"radians":-0.9556362936086461}},"curvature":-0.1130194860810929},{"time":0.5361165150646032,"velocity":4.313400071798417,"acceleration":0.9000098271463499,"pose":{"translation":{"x":1.4580926369302736,"y":-1.0949210956366426},"rotation":{"radians":-0.966499648626333}},"curvature":-0.09745162972922349},{"time":0.5603338518432681,"velocity":4.335195912886528,"acceleration":0.8208598473160442,"pose":{"translation":{"x":1.5171756571269421,"y":-1.181385535926058},"rotation":{"radians":-0.9759606502724327}},"curvature":-0.08350077098730027},{"time":0.5846688908967251,"velocity":4.355171569328379,"acceleration":0.7613488359955657,"pose":{"translation":{"x":1.5760624601099376,"y":-1.269211145638837},"rotation":{"radians":-0.9841096421884397}},"curvature":-0.07083758920433708},{"time":0.6090556078020036,"velocity":4.373738367857966,"acceleration":0.7198453794943244,"pose":{"translation":{"x":1.6346694311421397,"y":-1.3580569346264015},"rotation":{"radians":-0.9910202281418624}},"curvature":-0.05917124638340661},{"time":0.6334248213148449,"velocity":4.391280433607095,"acceleration":0.6954482609667484,"pose":{"translation":{"x":1.6929125338858921,"y":-1.447575756260394},"rotation":{"radians":-0.9967502648754831}},"curvature":-0.048239424685084},{"time":0.6577048106319545,"velocity":4.40816590995397,"acceleration":0.6880316153597182,"pose":{"translation":{"x":1.7507077968651603,"y":-1.5374163800643763},"rotation":{"radians":-1.00134260031699}},"curvature":-0.0377989561052516},{"time":0.6818219022155111,"velocity":4.424759231433983,"acceleration":0.6983353154572598,"pose":{"translation":{"x":1.807971799927687,"y":-1.6272255643455256},"rotation":{"radians":-1.004825530716281}},"curvature":-0.02761675829336551},{"time":0.7057010257488948,"velocity":4.441434866699511,"acceleration":0.7281238420974316,"pose":{"translation":{"x":1.8646221607071505,"y":-1.7166501288263332},"rotation":{"radians":-1.0072129531455787}},"curvature":-0.017460699081779364},{"time":0.7292662385270009,"velocity":4.4585932599673495,"acceleration":0.23889919002521667,"pose":{"translation":{"x":1.9205780210853223,"y":-1.8053390272763021},"rotation":{"radians":-1.008504187157782}},"curvature":-0.007089923341650348},{"time":0.7524737936799106,"velocity":4.464137526095845,"acceleration":-0.8418057704981504,"pose":{"translation":{"x":1.9757605336542223,"y":-1.8929454201436466},"rotation":{"radians":-1.0086834324076666}},"curvature":0.0037559323176499996},{"time":0.7753450862975656,"velocity":4.444884339991551,"acceleration":-0.9276777489993119,"pose":{"translation":{"x":2.030093348178279,"y":-1.979128747186985},"rotation":{"radians":-1.0077188182728354}},"curvature":0.015369358317897666},{"time":0.7978741011542355,"velocity":4.423984674202144,"acceleration":-1.0466704059158933,"pose":{"translation":{"x":2.0835030980564837,"y":-2.063556800107043},"rotation":{"radians":-1.0055609871508069}},"curvature":0.028090352121107495},{"time":0.8199975497641668,"velocity":4.400828715265328,"acceleration":-1.2066809299530705,"pose":{"translation":{"x":2.13591988678455,"y":-2.145907795178352},"rotation":{"radians":-1.0021411351255256}},"curvature":0.04232577816829033},{"time":0.8416570536654623,"velocity":4.37469260495539,"acceleration":-1.418413476156303,"pose":{"translation":{"x":2.18727777441707,"y":-2.2258724458809374},"rotation":{"radians":-0.9973684120631896}},"curvature":0.058574332428376834},{"time":0.8627999817275045,"velocity":4.344703190866786,"acceleration":-1.696131586806757,"pose":{"translation":{"x":2.2375152640296703,"y":-2.3031560355320284},"rotation":{"radians":-0.9911265582240422}},"curvature":0.07745929395032254},{"time":0.8833803741956509,"velocity":4.309796137132683,"acceleration":-2.0585371487899393,"pose":{"translation":{"x":2.286575788181171,"y":-2.377480489917751},"rotation":{"radians":-0.9832696274112916}},"curvature":0.09977199426284837},{"time":0.9033599711776307,"velocity":4.2686673945274265,"acceleration":-2.5296668683770758,"pose":{"translation":{"x":2.334408195375744,"y":-2.448586449924819},"rotation":{"radians":-0.9736166208148695}},"curvature":0.126529902884793},{"time":0.9227093650443854,"velocity":4.2197198739395185,"acceleration":-3.13953191681287,"pose":{"translation":{"x":2.3809672365250667,"y":-2.516235344172248},"rotation":{"radians":-0.9619448384531385}},"curvature":0.1590543960728061},{"time":0.9414092958496307,"velocity":4.161010844334259,"acceleration":-3.923919629505293,"pose":{"translation":{"x":2.426214051410481,"y":-2.580211461643035},"rotation":{"radians":-0.9479817617955386}},"curvature":0.19907449993361534},{"time":0.9594521036665412,"velocity":4.090212316570092,"acceleration":-4.922264584156884,"pose":{"translation":{"x":2.470116655145152,"y":-2.64032402431587},"rotation":{"radians":-0.9313953419033538}},"curvature":0.24886371793784065},{"time":0.976843336659243,"velocity":4.004608066335296,"acceleration":-6.17176774912248,"pose":{"translation":{"x":2.5126504246362225,"y":-2.6964092597968197},"rotation":{"radians":-0.9117827393816472}},"curvature":0.31141629925925174},{"time":0.9936034797059252,"velocity":3.9011683560091024,"acceleration":-8.55718066284625,"pose":{"translation":{"x":2.553798585046971,"y":-2.748332473951045},"rotation":{"radians":-0.8886579503447547}},"curvature":0.3906643088738414},{"time":1.0254537904752927,"velocity":3.628619492587828,"acceleration":-12.39662532879157,"pose":{"translation":{"x":2.631913139334245,"y":-2.8393118888255486},"rotation":{"radians":-0.8294412165109983}},"curvature":0.6211075800749466},{"time":1.0554677982545575,"velocity":3.2565470835328463,"acceleration":-15.10365161937661,"pose":{"translation":{"x":2.7045015699979063,"y":-2.9128450410468005},"rotation":{"radians":-0.7478462937091639}},"curvature":0.9979714067421676},{"time":1.069996742378132,"velocity":3.0371069730929885,"acceleration":-16.121922307845313,"pose":{"translation":{"x":2.7387788037720053,"y":-2.943100559831496},"rotation":{"radians":-0.696449348504947}},"curvature":1.263526319883902},{"time":1.08437649814755,"velocity":2.805277667772641,"acceleration":-16.100629398551472,"pose":{"translation":{"x":2.7717618347051216,"y":-2.969112603296221},"rotation":{"radians":-0.6368349398617001}},"curvature":1.5892041297400166},{"time":1.098711758885972,"velocity":2.5744709472917022,"acceleration":-14.800160225656162,"pose":{"translation":{"x":2.803502446693888,"y":-2.991008058807253},"rotation":{"radians":-0.5684342434947216}},"curvature":1.9717120030565085},{"time":1.113071966199183,"velocity":2.36193757818254,"acceleration":-12.189730557682944,"pose":{"translation":{"x":2.834064163588331,"y":-3.0089594730435323},"rotation":{"radians":-0.4912701719368094}},"curvature":2.390049211507602},{"time":1.1274565781948793,"velocity":2.1865930337781876,"acceleration":-9.452729526839338,"pose":{"translation":{"x":2.8635227356540307,"y":-3.0231871246283717},"rotation":{"radians":-0.40636987322213675}},"curvature":2.796409874573135},{"time":1.1346436226350656,"velocity":2.1186558465877323,"acceleration":-7.261194760818502,"pose":{"translation":{"x":2.877865477209893,"y":-3.0289869382615286},"rotation":{"radians":-0.36171741909431643}},"curvature":2.971933250793703},{"time":1.1417887663201607,"velocity":2.066773566696225,"acceleration":-4.773090124541358,"pose":{"translation":{"x":2.8919666260342733,"y":-3.0339610967611286},"rotation":{"radians":-0.31617091433168876}},"curvature":3.1137480375494775},{"time":1.148858246984371,"velocity":2.033030298352247,"acceleration":-1.9397716793931767,"pose":{"translation":{"x":2.905839306217418,"y":-3.0381514825332516},"rotation":{"radians":-0.2702880476444087}},"curvature":3.2098663582418205},{"time":1.1558106862534079,"velocity":2.019544153555468,"acceleration":1.3391284277157562,"pose":{"translation":{"x":2.919497497212209,"y":-3.0416033498489305},"rotation":{"radians":-0.22471642031179453}},"curvature":3.2491802821627607},{"time":1.162598455705074,"velocity":2.0286338485889748,"acceleration":5.241105012252983,"pose":{"translation":{"x":2.932956049036088,"y":-3.044365389613901},"rotation":{"radians":-0.18017420926151867}},"curvature":3.222625174251699},{"time":1.1691695815568548,"velocity":2.0630738092268883,"acceleration":13.159857369971245,"pose":{"translation":{"x":2.9462306974730144,"y":-3.046489794138356},"rotation":{"radians":-0.13742445513049514}},"curvature":3.1241333931057906},{"time":1.1813884049609846,"velocity":2.2238717824541028,"acceleration":30.872761161060968,"pose":{"translation":{"x":2.9722957473660427,"y":-3.0490523623471475},"rotation":{"radians":-0.060405926038590844}},"curvature":2.704652833577455},{"time":1.192083993719446,"velocity":2.5540741396710116,"acceleration":-64.97980757793125,"pose":{"translation":{"x":2.997836826166983,"y":-3.0497810822958833},"rotation":{"radians":3.9174549638033244E-4}},"curvature":2.008839569414959},{"time":1.2313896524290056,"velocity":0.0,"acceleration":-64.97980757793125,"pose":{"translation":{"x":3.048000000000002,"y":-3.048000000000002},"rotation":{"radians":0.05371225908084613}},"curvature":-1.1691366233348565E-14}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":82.04386788688518,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.003960837658956053}},"curvature":0.0},{"time":0.04861705599062372,"velocity":3.988731318744032,"acceleration":-14.986162120671922,"pose":{"translation":{"x":0.09695929073566933,"y":-4.16880132877712E-4},"rotation":{"radians":-0.02033040485690381}},"curvature":-0.48011339202264347},{"time":0.07447317296123704,"velocity":3.6012473580113644,"acceleration":-7.700425189411032,"pose":{"translation":{"x":0.19495981624216482,"y":-0.0053316734503858374},"rotation":{"radians":-0.08545062977466551}},"curvature":-0.8198502777066392},{"time":0.08855487040799276,"velocity":3.4928123002827016,"acceleration":-4.2851292698411925,"pose":{"translation":{"x":0.24462277107317196,"y":-0.010662122724874212},"rotation":{"radians":-0.12929952046633988}},"curvature":-0.9284223735685312},{"time":0.10323765312894014,"velocity":3.4298946782824515,"acceleration":-1.5645670869950543,"pose":{"translation":{"x":0.2948471423927566,"y":-0.01843507745101975},"rotation":{"radians":-0.17835307356051847}},"curvature":-0.9945667573290181},{"time":0.1184344076772456,"velocity":3.4061183362870304,"acceleration":0.6065764305371881,"pose":{"translation":{"x":0.3457074680596518,"y":-0.028983138147212293},"rotation":{"radians":-0.23085524023122095}},"curvature":-1.0201986826587648},{"time":0.13406821199091645,"velocity":3.415601433503334,"acceleration":2.304621027593365,"pose":{"translation":{"x":0.39726669237201556,"y":-0.04259091984913327},"rotation":{"radians":-0.28513455840977064}},"curvature":-1.0099327126714004},{"time":0.15007672441038006,"velocity":3.452494987845719,"acceleration":3.5731137837875306,"pose":{"translation":{"x":0.44957662374616525,"y":-0.0594968990491558},"rotation":{"radians":-0.3396883031848305}},"curvature":-0.9705299239146334},{"time":0.16641505004784743,"velocity":3.510873684384963,"acceleration":4.446660630426792,"pose":{"translation":{"x":0.5026783923953116,"y":-0.07989526063574501},"rotation":{"radians":-0.3932492699961454}},"curvature":-0.9098726567829792},{"time":0.18305641927624738,"velocity":3.584872205769285,"acceleration":4.965060662537582,"pose":{"translation":{"x":0.5566029080082937,"y":-0.10393774483285809},"rotation":{"radians":-0.44482289890825155}},"curvature":-0.835825077432052},{"time":0.1999906598326739,"velocity":3.668951737405947,"acceleration":5.178872118939808,"pose":{"translation":{"x":0.6113713174283122,"y":-0.13173549413934466},"rotation":{"radians":-0.4936918141390549}},"curvature":-0.7553148018316558},{"time":0.21722099414443607,"velocity":3.758185435373144,"acceleration":5.148057472944306,"pose":{"translation":{"x":0.6669954623316645,"y":-0.16336090026834685},"rotation":{"radians":-0.5393932214102857}},"curvature":-0.6738095874713677},{"time":0.234759951539094,"velocity":3.8484769960563643,"acceleration":4.93643001229542,"pose":{"translation":{"x":0.7234783369064792,"y":-0.1988494510866995},"rotation":{"radians":-0.5816790884865704}},"curvature":-0.5951852920387548},{"time":0.25262515031495936,"velocity":3.9366672994691694,"acceleration":4.604994697195861,"pose":{"translation":{"x":0.7808145455314498,"y":-0.23820157755433044},"rotation":{"radians":-0.6204693772224047}},"curvature":-0.5218724701926193},{"time":0.2708354955656566,"velocity":4.020525842782736,"acceleration":4.206588872506236,"pose":{"translation":{"x":0.838990760454569,"y":-0.28138450066366055},"rotation":{"radians":-0.655806281947034}},"curvature":-0.45514380303097307},{"time":0.289408087212753,"velocity":4.098653100139014,"acceleration":3.7829567821827563,"pose":{"translation":{"x":0.8979861794718639,"y":-0.3283340783790041},"rotation":{"radians":-0.6878142616676054}},"curvature":-0.39543267641623114},{"time":0.3083559240142426,"velocity":4.170331947874901,"acceleration":3.3642257650536935,"pose":{"translation":{"x":0.9577729836061292,"y":-0.37895665257596894},"rotation":{"radians":-0.7166678668322568}},"curvature":-0.34261784050540955},{"time":0.3276863537879395,"velocity":4.235363877769133,"acceleration":2.9700899332606645,"pose":{"translation":{"x":1.0183167947856622,"y":-0.4331308959808565},"rotation":{"radians":-0.742567453488204}},"curvature":-0.29624731732770176},{"time":0.3474001523523855,"velocity":4.293915632431723,"acceleration":2.6118590831086155,"pose":{"translation":{"x":1.079577133522997,"y":-0.4907096591100624},"rotation":{"radians":-0.7657218390020194}},"curvature":-0.25569904207677707},{"time":0.3674910940504928,"velocity":4.34639034099413,"acceleration":2.294695858761864,"pose":{"translation":{"x":1.1415078765936388,"y":-0.551521817209476},"rotation":{"radians":-0.7863365551744559}},"curvature":-0.22028752701688126},{"time":0.38794588486170145,"velocity":4.393327864760451,"acceleration":2.0196292959925226,"pose":{"translation":{"x":1.2040577147147982,"y":-0.6153741171938814},"rotation":{"radians":-0.8046063412012733}},"curvature":-0.1893294098683867},{"time":0.4087443497529076,"velocity":4.435333053766403,"acceleration":1.7851661520501068,"pose":{"translation":{"x":1.2671706102241251,"y":-0.6820530245863567},"rotation":{"radians":-0.8207106925835705}},"curvature":-0.1621800372499478},{"time":0.4298597896122911,"velocity":4.473027622289024,"acceleration":1.5884760015640393,"pose":{"translation":{"x":1.3307862547584441,"y":-0.7513265704576756},"rotation":{"radians":-0.834811517419783}},"curvature":-0.13825086553063487},{"time":0.4512594449630652,"velocity":4.50702046125547,"acceleration":1.42620605398305,"pose":{"translation":{"x":1.3948405269324877,"y":-0.8229461983657058},"rotation":{"radians":-0.8470521815066807}},"curvature":-0.11701485001282146},{"time":0.4729050217177735,"velocity":4.53789151386499,"acceleration":1.2950098135221093,"pose":{"translation":{"x":1.459265950017631,"y":-0.8966486112948104},"rotation":{"radians":-0.8575574194275142}},"curvature":-0.09800474543703949},{"time":0.494753248187605,"velocity":4.566185181551475,"acceleration":1.1918730332462482,"pose":{"translation":{"x":1.5239921496206263,"y":-0.972157618595248},"rotation":{"radians":-0.8664337427984783}},"curvature":-0.0808075223195219},{"time":0.5167564428436503,"velocity":4.592410195907283,"acceleration":1.114307380106349,"pose":{"translation":{"x":1.5889463113623374,"y":-1.0491859829225723},"rotation":{"radians":-0.8737700918600187}},"curvature":-0.06505688074422102},{"time":0.5388630796355971,"velocity":4.61704378443388,"acceleration":1.0604664491834883,"pose":{"translation":{"x":1.654053638556473,"y":-1.127437267177034},"rotation":{"radians":-0.8796385592970702}},"curvature":-0.05042501444162249},{"time":0.5610183427137745,"velocity":4.640538697601121,"acceleration":1.0292249031308387,"pose":{"translation":{"x":1.7192378098883225,"y":-1.206607681442978},"rotation":{"radians":-0.8840950728279422}},"curvature":-0.036614235957898436},{"time":0.5831646657820858,"velocity":4.663332244815808,"acceleration":1.0202513060755258,"pose":{"translation":{"x":1.784421437093489,"y":-1.2863879299282457},"rotation":{"radians":-0.887179962196901}},"curvature":-0.02334872853924968},{"time":0.6052422535180257,"velocity":4.685856932538398,"acceleration":0.6190297289205114,"pose":{"translation":{"x":1.8495265226366242,"y":-1.3664650579035758},"rotation":{"radians":-0.8889183619964093}},"curvature":-0.010366474520298714},{"time":0.6272108558372299,"velocity":4.699456150476817,"acceleration":-1.0504967716010856,"pose":{"translation":{"x":1.9144749173901634,"y":-1.4465242986420022},"rotation":{"radians":-0.8893204182932911}},"curvature":0.002588723896986337},{"time":0.6491148904032975,"velocity":4.676446032880125,"acceleration":-1.081508394360102,"pose":{"translation":{"x":1.9791887783130577,"y":-1.5262509203582562},"rotation":{"radians":-0.8883812774243289}},"curvature":0.015775299121229783},{"time":0.6709789593575614,"velocity":4.65279985877122,"acceleration":-1.1371104719694012,"pose":{"translation":{"x":2.043591026129511,"y":-1.605332073148167},"rotation":{"radians":-0.8860808419436056}},"curvature":0.02946226836672896},{"time":0.6927449034691424,"velocity":4.628049575789641,"acceleration":-1.219194441272511,"pose":{"translation":{"x":2.107605803007713,"y":-1.6834586359280597},"rotation":{"radians":-0.8823832835043174}},"curvature":0.04393813260960995},{"time":0.714357285036688,"velocity":4.601699880319829,"acceleration":-1.3306248642662981,"pose":{"translation":{"x":2.1711589302385734,"y":-1.7603270633741557},"rotation":{"radians":-0.8772363072499006}},"curvature":0.05952059236403715},{"time":0.7357639577379572,"velocity":4.573215629362309,"acceleration":-1.475253889594832,"pose":{"translation":{"x":2.2341783659144543,"y":-1.8356412328619742},"rotation":{"radians":-0.8705701690175973}},"curvature":0.07656734033760348},{"time":0.7569166610487092,"velocity":4.542010021527677,"acceleration":-1.6579143384256556,"pose":{"translation":{"x":2.2965946626079106,"y":-1.9091142914057355},"rotation":{"radians":-0.8622964577260398}},"curvature":0.09548814430263139},{"time":0.7777716383807286,"velocity":4.50743425558138,"acceleration":-1.8843466586654065,"pose":{"translation":{"x":2.3583414250504164,"y":-1.9804705025977558},"rotation":{"radians":-0.8523066739840298}},"curvature":0.11675831756366055},{"time":0.7982902755620526,"velocity":4.468770030168384,"acceleration":-2.1609911912303006,"pose":{"translation":{"x":2.4193557678111066,"y":-2.049447093547844},"rotation":{"radians":-0.8404706668248598}},"curvature":0.14093343621696822},{"time":0.818439752146611,"velocity":4.425227188761252,"acceleration":-2.494544357783928,"pose":{"translation":{"x":2.4795787729755046,"y":-2.115796101822716},"rotation":{"radians":-0.8266350401034745}},"curvature":0.16866471487091822},{"time":0.8381936914844454,"velocity":4.3759501108420515,"acceleration":-2.8911376736798027,"pose":{"translation":{"x":2.5389559478242623,"y":-2.1792862223853824},"rotation":{"radians":-0.8106217177148143}},"curvature":0.20071365851955927},{"time":0.8575327854022509,"velocity":4.320038127841452,"acceleration":-3.354961102939187,"pose":{"translation":{"x":2.597437682511891,"y":-2.23970465453455},"rotation":{"radians":-0.7922269749141588}},"curvature":0.23796326254617617},{"time":0.8764453543171904,"velocity":4.256587194775173,"acceleration":-3.8861395961432224,"pose":{"translation":{"x":2.654979707745497,"y":-2.2968589488440285},"rotation":{"radians":-0.7712214176061186}},"curvature":0.2814208492984974},{"time":0.8949277819897445,"velocity":4.184761900764007,"acceleration":-4.4777260255035625,"pose":{"translation":{"x":2.7115435524635143,"y":-2.3505788541021255},"rotation":{"radians":-0.7473516406900496}},"curvature":0.33220425608892623},{"time":0.912984734386199,"velocity":4.103907815077124,"acceleration":-5.11185842177919,"pose":{"translation":{"x":2.767097001514443,"y":-2.400718164251047},"rotation":{"radians":-0.7203446363245664}},"curvature":0.3914981985278621},{"time":0.9306290336987828,"velocity":4.0137126550397,"acceleration":-5.755509512267635,"pose":{"translation":{"x":2.821614553335579,"y":-2.4471565653262983},"rotation":{"radians":-0.6899164560608424}},"curvature":0.46046118584548174},{"time":0.9478810135495537,"velocity":3.9144187209031385,"acceleration":-6.356839268896832,"pose":{"translation":{"x":2.8750778776317483,"y":-2.489801482396083},"rotation":{"radians":-0.6557871246247801}},"curvature":0.5400562006079622},{"time":0.9647671374724911,"velocity":3.8070763452503513,"acceleration":-6.8437882315068626,"pose":{"translation":{"x":2.9274762730540473,"y":-2.528589926500712},"rotation":{"radians":-0.6177042511649705}},"curvature":0.6307732766495935},{"time":0.981317637459908,"velocity":3.6938082282109135,"acceleration":-7.126794452842301,"pose":{"translation":{"x":2.9788071248785712,"y":-2.563490341591984},"rotation":{"radians":-0.5754779499559356}},"curvature":0.7322154294929463},{"time":0.9975629544099581,"velocity":3.5780311934866313,"acceleration":-7.10674688337942,"pose":{"translation":{"x":3.029076362685149,"y":-2.594504451472612},"rotation":{"radians":-0.5290291461838743}},"curvature":0.8425421381827005},{"time":1.0135288841201933,"velocity":3.4645653722781624,"acceleration":-6.6870818297374965,"pose":{"translation":{"x":3.0782989180360785,"y":-2.621669106735596},"rotation":{"radians":-0.478451501975481}},"curvature":0.9578207889404049},{"time":1.0292306002321454,"velocity":3.3595667117702304,"acceleration":-5.785774257210771,"pose":{"translation":{"x":3.126499182154865,"y":-2.645058131703647},"rotation":{"radians":-0.4240834522171856}},"curvature":1.0714338957068112},{"time":1.0446661559449735,"velocity":3.2702600708812066,"acceleration":-4.340553001474387,"pose":{"translation":{"x":3.173711463604948,"y":-2.664784171368569},"rotation":{"radians":-0.3665810929551392}},"curvature":1.1738091280013403},{"time":1.059810582885297,"velocity":3.2045248830697757,"acceleration":-2.30081053720373,"pose":{"translation":{"x":3.2199804459684396,"y":-2.6810005383306725},"rotation":{"radians":-0.3069761459696382}},"curvature":1.2528094160899457},{"time":1.0746120846913012,"velocity":3.170469431748081,"acceleration":0.3977579187639632,"pose":{"translation":{"x":3.2653616455248597,"y":-2.693903059738172},"rotation":{"radians":-0.24669911820251192}},"curvature":1.2950253234940936},{"time":1.0889917302829935,"velocity":3.176189049651196,"acceleration":3.8780505815630546,"pose":{"translation":{"x":3.3099218689298664,"y":-2.703731924226575},"rotation":{"radians":-0.18755053544781314}},"curvature":1.2878719020972225},{"time":1.1028472499648765,"velocity":3.2299214558113807,"acceleration":8.392529795697191,"pose":{"translation":{"x":3.3537396708939986,"y":-2.710773528858087},"rotation":{"radians":-0.13161552235012597}},"curvature":1.2219067314503889},{"time":1.1160601938775772,"velocity":3.340811481287596,"acceleration":18.700043425813895,"pose":{"translation":{"x":3.3969058118613997,"y":-2.715362326061045},"rotation":{"radians":-0.08113614721932995}},"curvature":1.0924796198481246},{"time":1.1398773728434104,"velocity":3.786193762229057,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.4817099273230365,"y":-2.7187706663614057},"rotation":{"radians":-0.005486303923341652}},"curvature":0.6490192275525587},{"time":1.184047961373033,"velocity":0.0,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.565321805332028,"y":-2.7176638555734356},"rotation":{"radians":0.022896761221391358}},"curvature":7.928831080838964E-15}] \ No newline at end of file diff --git a/PathWeaver/pathweaver.json b/PathWeaver/pathweaver.json index 934fa17..0a8a4b8 100644 --- a/PathWeaver/pathweaver.json +++ b/PathWeaver/pathweaver.json @@ -1,8 +1,9 @@ { "lengthUnit": "Meter", - "maxVelocity": 4.4704, + "exportUnit": "Same as Project", + "maxVelocity": 4.704, "maxAcceleration": 90.0, "wheelBase": 0.747, - "gameName": "Destination: Deep Space", + "gameName": "Infinite Recharge", "outputDir": "" } \ No newline at end of file diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index cfd86e4..e512561 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -20,6 +20,7 @@ DriveSubsystem::DriveSubsystem() : void DriveSubsystem::robotInit() { cout << "Drive Subsystem" << endl; + cout << "joysticks are being registered" << endl; // Registers joystick axis and buttons, does inital setup for talons driverJoystick->RegisterAxis(CORE::COREJoystick::LEFT_STICK_Y); driverJoystick->RegisterAxis(CORE::COREJoystick::RIGHT_STICK_X); @@ -49,7 +50,7 @@ void DriveSubsystem::Periodic() { void DriveSubsystem::teleop() { // Code for teleop. Sets motor speed based on the values for the joystick, runs compressor, // toggles gears - double mag = -m_controller.GetY(frc::GenericHID::kLeftHand); + double mag = -m_controller.GetY(frc::GenericHID::kLeftHand); SmartDashboard::PutNumber("mag", mag); std::cout << mag << endl; double rot = m_controller.GetX(frc::GenericHID::kRightHand); diff --git a/src/main/deploy/paths/example.wpilib.json b/src/main/deploy/paths/example.wpilib.json index cb6be5b..667ae69 100644 --- a/src/main/deploy/paths/example.wpilib.json +++ b/src/main/deploy/paths/example.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":71.81853462273233,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.05154902732371937,"velocity":3.7021756036167144,"acceleration":-14.570586583617095,"pose":{"translation":{"x":0.0954175591874795,"y":-8.970348306178012E-4},"rotation":{"radians":-0.027650615332535523}},"curvature":-0.5555721590079611},{"time":0.07911903361344792,"velocity":3.3004644398613565,"acceleration":-7.210458670385726,"pose":{"translation":{"x":0.19176609884113538,"y":-0.006836141893059719},"rotation":{"radians":-0.10181937409911292}},"curvature":-0.9490656990275671},{"time":0.09426195644257385,"velocity":3.1912770206531036,"acceleration":-3.8275391053665806,"pose":{"translation":{"x":0.24052673799069652,"y":-0.013026151812177424},"rotation":{"radians":-0.15174007207787038}},"curvature":-1.0731419939317515},{"time":0.11009725577470761,"velocity":3.1306667932141763,"acceleration":-1.1455564555144113,"pose":{"translation":{"x":0.28977907417078114,"y":-0.02195386324792068},"rotation":{"radians":-0.20750053729514634}},"curvature":-1.1457526465583436},{"time":0.12651322391898032,"velocity":3.1118613749329858,"acceleration":0.9880141343238242,"pose":{"translation":{"x":0.3395834530119897,"y":-0.03399193143522784},"rotation":{"radians":-0.2670122588274609}},"curvature":-1.1688563545650115},{"time":0.14341110021863882,"velocity":3.128556715557104,"acceleration":2.6456659292549394,"pose":{"translation":{"x":0.389988609914771,"y":-0.049459184600208664},"rotation":{"radians":-0.32827964422324374}},"curvature":-1.148331183382902},{"time":0.16071185073581556,"velocity":3.174328721750938,"acceleration":3.8639398380608503,"pose":{"translation":{"x":0.441032156511579,"y":-0.0686226965918421},"rotation":{"radians":-0.38952006570031844}},"curvature":-1.0931666695325097},{"time":0.17836062833768684,"velocity":3.2425225366198847,"acceleration":4.672338159109252,"pose":{"translation":{"x":0.4927410671290303,"y":-0.09169985951367407},"rotation":{"radians":-0.44925799963162055}},"curvature":-1.0138680069811143},{"time":0.19632774121794166,"velocity":3.3264709637393226,"acceleration":5.110317311095119,"pose":{"translation":{"x":0.5451321652500615,"y":-0.11886045635551529},"rotation":{"radians":-0.5063736770642954}},"curvature":-0.9207139869212123},{"time":0.21460616461634946,"velocity":3.419879507251732,"acceleration":5.233210546194306,"pose":{"translation":{"x":0.5982126099760859,"y":-0.15022873362513905},"rotation":{"radians":-0.5601030251974476}},"curvature":-0.8224379042703561},{"time":0.23320658618430956,"velocity":3.517219429564841,"acceleration":5.109065552075489,"pose":{"translation":{"x":0.6519803824891512,"y":-0.18588547397997904},"rotation":{"radians":-0.6099993845273901}},"curvature":-0.7255796794556587},{"time":0.2521513382713219,"velocity":3.614009409845206,"acceleration":4.810311089326068,"pose":{"translation":{"x":0.7064247725140964,"y":-0.225870068858827},"rotation":{"radians":-0.6558736580963799}},"curvature":-0.6344421110814962},{"time":0.2714684065329755,"velocity":3.706930517517507,"acceleration":4.404711130561586,"pose":{"translation":{"x":0.7615268647807092,"y":-0.2701825911135307},"rotation":{"radians":-0.6977285910792212}},"curvature":-0.5514252264221119},{"time":0.29118628283685577,"velocity":3.793782066744245,"acceleration":3.9488070643090403,"pose":{"translation":{"x":0.8172600254858828,"y":-0.3187858676406917},"rotation":{"radians":-0.7356980906193501}},"curvature":-0.4775078535713296},{"time":0.3113299982726776,"velocity":3.8733257125586493,"acceleration":3.4850043042255767,"pose":{"translation":{"x":0.8735903887557737,"y":-0.37160755201336304},"rotation":{"radians":-0.7699971388185597}},"curvature":-0.4127183171142323},{"time":0.3319183569834702,"velocity":3.9450762312827017,"acceleration":3.041814848512116,"pose":{"translation":{"x":0.9304773431079583,"y":-0.42854219711274705},"rotation":{"radians":-0.8008837421565934}},"curvature":-0.35651765850700873},{"time":0.3529622164440334,"velocity":4.009087755459845,"acceleration":2.6360324587810537,"pose":{"translation":{"x":0.9878740179135905,"y":-0.48945332775989314},"rotation":{"radians":-0.8286319356988368}},"curvature":-0.30807667140802825},{"time":0.3744635940778765,"velocity":4.065766084811164,"acceleration":2.2756390699688773,"pose":{"translation":{"x":1.045727769859559,"y":-0.554175513347396},"rotation":{"radians":-0.8535138107447635}},"curvature":-0.26645832053513274},{"time":0.3964153808599162,"velocity":4.115720428468,"acceleration":1.9626199435440872,"pose":{"translation":{"x":1.103980669410644,"y":-0.6225164404710924},"rotation":{"radians":-0.8757883499385072}},"curvature":-0.23072768177274236},{"time":0.4188014748101557,"velocity":4.159655822912792,"acceleration":1.69527930582718,"pose":{"translation":{"x":1.1625699872716748,"y":-0.6942589855617601},"rotation":{"radians":-0.8956951014436992}},"curvature":-0.20001151310088602},{"time":0.4415971888007184,"velocity":4.198300925102548,"acceleration":1.4699484357724757,"pose":{"translation":{"x":1.2214286808496868,"y":-0.7691632875168153},"rotation":{"radians":-0.9134511227235513}},"curvature":-0.17352533617146237},{"time":0.4647698263131177,"velocity":4.232363507366622,"acceleration":1.2821427428554832,"pose":{"translation":{"x":1.2804858807160786,"y":-0.8469688203320094},"rotation":{"radians":-0.9292500252615125}},"curvature":-0.1505809300594235},{"time":0.4882793510791383,"velocity":4.2625060739333565,"acceleration":1.1272878683827954,"pose":{"translation":{"x":1.3396673770687697,"y":-0.927396465733129},"rotation":{"radians":-0.9432622910059878}},"curvature":-0.13058286232681732},{"time":0.5120791010832051,"velocity":4.289335243383484,"acceleration":1.0011404901357241,"pose":{"translation":{"x":1.3988961061943574,"y":-1.010150585807691},"rotation":{"radians":-0.9556362936086461}},"curvature":-0.1130194860810929},{"time":0.5361165150646032,"velocity":4.313400071798417,"acceleration":0.9000098271463499,"pose":{"translation":{"x":1.4580926369302736,"y":-1.0949210956366426},"rotation":{"radians":-0.966499648626333}},"curvature":-0.09745162972922349},{"time":0.5603338518432681,"velocity":4.335195912886528,"acceleration":0.8208598473160442,"pose":{"translation":{"x":1.5171756571269421,"y":-1.181385535926058},"rotation":{"radians":-0.9759606502724327}},"curvature":-0.08350077098730027},{"time":0.5846688908967251,"velocity":4.355171569328379,"acceleration":0.7613488359955657,"pose":{"translation":{"x":1.5760624601099376,"y":-1.269211145638837},"rotation":{"radians":-0.9841096421884397}},"curvature":-0.07083758920433708},{"time":0.6090556078020036,"velocity":4.373738367857966,"acceleration":0.7198453794943244,"pose":{"translation":{"x":1.6346694311421397,"y":-1.3580569346264015},"rotation":{"radians":-0.9910202281418624}},"curvature":-0.05917124638340661},{"time":0.6334248213148449,"velocity":4.391280433607095,"acceleration":0.6954482609667484,"pose":{"translation":{"x":1.6929125338858921,"y":-1.447575756260394},"rotation":{"radians":-0.9967502648754831}},"curvature":-0.048239424685084},{"time":0.6577048106319545,"velocity":4.40816590995397,"acceleration":0.6880316153597182,"pose":{"translation":{"x":1.7507077968651603,"y":-1.5374163800643763},"rotation":{"radians":-1.00134260031699}},"curvature":-0.0377989561052516},{"time":0.6818219022155111,"velocity":4.424759231433983,"acceleration":0.6983353154572598,"pose":{"translation":{"x":1.807971799927687,"y":-1.6272255643455256},"rotation":{"radians":-1.004825530716281}},"curvature":-0.02761675829336551},{"time":0.7057010257488948,"velocity":4.441434866699511,"acceleration":0.7281238420974316,"pose":{"translation":{"x":1.8646221607071505,"y":-1.7166501288263332},"rotation":{"radians":-1.0072129531455787}},"curvature":-0.017460699081779364},{"time":0.7292662385270009,"velocity":4.4585932599673495,"acceleration":0.23889919002521667,"pose":{"translation":{"x":1.9205780210853223,"y":-1.8053390272763021},"rotation":{"radians":-1.008504187157782}},"curvature":-0.007089923341650348},{"time":0.7524737936799106,"velocity":4.464137526095845,"acceleration":-0.8418057704981504,"pose":{"translation":{"x":1.9757605336542223,"y":-1.8929454201436466},"rotation":{"radians":-1.0086834324076666}},"curvature":0.0037559323176499996},{"time":0.7753450862975656,"velocity":4.444884339991551,"acceleration":-0.9276777489993119,"pose":{"translation":{"x":2.030093348178279,"y":-1.979128747186985},"rotation":{"radians":-1.0077188182728354}},"curvature":0.015369358317897666},{"time":0.7978741011542355,"velocity":4.423984674202144,"acceleration":-1.0466704059158933,"pose":{"translation":{"x":2.0835030980564837,"y":-2.063556800107043},"rotation":{"radians":-1.0055609871508069}},"curvature":0.028090352121107495},{"time":0.8199975497641668,"velocity":4.400828715265328,"acceleration":-1.2066809299530705,"pose":{"translation":{"x":2.13591988678455,"y":-2.145907795178352},"rotation":{"radians":-1.0021411351255256}},"curvature":0.04232577816829033},{"time":0.8416570536654623,"velocity":4.37469260495539,"acceleration":-1.418413476156303,"pose":{"translation":{"x":2.18727777441707,"y":-2.2258724458809374},"rotation":{"radians":-0.9973684120631896}},"curvature":0.058574332428376834},{"time":0.8627999817275045,"velocity":4.344703190866786,"acceleration":-1.696131586806757,"pose":{"translation":{"x":2.2375152640296703,"y":-2.3031560355320284},"rotation":{"radians":-0.9911265582240422}},"curvature":0.07745929395032254},{"time":0.8833803741956509,"velocity":4.309796137132683,"acceleration":-2.0585371487899393,"pose":{"translation":{"x":2.286575788181171,"y":-2.377480489917751},"rotation":{"radians":-0.9832696274112916}},"curvature":0.09977199426284837},{"time":0.9033599711776307,"velocity":4.2686673945274265,"acceleration":-2.5296668683770758,"pose":{"translation":{"x":2.334408195375744,"y":-2.448586449924819},"rotation":{"radians":-0.9736166208148695}},"curvature":0.126529902884793},{"time":0.9227093650443854,"velocity":4.2197198739395185,"acceleration":-3.13953191681287,"pose":{"translation":{"x":2.3809672365250667,"y":-2.516235344172248},"rotation":{"radians":-0.9619448384531385}},"curvature":0.1590543960728061},{"time":0.9414092958496307,"velocity":4.161010844334259,"acceleration":-3.923919629505293,"pose":{"translation":{"x":2.426214051410481,"y":-2.580211461643035},"rotation":{"radians":-0.9479817617955386}},"curvature":0.19907449993361534},{"time":0.9594521036665412,"velocity":4.090212316570092,"acceleration":-4.922264584156884,"pose":{"translation":{"x":2.470116655145152,"y":-2.64032402431587},"rotation":{"radians":-0.9313953419033538}},"curvature":0.24886371793784065},{"time":0.976843336659243,"velocity":4.004608066335296,"acceleration":-6.17176774912248,"pose":{"translation":{"x":2.5126504246362225,"y":-2.6964092597968197},"rotation":{"radians":-0.9117827393816472}},"curvature":0.31141629925925174},{"time":0.9936034797059252,"velocity":3.9011683560091024,"acceleration":-8.55718066284625,"pose":{"translation":{"x":2.553798585046971,"y":-2.748332473951045},"rotation":{"radians":-0.8886579503447547}},"curvature":0.3906643088738414},{"time":1.0254537904752927,"velocity":3.628619492587828,"acceleration":-12.39662532879157,"pose":{"translation":{"x":2.631913139334245,"y":-2.8393118888255486},"rotation":{"radians":-0.8294412165109983}},"curvature":0.6211075800749466},{"time":1.0554677982545575,"velocity":3.2565470835328463,"acceleration":-15.10365161937661,"pose":{"translation":{"x":2.7045015699979063,"y":-2.9128450410468005},"rotation":{"radians":-0.7478462937091639}},"curvature":0.9979714067421676},{"time":1.069996742378132,"velocity":3.0371069730929885,"acceleration":-16.121922307845313,"pose":{"translation":{"x":2.7387788037720053,"y":-2.943100559831496},"rotation":{"radians":-0.696449348504947}},"curvature":1.263526319883902},{"time":1.08437649814755,"velocity":2.805277667772641,"acceleration":-16.100629398551472,"pose":{"translation":{"x":2.7717618347051216,"y":-2.969112603296221},"rotation":{"radians":-0.6368349398617001}},"curvature":1.5892041297400166},{"time":1.098711758885972,"velocity":2.5744709472917022,"acceleration":-14.800160225656162,"pose":{"translation":{"x":2.803502446693888,"y":-2.991008058807253},"rotation":{"radians":-0.5684342434947216}},"curvature":1.9717120030565085},{"time":1.113071966199183,"velocity":2.36193757818254,"acceleration":-12.189730557682944,"pose":{"translation":{"x":2.834064163588331,"y":-3.0089594730435323},"rotation":{"radians":-0.4912701719368094}},"curvature":2.390049211507602},{"time":1.1274565781948793,"velocity":2.1865930337781876,"acceleration":-9.452729526839338,"pose":{"translation":{"x":2.8635227356540307,"y":-3.0231871246283717},"rotation":{"radians":-0.40636987322213675}},"curvature":2.796409874573135},{"time":1.1346436226350656,"velocity":2.1186558465877323,"acceleration":-7.261194760818502,"pose":{"translation":{"x":2.877865477209893,"y":-3.0289869382615286},"rotation":{"radians":-0.36171741909431643}},"curvature":2.971933250793703},{"time":1.1417887663201607,"velocity":2.066773566696225,"acceleration":-4.773090124541358,"pose":{"translation":{"x":2.8919666260342733,"y":-3.0339610967611286},"rotation":{"radians":-0.31617091433168876}},"curvature":3.1137480375494775},{"time":1.148858246984371,"velocity":2.033030298352247,"acceleration":-1.9397716793931767,"pose":{"translation":{"x":2.905839306217418,"y":-3.0381514825332516},"rotation":{"radians":-0.2702880476444087}},"curvature":3.2098663582418205},{"time":1.1558106862534079,"velocity":2.019544153555468,"acceleration":1.3391284277157562,"pose":{"translation":{"x":2.919497497212209,"y":-3.0416033498489305},"rotation":{"radians":-0.22471642031179453}},"curvature":3.2491802821627607},{"time":1.162598455705074,"velocity":2.0286338485889748,"acceleration":5.241105012252983,"pose":{"translation":{"x":2.932956049036088,"y":-3.044365389613901},"rotation":{"radians":-0.18017420926151867}},"curvature":3.222625174251699},{"time":1.1691695815568548,"velocity":2.0630738092268883,"acceleration":13.159857369971245,"pose":{"translation":{"x":2.9462306974730144,"y":-3.046489794138356},"rotation":{"radians":-0.13742445513049514}},"curvature":3.1241333931057906},{"time":1.1813884049609846,"velocity":2.2238717824541028,"acceleration":30.872761161060968,"pose":{"translation":{"x":2.9722957473660427,"y":-3.0490523623471475},"rotation":{"radians":-0.060405926038590844}},"curvature":2.704652833577455},{"time":1.192083993719446,"velocity":2.5540741396710116,"acceleration":-64.97980757793125,"pose":{"translation":{"x":2.997836826166983,"y":-3.0497810822958833},"rotation":{"radians":3.9174549638033244E-4}},"curvature":2.008839569414959},{"time":1.2313896524290056,"velocity":0.0,"acceleration":-64.97980757793125,"pose":{"translation":{"x":3.048000000000002,"y":-3.048000000000002},"rotation":{"radians":0.05371225908084613}},"curvature":-1.1691366233348565E-14}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":82.04386788688518,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.003960837658956053}},"curvature":0.0},{"time":0.04861705599062372,"velocity":3.988731318744032,"acceleration":-14.986162120671922,"pose":{"translation":{"x":0.09695929073566933,"y":-4.16880132877712E-4},"rotation":{"radians":-0.02033040485690381}},"curvature":-0.48011339202264347},{"time":0.07447317296123704,"velocity":3.6012473580113644,"acceleration":-7.700425189411032,"pose":{"translation":{"x":0.19495981624216482,"y":-0.0053316734503858374},"rotation":{"radians":-0.08545062977466551}},"curvature":-0.8198502777066392},{"time":0.08855487040799276,"velocity":3.4928123002827016,"acceleration":-4.2851292698411925,"pose":{"translation":{"x":0.24462277107317196,"y":-0.010662122724874212},"rotation":{"radians":-0.12929952046633988}},"curvature":-0.9284223735685312},{"time":0.10323765312894014,"velocity":3.4298946782824515,"acceleration":-1.5645670869950543,"pose":{"translation":{"x":0.2948471423927566,"y":-0.01843507745101975},"rotation":{"radians":-0.17835307356051847}},"curvature":-0.9945667573290181},{"time":0.1184344076772456,"velocity":3.4061183362870304,"acceleration":0.6065764305371881,"pose":{"translation":{"x":0.3457074680596518,"y":-0.028983138147212293},"rotation":{"radians":-0.23085524023122095}},"curvature":-1.0201986826587648},{"time":0.13406821199091645,"velocity":3.415601433503334,"acceleration":2.304621027593365,"pose":{"translation":{"x":0.39726669237201556,"y":-0.04259091984913327},"rotation":{"radians":-0.28513455840977064}},"curvature":-1.0099327126714004},{"time":0.15007672441038006,"velocity":3.452494987845719,"acceleration":3.5731137837875306,"pose":{"translation":{"x":0.44957662374616525,"y":-0.0594968990491558},"rotation":{"radians":-0.3396883031848305}},"curvature":-0.9705299239146334},{"time":0.16641505004784743,"velocity":3.510873684384963,"acceleration":4.446660630426792,"pose":{"translation":{"x":0.5026783923953116,"y":-0.07989526063574501},"rotation":{"radians":-0.3932492699961454}},"curvature":-0.9098726567829792},{"time":0.18305641927624738,"velocity":3.584872205769285,"acceleration":4.965060662537582,"pose":{"translation":{"x":0.5566029080082937,"y":-0.10393774483285809},"rotation":{"radians":-0.44482289890825155}},"curvature":-0.835825077432052},{"time":0.1999906598326739,"velocity":3.668951737405947,"acceleration":5.178872118939808,"pose":{"translation":{"x":0.6113713174283122,"y":-0.13173549413934466},"rotation":{"radians":-0.4936918141390549}},"curvature":-0.7553148018316558},{"time":0.21722099414443607,"velocity":3.758185435373144,"acceleration":5.148057472944306,"pose":{"translation":{"x":0.6669954623316645,"y":-0.16336090026834685},"rotation":{"radians":-0.5393932214102857}},"curvature":-0.6738095874713677},{"time":0.234759951539094,"velocity":3.8484769960563643,"acceleration":4.93643001229542,"pose":{"translation":{"x":0.7234783369064792,"y":-0.1988494510866995},"rotation":{"radians":-0.5816790884865704}},"curvature":-0.5951852920387548},{"time":0.25262515031495936,"velocity":3.9366672994691694,"acceleration":4.604994697195861,"pose":{"translation":{"x":0.7808145455314498,"y":-0.23820157755433044},"rotation":{"radians":-0.6204693772224047}},"curvature":-0.5218724701926193},{"time":0.2708354955656566,"velocity":4.020525842782736,"acceleration":4.206588872506236,"pose":{"translation":{"x":0.838990760454569,"y":-0.28138450066366055},"rotation":{"radians":-0.655806281947034}},"curvature":-0.45514380303097307},{"time":0.289408087212753,"velocity":4.098653100139014,"acceleration":3.7829567821827563,"pose":{"translation":{"x":0.8979861794718639,"y":-0.3283340783790041},"rotation":{"radians":-0.6878142616676054}},"curvature":-0.39543267641623114},{"time":0.3083559240142426,"velocity":4.170331947874901,"acceleration":3.3642257650536935,"pose":{"translation":{"x":0.9577729836061292,"y":-0.37895665257596894},"rotation":{"radians":-0.7166678668322568}},"curvature":-0.34261784050540955},{"time":0.3276863537879395,"velocity":4.235363877769133,"acceleration":2.9700899332606645,"pose":{"translation":{"x":1.0183167947856622,"y":-0.4331308959808565},"rotation":{"radians":-0.742567453488204}},"curvature":-0.29624731732770176},{"time":0.3474001523523855,"velocity":4.293915632431723,"acceleration":2.6118590831086155,"pose":{"translation":{"x":1.079577133522997,"y":-0.4907096591100624},"rotation":{"radians":-0.7657218390020194}},"curvature":-0.25569904207677707},{"time":0.3674910940504928,"velocity":4.34639034099413,"acceleration":2.294695858761864,"pose":{"translation":{"x":1.1415078765936388,"y":-0.551521817209476},"rotation":{"radians":-0.7863365551744559}},"curvature":-0.22028752701688126},{"time":0.38794588486170145,"velocity":4.393327864760451,"acceleration":2.0196292959925226,"pose":{"translation":{"x":1.2040577147147982,"y":-0.6153741171938814},"rotation":{"radians":-0.8046063412012733}},"curvature":-0.1893294098683867},{"time":0.4087443497529076,"velocity":4.435333053766403,"acceleration":1.7851661520501068,"pose":{"translation":{"x":1.2671706102241251,"y":-0.6820530245863567},"rotation":{"radians":-0.8207106925835705}},"curvature":-0.1621800372499478},{"time":0.4298597896122911,"velocity":4.473027622289024,"acceleration":1.5884760015640393,"pose":{"translation":{"x":1.3307862547584441,"y":-0.7513265704576756},"rotation":{"radians":-0.834811517419783}},"curvature":-0.13825086553063487},{"time":0.4512594449630652,"velocity":4.50702046125547,"acceleration":1.42620605398305,"pose":{"translation":{"x":1.3948405269324877,"y":-0.8229461983657058},"rotation":{"radians":-0.8470521815066807}},"curvature":-0.11701485001282146},{"time":0.4729050217177735,"velocity":4.53789151386499,"acceleration":1.2950098135221093,"pose":{"translation":{"x":1.459265950017631,"y":-0.8966486112948104},"rotation":{"radians":-0.8575574194275142}},"curvature":-0.09800474543703949},{"time":0.494753248187605,"velocity":4.566185181551475,"acceleration":1.1918730332462482,"pose":{"translation":{"x":1.5239921496206263,"y":-0.972157618595248},"rotation":{"radians":-0.8664337427984783}},"curvature":-0.0808075223195219},{"time":0.5167564428436503,"velocity":4.592410195907283,"acceleration":1.114307380106349,"pose":{"translation":{"x":1.5889463113623374,"y":-1.0491859829225723},"rotation":{"radians":-0.8737700918600187}},"curvature":-0.06505688074422102},{"time":0.5388630796355971,"velocity":4.61704378443388,"acceleration":1.0604664491834883,"pose":{"translation":{"x":1.654053638556473,"y":-1.127437267177034},"rotation":{"radians":-0.8796385592970702}},"curvature":-0.05042501444162249},{"time":0.5610183427137745,"velocity":4.640538697601121,"acceleration":1.0292249031308387,"pose":{"translation":{"x":1.7192378098883225,"y":-1.206607681442978},"rotation":{"radians":-0.8840950728279422}},"curvature":-0.036614235957898436},{"time":0.5831646657820858,"velocity":4.663332244815808,"acceleration":1.0202513060755258,"pose":{"translation":{"x":1.784421437093489,"y":-1.2863879299282457},"rotation":{"radians":-0.887179962196901}},"curvature":-0.02334872853924968},{"time":0.6052422535180257,"velocity":4.685856932538398,"acceleration":0.6190297289205114,"pose":{"translation":{"x":1.8495265226366242,"y":-1.3664650579035758},"rotation":{"radians":-0.8889183619964093}},"curvature":-0.010366474520298714},{"time":0.6272108558372299,"velocity":4.699456150476817,"acceleration":-1.0504967716010856,"pose":{"translation":{"x":1.9144749173901634,"y":-1.4465242986420022},"rotation":{"radians":-0.8893204182932911}},"curvature":0.002588723896986337},{"time":0.6491148904032975,"velocity":4.676446032880125,"acceleration":-1.081508394360102,"pose":{"translation":{"x":1.9791887783130577,"y":-1.5262509203582562},"rotation":{"radians":-0.8883812774243289}},"curvature":0.015775299121229783},{"time":0.6709789593575614,"velocity":4.65279985877122,"acceleration":-1.1371104719694012,"pose":{"translation":{"x":2.043591026129511,"y":-1.605332073148167},"rotation":{"radians":-0.8860808419436056}},"curvature":0.02946226836672896},{"time":0.6927449034691424,"velocity":4.628049575789641,"acceleration":-1.219194441272511,"pose":{"translation":{"x":2.107605803007713,"y":-1.6834586359280597},"rotation":{"radians":-0.8823832835043174}},"curvature":0.04393813260960995},{"time":0.714357285036688,"velocity":4.601699880319829,"acceleration":-1.3306248642662981,"pose":{"translation":{"x":2.1711589302385734,"y":-1.7603270633741557},"rotation":{"radians":-0.8772363072499006}},"curvature":0.05952059236403715},{"time":0.7357639577379572,"velocity":4.573215629362309,"acceleration":-1.475253889594832,"pose":{"translation":{"x":2.2341783659144543,"y":-1.8356412328619742},"rotation":{"radians":-0.8705701690175973}},"curvature":0.07656734033760348},{"time":0.7569166610487092,"velocity":4.542010021527677,"acceleration":-1.6579143384256556,"pose":{"translation":{"x":2.2965946626079106,"y":-1.9091142914057355},"rotation":{"radians":-0.8622964577260398}},"curvature":0.09548814430263139},{"time":0.7777716383807286,"velocity":4.50743425558138,"acceleration":-1.8843466586654065,"pose":{"translation":{"x":2.3583414250504164,"y":-1.9804705025977558},"rotation":{"radians":-0.8523066739840298}},"curvature":0.11675831756366055},{"time":0.7982902755620526,"velocity":4.468770030168384,"acceleration":-2.1609911912303006,"pose":{"translation":{"x":2.4193557678111066,"y":-2.049447093547844},"rotation":{"radians":-0.8404706668248598}},"curvature":0.14093343621696822},{"time":0.818439752146611,"velocity":4.425227188761252,"acceleration":-2.494544357783928,"pose":{"translation":{"x":2.4795787729755046,"y":-2.115796101822716},"rotation":{"radians":-0.8266350401034745}},"curvature":0.16866471487091822},{"time":0.8381936914844454,"velocity":4.3759501108420515,"acceleration":-2.8911376736798027,"pose":{"translation":{"x":2.5389559478242623,"y":-2.1792862223853824},"rotation":{"radians":-0.8106217177148143}},"curvature":0.20071365851955927},{"time":0.8575327854022509,"velocity":4.320038127841452,"acceleration":-3.354961102939187,"pose":{"translation":{"x":2.597437682511891,"y":-2.23970465453455},"rotation":{"radians":-0.7922269749141588}},"curvature":0.23796326254617617},{"time":0.8764453543171904,"velocity":4.256587194775173,"acceleration":-3.8861395961432224,"pose":{"translation":{"x":2.654979707745497,"y":-2.2968589488440285},"rotation":{"radians":-0.7712214176061186}},"curvature":0.2814208492984974},{"time":0.8949277819897445,"velocity":4.184761900764007,"acceleration":-4.4777260255035625,"pose":{"translation":{"x":2.7115435524635143,"y":-2.3505788541021255},"rotation":{"radians":-0.7473516406900496}},"curvature":0.33220425608892623},{"time":0.912984734386199,"velocity":4.103907815077124,"acceleration":-5.11185842177919,"pose":{"translation":{"x":2.767097001514443,"y":-2.400718164251047},"rotation":{"radians":-0.7203446363245664}},"curvature":0.3914981985278621},{"time":0.9306290336987828,"velocity":4.0137126550397,"acceleration":-5.755509512267635,"pose":{"translation":{"x":2.821614553335579,"y":-2.4471565653262983},"rotation":{"radians":-0.6899164560608424}},"curvature":0.46046118584548174},{"time":0.9478810135495537,"velocity":3.9144187209031385,"acceleration":-6.356839268896832,"pose":{"translation":{"x":2.8750778776317483,"y":-2.489801482396083},"rotation":{"radians":-0.6557871246247801}},"curvature":0.5400562006079622},{"time":0.9647671374724911,"velocity":3.8070763452503513,"acceleration":-6.8437882315068626,"pose":{"translation":{"x":2.9274762730540473,"y":-2.528589926500712},"rotation":{"radians":-0.6177042511649705}},"curvature":0.6307732766495935},{"time":0.981317637459908,"velocity":3.6938082282109135,"acceleration":-7.126794452842301,"pose":{"translation":{"x":2.9788071248785712,"y":-2.563490341591984},"rotation":{"radians":-0.5754779499559356}},"curvature":0.7322154294929463},{"time":0.9975629544099581,"velocity":3.5780311934866313,"acceleration":-7.10674688337942,"pose":{"translation":{"x":3.029076362685149,"y":-2.594504451472612},"rotation":{"radians":-0.5290291461838743}},"curvature":0.8425421381827005},{"time":1.0135288841201933,"velocity":3.4645653722781624,"acceleration":-6.6870818297374965,"pose":{"translation":{"x":3.0782989180360785,"y":-2.621669106735596},"rotation":{"radians":-0.478451501975481}},"curvature":0.9578207889404049},{"time":1.0292306002321454,"velocity":3.3595667117702304,"acceleration":-5.785774257210771,"pose":{"translation":{"x":3.126499182154865,"y":-2.645058131703647},"rotation":{"radians":-0.4240834522171856}},"curvature":1.0714338957068112},{"time":1.0446661559449735,"velocity":3.2702600708812066,"acceleration":-4.340553001474387,"pose":{"translation":{"x":3.173711463604948,"y":-2.664784171368569},"rotation":{"radians":-0.3665810929551392}},"curvature":1.1738091280013403},{"time":1.059810582885297,"velocity":3.2045248830697757,"acceleration":-2.30081053720373,"pose":{"translation":{"x":3.2199804459684396,"y":-2.6810005383306725},"rotation":{"radians":-0.3069761459696382}},"curvature":1.2528094160899457},{"time":1.0746120846913012,"velocity":3.170469431748081,"acceleration":0.3977579187639632,"pose":{"translation":{"x":3.2653616455248597,"y":-2.693903059738172},"rotation":{"radians":-0.24669911820251192}},"curvature":1.2950253234940936},{"time":1.0889917302829935,"velocity":3.176189049651196,"acceleration":3.8780505815630546,"pose":{"translation":{"x":3.3099218689298664,"y":-2.703731924226575},"rotation":{"radians":-0.18755053544781314}},"curvature":1.2878719020972225},{"time":1.1028472499648765,"velocity":3.2299214558113807,"acceleration":8.392529795697191,"pose":{"translation":{"x":3.3537396708939986,"y":-2.710773528858087},"rotation":{"radians":-0.13161552235012597}},"curvature":1.2219067314503889},{"time":1.1160601938775772,"velocity":3.340811481287596,"acceleration":18.700043425813895,"pose":{"translation":{"x":3.3969058118613997,"y":-2.715362326061045},"rotation":{"radians":-0.08113614721932995}},"curvature":1.0924796198481246},{"time":1.1398773728434104,"velocity":3.786193762229057,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.4817099273230365,"y":-2.7187706663614057},"rotation":{"radians":-0.005486303923341652}},"curvature":0.6490192275525587},{"time":1.184047961373033,"velocity":0.0,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.565321805332028,"y":-2.7176638555734356},"rotation":{"radians":0.022896761221391358}},"curvature":7.928831080838964E-15}] \ No newline at end of file From 2a00e074dbd83d54e31f835dc733bed8037d53d4 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 3 Mar 2020 19:40:00 -0600 Subject: [PATCH 20/31] More paths and updates to pathfinder action, robot, and drivesubsystem --- PathWeaver/Paths/example.path | 4 ++-- PathWeaver/Paths/first.path | 3 +++ PathWeaver/output/example.wpilib.json | 2 +- PathWeaver/output/first.wpilib.json | 1 + PathWeaver/output/second.wpilib.json | 1 + src/Autonomous/Actions/PathFinder.cpp | 1 + src/DriveSubsystem.cpp | 4 ++-- src/DriveSubsystem.h | 1 - src/Robot.cpp | 8 +++++++- src/main/deploy/paths/example.wpilib.json | 2 +- src/main/deploy/paths/first.wpilib.json | 1 + 11 files changed, 20 insertions(+), 8 deletions(-) create mode 100644 PathWeaver/Paths/first.path create mode 100644 PathWeaver/output/first.wpilib.json create mode 100644 PathWeaver/output/second.wpilib.json create mode 100644 src/main/deploy/paths/first.wpilib.json diff --git a/PathWeaver/Paths/example.path b/PathWeaver/Paths/example.path index d6ee0ad..21caaf4 100644 --- a/PathWeaver/Paths/example.path +++ b/PathWeaver/Paths/example.path @@ -1,3 +1,3 @@ X,Y,Tangent X,Tangent Y,Fixed Theta,Name -0.0,0.0,3.096751790637463,0.01226579525575619,true, -3.5653218053320264,-2.7176638555734374,2.6688118228255537,0.06111782800363885,true, +0.0,0.0,3.048,0.0,true, +15.23876963475554,-5.0266196237355265,3.16950164983399,-0.06852976540181599,true, diff --git a/PathWeaver/Paths/first.path b/PathWeaver/Paths/first.path new file mode 100644 index 0000000..addfad8 --- /dev/null +++ b/PathWeaver/Paths/first.path @@ -0,0 +1,3 @@ +X,Y,Tangent X,Tangent Y,Fixed Theta,Name +0.0,0.0,3.096751790637463,0.01226579525575619,true, +1.4128894649391648,-0.14387383885613672,2.6688118228255537,0.06111782800363885,true, diff --git a/PathWeaver/output/example.wpilib.json b/PathWeaver/output/example.wpilib.json index 667ae69..42fb442 100644 --- a/PathWeaver/output/example.wpilib.json +++ b/PathWeaver/output/example.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":82.04386788688518,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.003960837658956053}},"curvature":0.0},{"time":0.04861705599062372,"velocity":3.988731318744032,"acceleration":-14.986162120671922,"pose":{"translation":{"x":0.09695929073566933,"y":-4.16880132877712E-4},"rotation":{"radians":-0.02033040485690381}},"curvature":-0.48011339202264347},{"time":0.07447317296123704,"velocity":3.6012473580113644,"acceleration":-7.700425189411032,"pose":{"translation":{"x":0.19495981624216482,"y":-0.0053316734503858374},"rotation":{"radians":-0.08545062977466551}},"curvature":-0.8198502777066392},{"time":0.08855487040799276,"velocity":3.4928123002827016,"acceleration":-4.2851292698411925,"pose":{"translation":{"x":0.24462277107317196,"y":-0.010662122724874212},"rotation":{"radians":-0.12929952046633988}},"curvature":-0.9284223735685312},{"time":0.10323765312894014,"velocity":3.4298946782824515,"acceleration":-1.5645670869950543,"pose":{"translation":{"x":0.2948471423927566,"y":-0.01843507745101975},"rotation":{"radians":-0.17835307356051847}},"curvature":-0.9945667573290181},{"time":0.1184344076772456,"velocity":3.4061183362870304,"acceleration":0.6065764305371881,"pose":{"translation":{"x":0.3457074680596518,"y":-0.028983138147212293},"rotation":{"radians":-0.23085524023122095}},"curvature":-1.0201986826587648},{"time":0.13406821199091645,"velocity":3.415601433503334,"acceleration":2.304621027593365,"pose":{"translation":{"x":0.39726669237201556,"y":-0.04259091984913327},"rotation":{"radians":-0.28513455840977064}},"curvature":-1.0099327126714004},{"time":0.15007672441038006,"velocity":3.452494987845719,"acceleration":3.5731137837875306,"pose":{"translation":{"x":0.44957662374616525,"y":-0.0594968990491558},"rotation":{"radians":-0.3396883031848305}},"curvature":-0.9705299239146334},{"time":0.16641505004784743,"velocity":3.510873684384963,"acceleration":4.446660630426792,"pose":{"translation":{"x":0.5026783923953116,"y":-0.07989526063574501},"rotation":{"radians":-0.3932492699961454}},"curvature":-0.9098726567829792},{"time":0.18305641927624738,"velocity":3.584872205769285,"acceleration":4.965060662537582,"pose":{"translation":{"x":0.5566029080082937,"y":-0.10393774483285809},"rotation":{"radians":-0.44482289890825155}},"curvature":-0.835825077432052},{"time":0.1999906598326739,"velocity":3.668951737405947,"acceleration":5.178872118939808,"pose":{"translation":{"x":0.6113713174283122,"y":-0.13173549413934466},"rotation":{"radians":-0.4936918141390549}},"curvature":-0.7553148018316558},{"time":0.21722099414443607,"velocity":3.758185435373144,"acceleration":5.148057472944306,"pose":{"translation":{"x":0.6669954623316645,"y":-0.16336090026834685},"rotation":{"radians":-0.5393932214102857}},"curvature":-0.6738095874713677},{"time":0.234759951539094,"velocity":3.8484769960563643,"acceleration":4.93643001229542,"pose":{"translation":{"x":0.7234783369064792,"y":-0.1988494510866995},"rotation":{"radians":-0.5816790884865704}},"curvature":-0.5951852920387548},{"time":0.25262515031495936,"velocity":3.9366672994691694,"acceleration":4.604994697195861,"pose":{"translation":{"x":0.7808145455314498,"y":-0.23820157755433044},"rotation":{"radians":-0.6204693772224047}},"curvature":-0.5218724701926193},{"time":0.2708354955656566,"velocity":4.020525842782736,"acceleration":4.206588872506236,"pose":{"translation":{"x":0.838990760454569,"y":-0.28138450066366055},"rotation":{"radians":-0.655806281947034}},"curvature":-0.45514380303097307},{"time":0.289408087212753,"velocity":4.098653100139014,"acceleration":3.7829567821827563,"pose":{"translation":{"x":0.8979861794718639,"y":-0.3283340783790041},"rotation":{"radians":-0.6878142616676054}},"curvature":-0.39543267641623114},{"time":0.3083559240142426,"velocity":4.170331947874901,"acceleration":3.3642257650536935,"pose":{"translation":{"x":0.9577729836061292,"y":-0.37895665257596894},"rotation":{"radians":-0.7166678668322568}},"curvature":-0.34261784050540955},{"time":0.3276863537879395,"velocity":4.235363877769133,"acceleration":2.9700899332606645,"pose":{"translation":{"x":1.0183167947856622,"y":-0.4331308959808565},"rotation":{"radians":-0.742567453488204}},"curvature":-0.29624731732770176},{"time":0.3474001523523855,"velocity":4.293915632431723,"acceleration":2.6118590831086155,"pose":{"translation":{"x":1.079577133522997,"y":-0.4907096591100624},"rotation":{"radians":-0.7657218390020194}},"curvature":-0.25569904207677707},{"time":0.3674910940504928,"velocity":4.34639034099413,"acceleration":2.294695858761864,"pose":{"translation":{"x":1.1415078765936388,"y":-0.551521817209476},"rotation":{"radians":-0.7863365551744559}},"curvature":-0.22028752701688126},{"time":0.38794588486170145,"velocity":4.393327864760451,"acceleration":2.0196292959925226,"pose":{"translation":{"x":1.2040577147147982,"y":-0.6153741171938814},"rotation":{"radians":-0.8046063412012733}},"curvature":-0.1893294098683867},{"time":0.4087443497529076,"velocity":4.435333053766403,"acceleration":1.7851661520501068,"pose":{"translation":{"x":1.2671706102241251,"y":-0.6820530245863567},"rotation":{"radians":-0.8207106925835705}},"curvature":-0.1621800372499478},{"time":0.4298597896122911,"velocity":4.473027622289024,"acceleration":1.5884760015640393,"pose":{"translation":{"x":1.3307862547584441,"y":-0.7513265704576756},"rotation":{"radians":-0.834811517419783}},"curvature":-0.13825086553063487},{"time":0.4512594449630652,"velocity":4.50702046125547,"acceleration":1.42620605398305,"pose":{"translation":{"x":1.3948405269324877,"y":-0.8229461983657058},"rotation":{"radians":-0.8470521815066807}},"curvature":-0.11701485001282146},{"time":0.4729050217177735,"velocity":4.53789151386499,"acceleration":1.2950098135221093,"pose":{"translation":{"x":1.459265950017631,"y":-0.8966486112948104},"rotation":{"radians":-0.8575574194275142}},"curvature":-0.09800474543703949},{"time":0.494753248187605,"velocity":4.566185181551475,"acceleration":1.1918730332462482,"pose":{"translation":{"x":1.5239921496206263,"y":-0.972157618595248},"rotation":{"radians":-0.8664337427984783}},"curvature":-0.0808075223195219},{"time":0.5167564428436503,"velocity":4.592410195907283,"acceleration":1.114307380106349,"pose":{"translation":{"x":1.5889463113623374,"y":-1.0491859829225723},"rotation":{"radians":-0.8737700918600187}},"curvature":-0.06505688074422102},{"time":0.5388630796355971,"velocity":4.61704378443388,"acceleration":1.0604664491834883,"pose":{"translation":{"x":1.654053638556473,"y":-1.127437267177034},"rotation":{"radians":-0.8796385592970702}},"curvature":-0.05042501444162249},{"time":0.5610183427137745,"velocity":4.640538697601121,"acceleration":1.0292249031308387,"pose":{"translation":{"x":1.7192378098883225,"y":-1.206607681442978},"rotation":{"radians":-0.8840950728279422}},"curvature":-0.036614235957898436},{"time":0.5831646657820858,"velocity":4.663332244815808,"acceleration":1.0202513060755258,"pose":{"translation":{"x":1.784421437093489,"y":-1.2863879299282457},"rotation":{"radians":-0.887179962196901}},"curvature":-0.02334872853924968},{"time":0.6052422535180257,"velocity":4.685856932538398,"acceleration":0.6190297289205114,"pose":{"translation":{"x":1.8495265226366242,"y":-1.3664650579035758},"rotation":{"radians":-0.8889183619964093}},"curvature":-0.010366474520298714},{"time":0.6272108558372299,"velocity":4.699456150476817,"acceleration":-1.0504967716010856,"pose":{"translation":{"x":1.9144749173901634,"y":-1.4465242986420022},"rotation":{"radians":-0.8893204182932911}},"curvature":0.002588723896986337},{"time":0.6491148904032975,"velocity":4.676446032880125,"acceleration":-1.081508394360102,"pose":{"translation":{"x":1.9791887783130577,"y":-1.5262509203582562},"rotation":{"radians":-0.8883812774243289}},"curvature":0.015775299121229783},{"time":0.6709789593575614,"velocity":4.65279985877122,"acceleration":-1.1371104719694012,"pose":{"translation":{"x":2.043591026129511,"y":-1.605332073148167},"rotation":{"radians":-0.8860808419436056}},"curvature":0.02946226836672896},{"time":0.6927449034691424,"velocity":4.628049575789641,"acceleration":-1.219194441272511,"pose":{"translation":{"x":2.107605803007713,"y":-1.6834586359280597},"rotation":{"radians":-0.8823832835043174}},"curvature":0.04393813260960995},{"time":0.714357285036688,"velocity":4.601699880319829,"acceleration":-1.3306248642662981,"pose":{"translation":{"x":2.1711589302385734,"y":-1.7603270633741557},"rotation":{"radians":-0.8772363072499006}},"curvature":0.05952059236403715},{"time":0.7357639577379572,"velocity":4.573215629362309,"acceleration":-1.475253889594832,"pose":{"translation":{"x":2.2341783659144543,"y":-1.8356412328619742},"rotation":{"radians":-0.8705701690175973}},"curvature":0.07656734033760348},{"time":0.7569166610487092,"velocity":4.542010021527677,"acceleration":-1.6579143384256556,"pose":{"translation":{"x":2.2965946626079106,"y":-1.9091142914057355},"rotation":{"radians":-0.8622964577260398}},"curvature":0.09548814430263139},{"time":0.7777716383807286,"velocity":4.50743425558138,"acceleration":-1.8843466586654065,"pose":{"translation":{"x":2.3583414250504164,"y":-1.9804705025977558},"rotation":{"radians":-0.8523066739840298}},"curvature":0.11675831756366055},{"time":0.7982902755620526,"velocity":4.468770030168384,"acceleration":-2.1609911912303006,"pose":{"translation":{"x":2.4193557678111066,"y":-2.049447093547844},"rotation":{"radians":-0.8404706668248598}},"curvature":0.14093343621696822},{"time":0.818439752146611,"velocity":4.425227188761252,"acceleration":-2.494544357783928,"pose":{"translation":{"x":2.4795787729755046,"y":-2.115796101822716},"rotation":{"radians":-0.8266350401034745}},"curvature":0.16866471487091822},{"time":0.8381936914844454,"velocity":4.3759501108420515,"acceleration":-2.8911376736798027,"pose":{"translation":{"x":2.5389559478242623,"y":-2.1792862223853824},"rotation":{"radians":-0.8106217177148143}},"curvature":0.20071365851955927},{"time":0.8575327854022509,"velocity":4.320038127841452,"acceleration":-3.354961102939187,"pose":{"translation":{"x":2.597437682511891,"y":-2.23970465453455},"rotation":{"radians":-0.7922269749141588}},"curvature":0.23796326254617617},{"time":0.8764453543171904,"velocity":4.256587194775173,"acceleration":-3.8861395961432224,"pose":{"translation":{"x":2.654979707745497,"y":-2.2968589488440285},"rotation":{"radians":-0.7712214176061186}},"curvature":0.2814208492984974},{"time":0.8949277819897445,"velocity":4.184761900764007,"acceleration":-4.4777260255035625,"pose":{"translation":{"x":2.7115435524635143,"y":-2.3505788541021255},"rotation":{"radians":-0.7473516406900496}},"curvature":0.33220425608892623},{"time":0.912984734386199,"velocity":4.103907815077124,"acceleration":-5.11185842177919,"pose":{"translation":{"x":2.767097001514443,"y":-2.400718164251047},"rotation":{"radians":-0.7203446363245664}},"curvature":0.3914981985278621},{"time":0.9306290336987828,"velocity":4.0137126550397,"acceleration":-5.755509512267635,"pose":{"translation":{"x":2.821614553335579,"y":-2.4471565653262983},"rotation":{"radians":-0.6899164560608424}},"curvature":0.46046118584548174},{"time":0.9478810135495537,"velocity":3.9144187209031385,"acceleration":-6.356839268896832,"pose":{"translation":{"x":2.8750778776317483,"y":-2.489801482396083},"rotation":{"radians":-0.6557871246247801}},"curvature":0.5400562006079622},{"time":0.9647671374724911,"velocity":3.8070763452503513,"acceleration":-6.8437882315068626,"pose":{"translation":{"x":2.9274762730540473,"y":-2.528589926500712},"rotation":{"radians":-0.6177042511649705}},"curvature":0.6307732766495935},{"time":0.981317637459908,"velocity":3.6938082282109135,"acceleration":-7.126794452842301,"pose":{"translation":{"x":2.9788071248785712,"y":-2.563490341591984},"rotation":{"radians":-0.5754779499559356}},"curvature":0.7322154294929463},{"time":0.9975629544099581,"velocity":3.5780311934866313,"acceleration":-7.10674688337942,"pose":{"translation":{"x":3.029076362685149,"y":-2.594504451472612},"rotation":{"radians":-0.5290291461838743}},"curvature":0.8425421381827005},{"time":1.0135288841201933,"velocity":3.4645653722781624,"acceleration":-6.6870818297374965,"pose":{"translation":{"x":3.0782989180360785,"y":-2.621669106735596},"rotation":{"radians":-0.478451501975481}},"curvature":0.9578207889404049},{"time":1.0292306002321454,"velocity":3.3595667117702304,"acceleration":-5.785774257210771,"pose":{"translation":{"x":3.126499182154865,"y":-2.645058131703647},"rotation":{"radians":-0.4240834522171856}},"curvature":1.0714338957068112},{"time":1.0446661559449735,"velocity":3.2702600708812066,"acceleration":-4.340553001474387,"pose":{"translation":{"x":3.173711463604948,"y":-2.664784171368569},"rotation":{"radians":-0.3665810929551392}},"curvature":1.1738091280013403},{"time":1.059810582885297,"velocity":3.2045248830697757,"acceleration":-2.30081053720373,"pose":{"translation":{"x":3.2199804459684396,"y":-2.6810005383306725},"rotation":{"radians":-0.3069761459696382}},"curvature":1.2528094160899457},{"time":1.0746120846913012,"velocity":3.170469431748081,"acceleration":0.3977579187639632,"pose":{"translation":{"x":3.2653616455248597,"y":-2.693903059738172},"rotation":{"radians":-0.24669911820251192}},"curvature":1.2950253234940936},{"time":1.0889917302829935,"velocity":3.176189049651196,"acceleration":3.8780505815630546,"pose":{"translation":{"x":3.3099218689298664,"y":-2.703731924226575},"rotation":{"radians":-0.18755053544781314}},"curvature":1.2878719020972225},{"time":1.1028472499648765,"velocity":3.2299214558113807,"acceleration":8.392529795697191,"pose":{"translation":{"x":3.3537396708939986,"y":-2.710773528858087},"rotation":{"radians":-0.13161552235012597}},"curvature":1.2219067314503889},{"time":1.1160601938775772,"velocity":3.340811481287596,"acceleration":18.700043425813895,"pose":{"translation":{"x":3.3969058118613997,"y":-2.715362326061045},"rotation":{"radians":-0.08113614721932995}},"curvature":1.0924796198481246},{"time":1.1398773728434104,"velocity":3.786193762229057,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.4817099273230365,"y":-2.7187706663614057},"rotation":{"radians":-0.005486303923341652}},"curvature":0.6490192275525587},{"time":1.184047961373033,"velocity":0.0,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.565321805332028,"y":-2.7176638555734356},"rotation":{"radians":0.022896761221391358}},"curvature":7.928831080838964E-15}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":71.6754486328193,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.052504537201690564,"velocity":3.763286259189722,"acceleration":3.393027875765885,"pose":{"translation":{"x":0.0987840856718992,"y":-0.0014550809384724233},"rotation":{"radians":-0.0406235201304543}},"curvature":-0.669267331858832},{"time":0.08369849591678691,"velocity":3.869128230665534,"acceleration":8.940395462782044,"pose":{"translation":{"x":0.21743610778889016,"y":-0.011090481290308164},"rotation":{"radians":-0.11922715157584657}},"curvature":-0.5777181959580991},{"time":0.10210103517690408,"velocity":4.033654209170354,"acceleration":7.7520539423460715,"pose":{"translation":{"x":0.2894547521368349,"y":-0.021134285931893225},"rotation":{"radians":-0.15629119482489962}},"curvature":-0.4449483653936229},{"time":0.12254133010230119,"velocity":4.192108478029495,"acceleration":5.75700633123382,"pose":{"translation":{"x":0.3722655413186195,"y":-0.035621769310835674},"rotation":{"radians":-0.18844460732445098}},"curvature":-0.3269300330427504},{"time":0.14533768211239437,"velocity":4.3233472208806365,"acceleration":3.944401761401226,"pose":{"translation":{"x":0.4673396090946371,"y":-0.055158757396353585},"rotation":{"radians":-0.21542702352704587}},"curvature":-0.2357318596690303},{"time":0.17082259532410582,"velocity":4.423869957442069,"acceleration":2.8844388002223487,"pose":{"translation":{"x":0.5759365232228123,"y":-0.08026398863855952},"rotation":{"radians":-0.23772289170313524}},"curvature":-0.16953787250521077},{"time":0.18466411165336516,"velocity":4.4637949641960954,"acceleration":2.326862827367757,"pose":{"translation":{"x":0.635643814194672,"y":-0.09504381204755785},"rotation":{"radians":-0.24733668078881516}},"curvature":-0.14407454738817005},{"time":0.1992899012288189,"velocity":4.497827170280122,"acceleration":1.8726028175616212,"pose":{"translation":{"x":0.6991124192700513,"y":-0.11137246160318348},"rotation":{"radians":-0.2560512882871814}},"curvature":-0.12272641890725453},{"time":0.21473112059424881,"velocity":4.526742441170413,"acceleration":1.5061957817442015,"pose":{"translation":{"x":0.766443903568408,"y":-0.1292917769905396},"rotation":{"radians":-0.2639545845640026}},"curvature":-0.1048403284194074},{"time":0.23101567055964584,"velocity":4.551270161635896,"acceleration":1.2125328488063274,"pose":{"translation":{"x":0.8377281344236926,"y":-0.14883878260629593},"rotation":{"radians":-0.27112822180522567}},"curvature":-0.08984639789950959},{"time":0.2481681966511829,"velocity":4.572068162961893,"acceleration":0.9780339853892758,"pose":{"translation":{"x":0.9130435355659563,"y":-0.1700457921722737},"rotation":{"radians":-0.2776468756372453}},"curvature":-0.07725850624670107},{"time":0.2662101398397362,"velocity":4.58971379656276,"acceleration":0.7910806745495272,"pose":{"translation":{"x":0.9924573413029585,"y":-0.19294051334903078},"rotation":{"radians":-0.2835780974936386}},"curvature":-0.06666802579853986},{"time":0.28515981743654306,"velocity":4.604704520298538,"acceleration":0.6420396874172175,"pose":{"translation":{"x":1.0760258507017746,"y":-0.21754615234944685},"rotation":{"radians":-0.2889825347232104}},"curvature":-0.057734725453877866},{"time":0.30503252074980275,"velocity":4.617463584521919,"acceleration":0.5230871945044425,"pose":{"translation":{"x":1.1637946817704043,"y":-0.24388151855230836},"rotation":{"radians":-0.29391435676502015}},"curvature":-0.050177014396362525},{"time":0.32584062079799275,"velocity":4.628348035199094,"acceleration":0.42795546527859657,"pose":{"translation":{"x":1.2557990256393792,"y":-0.2719611291158937},"rotation":{"radians":-0.29842178249670276}},"curvature":-0.04376264842952715},{"time":0.3475936765970335,"velocity":4.637657374314804,"acceleration":0.35166819045207165,"pose":{"translation":{"x":1.3520639007433704,"y":-0.3017953135915584},"rotation":{"radians":-0.30254764263473954}},"curvature":-0.03830040704132812},{"time":0.37029854270166584,"velocity":4.645641953492277,"acceleration":0.29029645766093237,"pose":{"translation":{"x":1.4526044070027964,"y":-0.33339031853731993},"rotation":{"radians":-0.3063299370432376}},"curvature":-0.03363290685993953},{"time":0.3939594741066458,"velocity":4.652510638064101,"acceleration":0.24074807079349372,"pose":{"translation":{"x":1.5574259800054309,"y":-0.36674841213144305},"rotation":{"radians":-0.3098023639018164}},"curvature":-0.02963053745593578},{"time":0.4185782275335135,"velocity":4.65843755545696,"acceleration":0.2005926419332328,"pose":{"translation":{"x":1.666524645188012,"y":-0.4018679887860249},"rotation":{"radians":-0.3129948087165449}},"curvature":-0.026186420205458822},{"time":0.4441541587084636,"velocity":4.6635678990612455,"acceleration":0.16791995076836871,"pose":{"translation":{"x":1.7798872720178476,"y":-0.4387436737605798},"rotation":{"radians":-0.31593378811677125}},"curvature":-0.023212258501245673},{"time":0.4706843155906152,"velocity":4.6680228416987735,"acceleration":0.1473081055449243,"pose":{"translation":{"x":1.8974918281744246,"y":-0.477366427775625},"rotation":{"radians":-0.3186428476369191}},"curvature":-0.020634943232970684},{"time":0.48430557417763576,"velocity":4.670029363496365,"acceleration":0.13525227729273576,"pose":{"translation":{"x":1.9578755731199786,"y":-0.49732915462086014},"rotation":{"radians":-0.31991779085791866}},"curvature":-0.01947571752148467},{"time":0.4981632894321226,"velocity":4.671903651042609,"acceleration":0.12432688548768328,"pose":{"translation":{"x":2.019307633731017,"y":-0.5177236516262647},"rotation":{"radians":-0.3211429151700534}},"curvature":-0.018393786838207256},{"time":0.5122564819575298,"velocity":4.673655813775871,"acceleration":0.11441569818551017,"pose":{"translation":{"x":2.081782865529898,"y":-0.538547804816047},"rotation":{"radians":-0.3223204787561041}},"curvature":-0.017383137392378067},{"time":0.5265840442775498,"velocity":4.675295111822012,"acceleration":0.10541529555668874,"pose":{"translation":{"x":2.145295615336293,"y":-0.5597992907957762},"rotation":{"radians":-0.3234526131282243}},"curvature":-0.01643827432726884},{"time":0.5411447433384899,"velocity":4.676830032217033,"acceleration":0.0972335891691984,"pose":{"translation":{"x":2.20983972921036,"y":-0.5814755800215547},"rotation":{"radians":-0.3245413308852529}},"curvature":-0.015554173193681813},{"time":0.5559372229684437,"velocity":4.678268358104166,"acceleration":0.08978851658604482,"pose":{"translation":{"x":2.275408560395923,"y":-0.6035739400691946},"rotation":{"radians":-0.3255885329724584}},"curvature":-0.014726236202830386},{"time":0.5709600062957906,"velocity":4.679617231534122,"acceleration":0.0830068906946886,"pose":{"translation":{"x":2.3419949772636413,"y":-0.6260914389033911},"rotation":{"radians":-0.32659601547299605}},"curvature":-0.013950252777561888},{"time":0.5862114981295551,"velocity":4.680883210449698,"acceleration":0.07682338543969686,"pose":{"translation":{"x":2.4095913712541885,"y":-0.6490249481468979},"rotation":{"radians":-0.3275654759594006}},"curvature":-0.013222363967972418},{"time":0.6016899873039058,"velocity":4.682072320389564,"acceleration":0.07117964169334849,"pose":{"translation":{"x":2.4781896648214286,"y":-0.6723711463497003},"rotation":{"radians":-0.3284985194323406}},"curvature":-0.012539030340552192},{"time":0.6173936489891477,"velocity":4.683190101401593,"acceleration":0.06602347886871857,"pose":{"translation":{"x":2.547781319375588,"y":-0.6961265222581916},"rotation":{"radians":-0.32939666387264166}},"curvature":-0.011897002989255367},{"time":0.6333205469712927,"velocity":4.684241650613961,"acceleration":0.061308199557898,"pose":{"translation":{"x":2.618357343226433,"y":-0.7202873780843462},"rotation":{"radians":-0.3302613454313242}},"curvature":-0.011293297352516853},{"time":0.6494686359022924,"velocity":4.685231660872621,"acceleration":0.056991975988469196,"pose":{"translation":{"x":2.6899082995264454,"y":-0.7448498327748948},"rotation":{"radians":-0.33109392328110016}},"curvature":-0.010725169552478188},{"time":0.6658357635228018,"velocity":4.68616445581697,"acceleration":0.05303730842556608,"pose":{"translation":{"x":2.762424314213996,"y":-0.7698098252804986},"rotation":{"radians":-0.33189568415147325}},"curvature":-0.010190095001780771},{"time":0.6824196728593326,"velocity":4.687044021731353,"acceleration":0.04941054684157204,"pose":{"translation":{"x":2.8358950839565202,"y":-0.7951631178249241},"rotation":{"radians":-0.332667846568304}},"curvature":-0.009685749049497792},{"time":0.699218004397476,"velocity":4.687874036478679,"acceleration":0.046081468224634096,"pose":{"translation":{"x":2.9103098840936954,"y":-0.8209052991742178},"rotation":{"radians":-0.3334115648174423}},"curvature":-0.009209989461344641},{"time":0.7162282982327365,"velocity":4.68865789579354,"acceleration":0.04302290282954284,"pose":{"translation":{"x":2.9856575765806124,"y":-0.8470317879058803},"rotation":{"radians":-0.3341279326508223}},"curvature":-0.008760840550476132},{"time":0.7334479962006001,"velocity":4.689398737185965,"acceleration":0.04021040348993698,"pose":{"translation":{"x":3.061926617930954,"y":-0.8735378356780407},"rotation":{"radians":-0.3348179867522378}},"curvature":-0.008336478794167414},{"time":0.7508744439870677,"velocity":4.6900994616828555,"acceleration":0.03762195283333545,"pose":{"translation":{"x":3.13910506716017,"y":-0.9004185304986319},"rotation":{"radians":-0.33548270997890794}},"curvature":-0.007935219788693488},{"time":0.7685048932210419,"velocity":4.690762753612367,"acceleration":0.03523770386995457,"pose":{"translation":{"x":3.2171805937286497,"y":-0.927668799994564},"rotation":{"radians":-0.33612303439387825}},"curvature":-0.007555506409969931},{"time":0.7863365035498443,"velocity":4.691391098616657,"acceleration":0.033039749987155066,"pose":{"translation":{"x":3.296140485484901,"y":-0.9552834146809005},"rotation":{"radians":-0.3367398441032938}},"curvature":-0.007195898061161926},{"time":0.8043663446988317,"velocity":4.691986800060528,"acceleration":0.03101192085748364,"pose":{"translation":{"x":3.3759716566087206,"y":-0.983256991230031},"rotation":{"radians":-0.3373339779116408}},"curvature":-0.006855060900686268},{"time":0.8225913985163283,"velocity":4.69255199398714,"acceleration":0.029139601208403573,"pose":{"translation":{"x":3.4566606555543737,"y":-1.011583995740847},"rotation":{"radians":-0.3379062318071501}},"curvature":-0.00653175895495657},{"time":0.8410085610047663,"velocity":4.693088662757443,"acceleration":0.027409569760689707,"pose":{"translation":{"x":3.5381936729937724,"y":-1.0402587470079157},"rotation":{"radians":-0.3384573612887194}},"curvature":-0.006224846030001168},{"time":0.8596146443389476,"velocity":4.6935986474965645,"acceleration":0.025809855984173163,"pose":{"translation":{"x":3.6205565497596375,"y":-1.069275419790655},"rotation":{"radians":-0.3389880835449301}},"curvature":-0.005933258344827627},{"time":0.8784063788723748,"velocity":4.694083659458565,"acceleration":0.02432961259209342,"pose":{"translation":{"x":3.70373478478869,"y":-1.0986280480825084},"rotation":{"radians":-0.3394990794949884}},"curvature":-0.0056560078172345615},{"time":0.897380415132286,"velocity":4.694545290410077,"acceleration":0.022959001958506343,"pose":{"translation":{"x":3.7877135430648137,"y":-1.1283105283801182},"rotation":{"radians":-0.3399909957007404}},"curvature":-0.005392175939770404},{"time":0.9165333258042762,"velocity":4.694985022123706,"acceleration":0.021689094852614006,"pose":{"translation":{"x":3.872477663562239,"y":-1.1583166229525013},"rotation":{"radians":-0.34046444615826527}},"curvature":-0.00514090818980659},{"time":0.9358616077071303,"velocity":4.6954042350632355,"acceleration":0.020511780085435836,"pose":{"translation":{"x":3.9580116671887158,"y":-1.1886399631102225},"rotation":{"radians":-0.34092001397695176}},"curvature":-0.004901408923299515},{"time":0.9553616837584529,"velocity":4.6958042163348495,"acceleration":0.01941968382425391,"pose":{"translation":{"x":4.044299764728684,"y":-1.2192740524745713},"rotation":{"radians":-0.34135825295340627}},"curvature":-0.004672936706836661},{"time":0.9750299049318558,"velocity":4.696186166971422,"acceleration":0.018406097485132958,"pose":{"translation":{"x":4.131325864786455,"y":-1.250212270246734},"rotation":{"radians":-0.34177968904702144}},"curvature":-0.004454800047062241},{"time":0.9948625522059731,"velocity":4.696551208610538,"acceleration":0.017464913239636663,"pose":{"translation":{"x":4.219073581729384,"y":-1.281447874476969},"rotation":{"radians":-0.3421848217635512}},"curvature":-0.004246353480603635},{"time":1.0148558385061224,"velocity":4.696900389621145,"acceleration":0.01659056628522065,"pose":{"translation":{"x":4.3075262436310435,"y":-1.312974005333782},"rotation":{"radians":-0.3425741254525841}},"curvature":-0.00404699399123586},{"time":1.0350059106388894,"velocity":4.697234690728516,"acceleration":0.015777983132407462,"pose":{"translation":{"x":4.396666900214407,"y":-1.3447836883730995},"rotation":{"radians":-0.3429480505243987}},"curvature":-0.0038561577242561726},{"time":1.0553088512201658,"velocity":4.697555030182546,"acceleration":0.015022535243084308,"pose":{"translation":{"x":4.48647833079501,"y":-1.3768698378074444},"rotation":{"radians":-0.34330702459128587}},"curvature":-0.003673316970948526},{"time":1.0757606805969266,"velocity":4.697862268510144,"acceleration":0.014319997438426777,"pose":{"translation":{"x":4.576943052224139,"y":-1.4092252597751103},"rotation":{"radians":-0.34365145353806514}},"curvature":-0.003497977398624211},{"time":1.0963573587634323,"velocity":4.698157212888728,"acceleration":0.013666510556798168,"pose":{"translation":{"x":4.668043326831998,"y":-1.4418426556093347},"rotation":{"radians":-0.3439817225261905}},"curvature":-0.00332967550406501},{"time":1.117094787271751,"velocity":4.698440621174358,"acceleration":0.013058547904707297,"pose":{"translation":{"x":4.759761170370888,"y":-1.474714625107476},"rotation":{"radians":-0.3442981969355225}},"curvature":-0.0031679762702993635},{"time":1.1379688111373605,"velocity":4.698713205614971,"acceleration":0.012492885094505708,"pose":{"translation":{"x":4.852078359958381,"y":-1.507833669800185},"rotation":{"radians":-0.3446012232475584}},"curvature":-0.00301247100853054},{"time":1.1589752207398896,"velocity":4.6989756362763835,"acceleration":0.011966572911404053,"pose":{"translation":{"x":4.944976442020495,"y":-1.5411921962205826},"rotation":{"radians":-0.34489112987363685}},"curvature":-0.0028627753687348653},{"time":1.1801097537194458,"velocity":4.699228544206232,"acceleration":0.011476912888864071,"pose":{"translation":{"x":5.03843674023487,"y":-1.5747825191734315},"rotation":{"radians":-0.3451682279313891}},"curvature":-0.002718527503976295},{"time":1.201368096868549,"velocity":4.699472524358716,"acceleration":0.011021435311205923,"pose":{"translation":{"x":5.13244036347394,"y":-1.608596865004313},"rotation":{"radians":-0.3454328119724706}},"curvature":-0.0025793863748584827},{"time":1.2227458880201547,"velocity":4.6997081383009895,"acceleration":0.010597879392235597,"pose":{"translation":{"x":5.226968213748115,"y":-1.6426273748688005},"rotation":{"radians":-0.3456851606643893}},"curvature":-0.002445030181772817},{"time":1.2442387179320789,"velocity":4.699935916720194,"acceleration":0.01020417540646546,"pose":{"translation":{"x":5.322000994148948,"y":-1.676866108001632},"rotation":{"radians":-0.34592553742904764}},"curvature":-0.0023151549137154226},{"time":1.2658421321675262,"velocity":4.700156361748431,"acceleration":0.009838428575118652,"pose":{"translation":{"x":5.41751921679232,"y":-1.7113050449858913},"rotation":{"radians":-0.34615419104042433}},"curvature":-0.002189473003451237},{"time":1.2875516329725323,"velocity":4.7003699491215025,"acceleration":0.009498904530761338,"pose":{"translation":{"x":5.513503210761603,"y":-1.7459360910221728},"rotation":{"radians":-0.3463713561836444}},"curvature":-0.002067712079705491},{"time":1.3093626811503483,"velocity":4.700577130185859,"acceleration":0.009184016203396412,"pose":{"translation":{"x":5.609933130050849,"y":-1.7807510791977645},"rotation":{"radians":-0.34657725397752587}},"curvature":-0.001949613807880811},{"time":1.3312706979323152,"velocity":4.700778333766969,"acceleration":0.008892311988809397,"pose":{"translation":{"x":5.70678896150795,"y":-1.8157417737558181},"rotation":{"radians":-0.3467720924625369}},"curvature":-0.0018349328115315432},{"time":1.353271066846537,"velocity":4.7009739679112235,"acceleration":0.008622465074958126,"pose":{"translation":{"x":5.804050532777829,"y":-1.8508998733645248},"rotation":{"radians":-0.34695606705594856}},"curvature":-0.0017234356674891186},{"time":1.3753591355835073,"velocity":4.701164421512481,"acceleration":0.00837326381556048,"pose":{"translation":{"x":5.901697520245603,"y":-1.8862170143862897},"rotation":{"radians":-0.3471293609758433}},"curvature":-0.0016148999681312745},{"time":1.3975302178590974,"velocity":4.701350065833451,"acceleration":0.008143603052542164,"pose":{"translation":{"x":5.999709456979765,"y":-1.9216847741469065},"rotation":{"radians":-0.34729214563550515}},"curvature":-0.0015091134448230758},{"time":1.419779595275509,"velocity":4.701531255931297,"acceleration":0.007932476300126834,"pose":{"translation":{"x":6.098065740675358,"y":-1.9572946742047326},"rotation":{"radians":-0.34744458100960596}},"curvature":-0.001405873147046175},{"time":1.442102519179547,"velocity":4.701708331996115,"acceleration":0.007738968711621765,"pose":{"translation":{"x":6.196745641597146,"y":-1.9930381836198596},"rotation":{"radians":-0.34758681597348584}},"curvature":-0.001304984672166229},{"time":1.4644942125187514,"velocity":4.701881620610267,"acceleration":0.007562250761078728,"pose":{"translation":{"x":6.295728310522794,"y":-2.028906722223296},"rotation":{"radians":-0.34771898861672773}},"curvature":-0.001206261441183089},{"time":1.4869498716956224,"velocity":4.702051435935968,"acceleration":0.007401572575570495,"pose":{"translation":{"x":6.394992786686045,"y":-2.064891663886134},"rotation":{"radians":-0.34784122653211924}},"curvature":-0.001109524016160343},{"time":1.5094646684197912,"velocity":4.702218080837946,"acceleration":0.007256258868360784,"pose":{"translation":{"x":6.494518005719888,"y":-2.1009843397887265},"rotation":{"radians":-0.34795364708101434}},"curvature":-0.0010145994553500933},{"time":1.5320337515578726,"velocity":4.702381847947618,"acceleration":0.007125704417549445,"pose":{"translation":{"x":6.594282807599738,"y":-2.1371760416898637},"rotation":{"radians":-0.348056357636004}},"curvature":-9.213207023082924E-4},{"time":1.5546522489821248,"velocity":4.702543020674632,"acceleration":0.007009370055230198,"pose":{"translation":{"x":6.694265944586614,"y":-2.173458025195944},"rotation":{"radians":-0.3481494558017369}},"curvature":-8.295260055553096E-4},{"time":1.5773152694167862,"velocity":4.702701874171428,"acceleration":0.006906779123471565,"pose":{"translation":{"x":6.794446089170307,"y":-2.2098215130301524},"rotation":{"radians":-0.34823302961464364}},"curvature":-7.390583655584746E-4},{"time":1.6000179042829614,"velocity":4.702858676255969,"acceleration":0.00681751436758972,"pose":{"translation":{"x":6.894801842012562,"y":-2.246257698301633},"rotation":{"radians":-0.3483071577222395}},"curvature":-6.497650060150667E-4},{"time":1.6227552295418346,"velocity":4.703013688297602,"acceleration":0.0067412152377363125,"pose":{"translation":{"x":6.995311739890247,"y":-2.282757747774662},"rotation":{"radians":-0.3483719095426188}},"curvature":-5.614968665936572E-4},{"time":1.6455223075360237,"velocity":4.7031671660706955,"acceleration":0.006677575573078309,"pose":{"translation":{"x":7.095954263638535,"y":-2.319312805137826},"rotation":{"radians":-0.3484273454046753}},"curvature":-4.7410811444260957E-4},{"time":1.6683141888298572,"velocity":4.703319360580488,"acceleration":0.006626341648883162,"pose":{"translation":{"x":7.196707846094072,"y":-2.355913994273193},"rotation":{"radians":-0.3484735166695209}},"curvature":-3.8745567191490635E-4},{"time":1.691125914047767,"velocity":4.703470518865382,"acceleration":0.006587310568012005,"pose":{"translation":{"x":7.2975508800381625,"y":-2.3925524225254877},"rotation":{"radians":-0.34851046583350903}},"curvature":-3.013987580703957E-4},{"time":1.7139525157111006,"velocity":4.703620884779751,"acceleration":0.006560328983487329,"pose":{"translation":{"x":7.398461726139931,"y":-2.429219183971269},"rotation":{"radians":-0.3485382266132044}},"curvature":-2.1579844161684353E-4},{"time":1.7367890200739886,"velocity":4.703770699761204,"acceleration":0.0065452921394948465,"pose":{"translation":{"x":7.499418720899509,"y":-2.465905362688101},"rotation":{"radians":-0.34855682401258936}},"curvature":-1.3051720303238805E-4},{"time":1.759630448957244,"velocity":4.7039202035861285,"acceleration":4.449473299374387E-4,"pose":{"translation":{"x":7.600400184591206,"y":-2.5026020360237293},"rotation":{"radians":-0.3485662743727219}},"curvature":-4.541850367600483E-5},{"time":1.7824721597108582,"velocity":4.7039303669443395,"acceleration":-0.00654966633545872,"pose":{"translation":{"x":7.701384429206682,"y":-2.5393002778652534},"rotation":{"radians":-0.3485665854040169}},"curvature":3.963364025820933E-5},{"time":1.8053098968726535,"velocity":4.703780787386073,"acceleration":-0.006569054232772703,"pose":{"translation":{"x":7.802349766398126,"y":-2.5759911619083042},"rotation":{"radians":-0.34855775620125407}},"curvature":1.2477508105031952E-4},{"time":1.828139068949373,"velocity":4.703630821316612,"acceleration":-0.006600426578437126,"pose":{"translation":{"x":7.9032745154214314,"y":-2.612665764926218},"rotation":{"radians":-0.34853977724137036}},"curvature":2.101419621190588E-4},{"time":1.850954701227469,"velocity":4.703480228410919,"acceleration":-0.00664390882496388,"pose":{"translation":{"x":8.004137011079372,"y":-2.649315170039208},"rotation":{"radians":-0.3485126303640174}},"curvature":2.958711421266519E-4},{"time":1.8737518250882366,"velocity":4.703328766398517,"acceleration":-0.006699675404599612,"pose":{"translation":{"x":8.10491561166477,"y":-2.6859304699835427},"rotation":{"radians":-0.34847628873483827}},"curvature":3.8210062261826935E-4},{"time":1.8965254798420614,"velocity":4.70317619030389,"acceleration":-0.006767950827795425,"pose":{"translation":{"x":8.205588706903683,"y":-2.7225027703807188},"rotation":{"radians":-0.34843071679132664}},"curvature":4.689699813158928E-4},{"time":1.919270714564398,"velocity":4.703022251673723,"acceleration":-0.0068490111044155035,"pose":{"translation":{"x":8.306134725898573,"y":-2.7590231930066356},"rotation":{"radians":-0.348375870171102}},"curvature":5.566208132271923E-4},{"time":1.9419825899332837,"velocity":4.702866697787119,"acceleration":-0.006943185502400931,"pose":{"translation":{"x":8.406532145071477,"y":-2.795482879060766},"rotation":{"radians":-0.3483116956223592}},"curvature":6.451971817814837E-4},{"time":1.9646561800679763,"velocity":4.702709270844808,"acceleration":-0.0070508586574038225,"pose":{"translation":{"x":8.50675949610719,"y":-2.8318729924353425},"rotation":{"radians":-0.3482381308961976}},"curvature":7.34846082278786E-4},{"time":1.9872865743693844,"velocity":4.702549707133228,"acceleration":-0.007172473054539557,"pose":{"translation":{"x":8.606795373896436,"y":-2.868184722984517},"rotation":{"radians":-0.34815510462047056}},"curvature":8.257179200227773E-4},{"time":2.009868879362072,"velocity":4.702387736159158,"acceleration":-0.007308531901937402,"pose":{"translation":{"x":8.706618444479046,"y":-2.904409289793546},"rotation":{"radians":-0.34806253615474037}},"curvature":9.179670056143282E-4},{"time":2.0323982205378757,"velocity":4.702223079750445,"acceleration":-0.007459602426343874,"pose":{"translation":{"x":8.806207452987135,"y":-2.940537944447957},"rotation":{"radians":-0.3479603354258481}},"curvature":0.0010117520700021036},{"time":2.0548697442008126,"velocity":4.702055451118006,"acceleration":-0.007626319616182957,"pose":{"translation":{"x":8.905541231588264,"y":-2.976561974302734},"rotation":{"radians":-0.3478484027435526}},"curvature":0.001107236802033505},{"time":2.0772786193144706,"velocity":4.70188455387415,"acceleration":-0.007809390451326412,"pose":{"translation":{"x":9.004598707428634,"y":-3.0124727057514793},"rotation":{"radians":-0.347726628595613}},"curvature":0.0012045904114051415},{"time":2.0996200393503432,"velocity":4.701710081001853,"acceleration":-0.008009598655879972,"pose":{"translation":{"x":9.10335891057625,"y":-3.0482615074955994},"rotation":{"radians":-0.34759489342162275}},"curvature":0.0013039882201029346},{"time":2.121889224138702,"velocity":4.701531713769304,"acceleration":-0.00822781002135825,"pose":{"translation":{"x":9.201800981964098,"y":-3.08391979381347},"rotation":{"radians":-0.34745306736482856}},"curvature":0.0014056122856276633},{"time":2.1440814217209203,"velocity":4.701349120583641,"acceleration":-0.008464978348691914,"pose":{"translation":{"x":9.299904181333321,"y":-3.119439027829614},"rotation":{"radians":-0.3473010100010797}},"curvature":0.0015096520595355926},{"time":2.1661919102041907,"velocity":4.701161955777351,"acceleration":-0.008722152069124894,"pose":{"translation":{"x":9.397647895176398,"y":-3.1548107247838875},"rotation":{"radians":-0.3471385700439829}},"curvature":0.0016163050850910667},{"time":2.188215999618132,"velocity":4.700969858320299,"acceleration":-0.009000481606593141,"pose":{"translation":{"x":9.495011644680316,"y":-3.190026455300628},"rotation":{"radians":-0.34696558502523067}},"curvature":0.001725777738118011},{"time":2.210149033773783,"velocity":4.700772450449804,"acceleration":-0.00930122755461837,"pose":{"translation":{"x":9.591975093669726,"y":-3.2250778486578557},"rotation":{"radians":-0.3467818809490062}},"curvature":0.001838286015466734},{"time":2.2319863921246013,"velocity":4.700569336210592,"acceleration":-0.009625769750443165,"pose":{"translation":{"x":9.68851805655017,"y":-3.2599565960564316},"rotation":{"radians":-0.3465872719192283}},"curvature":0.0019540563758784833},{"time":2.2537234916304514,"velocity":4.700360099895706,"acceleration":-0.009975617338042204,"pose":{"translation":{"x":9.78462050625119,"y":-3.294654453889242},"rotation":{"radians":-0.34638155973835105}},"curvature":0.002073326638432182},{"time":2.275355788623497,"velocity":4.70014430437876,"acceleration":-0.010352419921175708,"pose":{"translation":{"x":9.880262582169562,"y":-3.3291632470103636},"rotation":{"radians":-0.3461645334762574}},"curvature":0.002196346944214573},{"time":2.296878780677523,"velocity":4.699921489327057,"acceleration":-0.010757979926080005,"pose":{"translation":{"x":9.975424598112431,"y":-3.3634748720042476},"rotation":{"radians":-0.34593596900772544}},"curvature":0.0023233807873473296},{"time":2.318288008479419,"velocity":4.699691169284131,"acceleration":-0.011194266298869378,"pose":{"translation":{"x":10.07008705024051,"y":-3.3975813004548874},"rotation":{"radians":-0.3456956285167822}},"curvature":0.0024547061220649216},{"time":2.3395790577042384,"velocity":4.699452831609326,"acceleration":-0.011663429689199518,"pose":{"translation":{"x":10.164230625011236,"y":-3.4314745822149924},"rotation":{"radians":-0.34544325996614667}},"curvature":0.002590616553150375},{"time":2.360747560893146,"velocity":4.699205934260757,"acceleration":-0.0121678192788589,"pose":{"translation":{"x":10.257836207121956,"y":-3.46514684867517},"rotation":{"radians":-0.345178596529807}},"curvature":0.0027314226177157816},{"time":2.3817891993347553,"velocity":4.698949903406868,"acceleration":-0.012710001443912312,"pose":{"translation":{"x":10.350884887453121,"y":-3.498590316033094},"rotation":{"radians":-0.34490135598663285}},"curvature":0.002877453167072652},{"time":2.4026997049501913,"velocity":4.698684130850303,"acceleration":-0.013292780455117918,"pose":{"translation":{"x":10.44335797101142,"y":-3.5317972885626787},"rotation":{"radians":-0.3446112400727581}},"curvature":0.0030290568582754976},{"time":2.423474862181822,"velocity":4.6984079712463025,"acceleration":-0.013919221449873004,"pose":{"translation":{"x":10.53523698487298,"y":-3.5647601618832567},"rotation":{"radians":-0.3443079337902877}},"curvature":0.0031866037658480804},{"time":2.4441105098860723,"velocity":4.6981207390961455,"acceleration":-0.014592675939876076,"pose":{"translation":{"x":10.626503686126556,"y":-3.597471426228756},"rotation":{"radians":-0.3439911046697081}},"curvature":0.0033504871252351643},{"time":2.4646025432303795,"velocity":4.697821705494203,"acceleration":-0.015316810146859804,"pose":{"translation":{"x":10.717140069816656,"y":-3.629923669716865},"rotation":{"radians":-0.34366040198316133}},"curvature":0.0035211252206675107},{"time":2.4849469155949153,"velocity":4.697510094605138,"acceleration":-0.0160956365025476,"pose":{"translation":{"x":10.807128376886784,"y":-3.6621095816182105},"rotation":{"radians":-0.34331545590554663}},"curvature":0.0036989634313900604},{"time":2.505139640478907,"velocity":4.69718507984541,"acceleration":-0.016933548684983864,"pose":{"translation":{"x":10.896451102122565,"y":-3.694021955625546},"rotation":{"radians":-0.3429558766201623}},"curvature":0.0038844764516212213},{"time":2.5251767934121814,"velocity":4.6968457797407055,"acceleration":-0.017835360616437822,"pose":{"translation":{"x":10.985091002094928,"y":-3.7256536931229007},"rotation":{"radians":-0.34258125336537437}},"curvature":0.004078170701167172},{"time":2.545054513872177,"velocity":4.696491253428069,"acceleration":-0.018806349899489008,"pose":{"translation":{"x":11.073031103103302,"y":-3.756997806454782},"rotation":{"radians":-0.3421911534185059}},"curvature":0.004280586945357151},{"time":2.5647690072067633,"velocity":4.696120495768327,"acceleration":-0.019852306232666976,"pose":{"translation":{"x":11.16025470911876,"y":-3.7880474221953246},"rotation":{"radians":-0.3417851210128856}},"curvature":0.004492303144895317},{"time":2.5843165465631714,"velocity":4.695732432030929,"acceleration":-0.020979585412727316,"pose":{"translation":{"x":11.246745409727243,"y":-3.8187957844174782},"rotation":{"radians":-0.3413626761836514}},"curvature":0.004713937558374009},{"time":2.603693474823708,"velocity":4.695325912109451,"acceleration":-0.022195169616132677,"pose":{"translation":{"x":11.33248708807267,"y":-3.849236257962188},"rotation":{"radians":-0.34092331353761457}},"curvature":0.004946152122576614},{"time":2.62289620654834,"velocity":4.694899704221729,"acceleration":-0.02350673473946075,"pose":{"translation":{"x":11.417463928800158,"y":-3.8793623317075525},"rotation":{"radians":-0.3404665009421011}},"curvature":0.005189656138359233},{"time":2.6419212299249346,"velocity":4.694452488043804,"acceleration":-0.024922725682528783,"pose":{"translation":{"x":11.501660425999223,"y":-3.9091676218380123},"rotation":{"radians":-0.33999167812732334}},"curvature":0.005445210292855843},{"time":2.660765108727339,"velocity":4.6939828472216165,"acceleration":-0.026452440575377722,"pose":{"translation":{"x":11.585061391146851,"y":-3.9386458751135187},"rotation":{"radians":-0.33949825519644855}},"curvature":0.00571363105204153},{"time":2.679424484282301,"velocity":4.693489261198575,"acceleration":-0.028106125087259022,"pose":{"translation":{"x":11.667651961050796,"y":-3.967790972138708},"rotation":{"radians":-0.33898561103703356}},"curvature":0.005995795461361073},{"time":2.697896077445319,"velocity":4.6929700962905745,"acceleration":-0.02989507810188587,"pose":{"translation":{"x":11.749417605792681,"y":-3.9965969306320748},"rotation":{"radians":-0.3384530916271089}},"curvature":0.006292646396205132},{"time":2.716176690586381,"velocity":4.692423595932972,"acceleration":-0.031831770225640814,"pose":{"translation":{"x":11.830344136671187,"y":-4.025057908695155},"rotation":{"radians":-0.3379000082286223}},"curvature":0.006605198308581373},{"time":2.7342632095861976,"velocity":4.691847870015988,"acceleration":-0.033929976783624,"pose":{"translation":{"x":11.910417714145257,"y":-4.053168208081688},"rotation":{"radians":-0.33732563546046274}},"curvature":0.006934543521389735},{"time":2.752152605843496,"velocity":4.691240883216305,"acceleration":-0.03620492719374585,"pose":{"translation":{"x":11.989624855777217,"y":-4.0809222774667955},"rotation":{"radians":-0.33672920924269195}},"curvature":0.0072818591273748415},{"time":2.769841938294482,"velocity":4.690600442222811,"acceleration":-0.03867347285947374,"pose":{"translation":{"x":12.067952444176013,"y":-4.108314715716173},"rotation":{"radians":-0.3361099246030069}},"curvature":0.007648414556132973},{"time":2.7873283554448736,"velocity":4.689924181743736,"acceleration":-0.04135427601665364,"pose":{"translation":{"x":12.145387734940332,"y":-4.135340275155226},"rotation":{"radians":-0.3354669333358014}},"curvature":0.008035579879585916},{"time":2.80460909741585,"velocity":4.689209549170496,"acceleration":-0.04426802230643189,"pose":{"translation":{"x":12.221918364601805,"y":-4.161993864838287},"rotation":{"radians":-0.3347993415035072}},"curvature":0.008444834934168088},{"time":2.8216814980044727,"velocity":4.688453787760414,"acceleration":-0.047437660221822595,"pose":{"translation":{"x":12.297532358568203,"y":-4.1882705538177625},"rotation":{"radians":-0.3341062067691632}},"curvature":0.008877779346723532},{"time":2.838542986759918,"velocity":4.687653918185999,"acceleration":-0.05088867101258431,"pose":{"translation":{"x":12.372218139066542,"y":-4.214165574413309},"rotation":{"radians":-0.3333865355483635}},"curvature":0.009336143560852333},{"time":2.8551910910764002,"velocity":4.686806718282455,"acceleration":-0.054649373121779386,"pose":{"translation":{"x":12.445964533086354,"y":-4.239674325481033},"rotation":{"radians":-0.3326392799679521}},"curvature":0.009821800971294984},{"time":2.871623438304054,"velocity":4.685908700807544,"acceleration":-0.05875126578953377,"pose":{"translation":{"x":12.518760780322776,"y":-4.264792375682632},"rotation":{"radians":-0.33186333461791867}},"curvature":0.010336781286057863},{"time":2.8878377578790704,"velocity":4.684956089008596,"acceleration":-0.06322941709174404,"pose":{"translation":{"x":12.590596541119782,"y":-4.289515466754583},"rotation":{"radians":-0.3310575330820859}},"curvature":0.01088328524943052},{"time":2.903831883474275,"velocity":4.683944789770319,"acceleration":-0.06812290240327248,"pose":{"translation":{"x":12.661461904413306,"y":-4.313839516777328},"rotation":{"radians":-0.3302206442322277}},"curvature":0.011463700874031485},{"time":2.9196037551717033,"velocity":4.682870364093958,"acceleration":-0.07347530008608452,"pose":{"translation":{"x":12.731347395674508,"y":-4.337760623444428},"rotation":{"radians":-0.32935136826924993}},"curvature":0.012080621346673854},{"time":2.935151421658612,"velocity":4.681727994633194,"acceleration":-0.0793352521256913,"pose":{"translation":{"x":12.800243984852827,"y":-4.361275067331761},"rotation":{"radians":-0.32844833249412186}},"curvature":0.01273686479130493},{"time":2.950473042448533,"velocity":4.680512449984851,"acceleration":-0.08575709846545777,"pose":{"translation":{"x":12.86814309431925,"y":-4.3843793151666635},"rotation":{"radians":-0.3275100867901435}},"curvature":0.013435496092784157},{"time":2.965566890129039,"velocity":4.679218045403092,"acceleration":-0.09280159495653127,"pose":{"translation":{"x":12.935036606809449,"y":-4.40707002309715},"rotation":{"radians":-0.3265350987972188}},"curvature":0.01417985100789982},{"time":2.980431352638047,"velocity":4.677838599574084,"acceleration":-0.10053672612980348,"pose":{"translation":{"x":13.000916873366975,"y":-4.4293440399610375},"rotation":{"radians":-0.32552174875765966}},"curvature":0.014973562815084425},{"time":2.9950649355704617,"velocity":4.67636738705451,"acceleration":-0.10903862543674586,"pose":{"translation":{"x":13.06577672128643,"y":-4.451198410555165},"rotation":{"radians":-0.32446832401217235}},"curvature":0.015820591781829072},{"time":3.0094662645171266,"velocity":4.674797085941703,"acceleration":-0.11839261719725701,"pose":{"translation":{"x":13.129609462056594,"y":-4.472630378904537},"rotation":{"radians":-0.32337301312369243}},"curvature":0.016725257759070637},{"time":3.0236340874381407,"velocity":4.673119720306097,"acceleration":-0.12869439622974374,"pose":{"translation":{"x":13.192408899303656,"y":-4.493637391531511},"rotation":{"radians":-0.32223389960592}},"curvature":0.017692276244898913},{"time":3.037567277072596,"velocity":4.6713265968785365,"acceleration":-0.1400513630315125,"pose":{"translation":{"x":13.254169336734417,"y":-4.514217100724977},"rotation":{"radians":-0.32104895523272536}},"curvature":0.018726798295979317},{"time":3.0512648333868566,"velocity":4.669408235446523,"acceleration":-0.15944310911691464,"pose":{"translation":{"x":13.31488558607937,"y":-4.534367367809519},"rotation":{"radians":-0.3198160329040922}},"curvature":0.01983445470401043},{"time":3.077949955319033,"velocity":4.665153476638493,"acceleration":-0.1901269962237044,"pose":{"translation":{"x":13.433167355211653,"y":-4.573372085743699},"rotation":{"radians":-0.3171970255059308}},"curvature":0.022294391065331428},{"time":3.103683870896565,"velocity":4.660260764568663,"acceleration":-0.22775501837782047,"pose":{"translation":{"x":13.547223162860146,"y":-4.61063874087338},"rotation":{"radians":-0.31435702175215313}},"curvature":0.025128719746191984},{"time":3.1284634250193823,"velocity":4.654617096764026,"acceleration":-0.27407522987829763,"pose":{"translation":{"x":13.657030601927586,"y":-4.6461580825362425},"rotation":{"radians":-0.3112737242049294}},"curvature":0.02840547474637604},{"time":3.1522877493248997,"velocity":4.648087439603296,"acceleration":-0.33130354234391324,"pose":{"translation":{"x":13.762576156241451,"y":-4.679924518481943},"rotation":{"radians":-0.30792207344212147}},"curvature":0.03220657073056085},{"time":3.175158351948469,"velocity":4.640510327938568,"acceleration":-0.4022481120027285,"pose":{"translation":{"x":13.863855454735537,"y":-4.711936219485672},"rotation":{"radians":-0.3042738902734083}},"curvature":0.03663082788132656},{"time":3.197079210639608,"velocity":4.6316927039165785,"acceleration":-0.4904616550168139,"pose":{"translation":{"x":13.960873525631587,"y":-4.74219522396174},"rotation":{"radians":-0.3002974800220574}},"curvature":0.041797641580355344},{"time":3.2180568690647227,"velocity":4.621403966847019,"acceleration":-0.6004230195223179,"pose":{"translation":{"x":14.053645050620927,"y":-4.770707542577206},"rotation":{"radians":-0.29595720118383684}},"curvature":0.047851400266761906},{"time":3.238100535762091,"velocity":4.609369287966286,"acceleration":-0.7377446298927908,"pose":{"translation":{"x":14.14219461904598,"y":-4.797483262865374},"rotation":{"radians":-0.2912130051670268}},"curvature":0.05496674222623008},{"time":3.2572221846333433,"velocity":4.5952623941968245,"acceleration":-0.9093929586820941,"pose":{"translation":{"x":14.226556982082004,"y":-4.822536653839496},"rotation":{"radians":-0.28601996080331615}},"curvature":0.06335470093611098},{"time":3.2754366549525287,"velocity":4.578698283142433,"acceleration":-1.1238917562461512,"pose":{"translation":{"x":14.306777306918573,"y":-4.845886270606236},"rotation":{"radians":-0.2803277881560503}},"curvature":0.07326969592626409},{"time":3.292761747501338,"velocity":4.559226754450624,"acceleration":-1.3914476517067018,"pose":{"translation":{"x":14.382911430941283,"y":-4.867555058979352},"rotation":{"radians":-0.27408044263325626}},"curvature":0.08501714408146493},{"time":3.3092183113897087,"velocity":4.53632830727299,"acceleration":-1.7238886333663872,"pose":{"translation":{"x":14.455026115913277,"y":-4.887570460093219},"rotation":{"radians":-0.2672158150436699}},"curvature":0.098961134271922},{"time":3.324830313117469,"velocity":4.509414954950408,"acceleration":-2.134230780024759,"pose":{"translation":{"x":14.523199302156948,"y":-4.90596451501645},"rotation":{"radians":-0.2596656494177151}},"curvature":0.11553103187927309},{"time":3.3396248751158573,"velocity":4.477839945356463,"acceleration":-2.635582574494589,"pose":{"translation":{"x":14.587520362735464,"y":-4.922773969365473},"rotation":{"radians":-0.2513558325781181}},"curvature":0.1352249183989282},{"time":3.3536322649503463,"velocity":4.44092231279453,"acceleration":-3.582519105845448,"pose":{"translation":{"x":14.6480903576344,"y":-4.938040377918078},"rotation":{"radians":-0.24220728295076446}},"curvature":0.1586062266635573},{"time":3.3794347583579305,"velocity":4.348484387183408,"acceleration":-5.186635757116057,"pose":{"translation":{"x":14.758441350037616,"y":-4.964134950233838},"rotation":{"radians":-0.2210651007715408}},"curvature":0.21889213471806965},{"time":3.402523334073605,"velocity":4.228732354795608,"acceleration":-6.925099334184698,"pose":{"translation":{"x":14.855304156600658,"y":-4.984680828730376},"rotation":{"radians":-0.19561593010305592}},"curvature":0.3009105711885031},{"time":3.423220591137756,"velocity":4.085401793681209,"acceleration":-7.899727949539971,"pose":{"translation":{"x":14.939933912939077,"y":-5.000194252026091},"rotation":{"radians":-0.16547937300014395}},"curvature":0.40539956187435466},{"time":3.4418379315812926,"velocity":3.9383298690332986,"acceleration":-2.659333139312578,"pose":{"translation":{"x":15.01379714686142,"y":-5.01127844822588},"rotation":{"radians":-0.13098495469222307}},"curvature":0.5205219044461243},{"time":3.4733958669977514,"velocity":3.8544068055720233,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.136195922525479,"y":-5.023027104998107},"rotation":{"radians":-0.05862956694538753}},"curvature":0.5901506220921002},{"time":3.526652624736256,"velocity":0.0,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.238769634755512,"y":-5.02661962373552},"rotation":{"radians":-0.02161825323650912}},"curvature":-7.335559861346185E-16}] \ No newline at end of file diff --git a/PathWeaver/output/first.wpilib.json b/PathWeaver/output/first.wpilib.json new file mode 100644 index 0000000..832f6c6 --- /dev/null +++ b/PathWeaver/output/first.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":89.99999999999999,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.003960837658956053}},"curvature":0.0},{"time":0.046268155422340224,"velocity":4.16413398801062,"acceleration":20.122343156600795,"pose":{"translation":{"x":0.09633282642131955,"y":3.32220114244968E-4},"rotation":{"radians":0.0024357124642793598}},"curvature":-0.03131873164373634},{"time":0.06769694599968468,"velocity":4.595331465438878,"acceleration":-3.2657388277819996,"pose":{"translation":{"x":0.19018519082278293,"y":3.776271428801176E-4},"rotation":{"radians":-0.0019667245489377147}},"curvature":-0.06331350571724444},{"time":0.08727201667016053,"velocity":4.531404397093729,"acceleration":-4.52621852103831,"pose":{"translation":{"x":0.27951217351503466,"y":-9.815272475990487E-5},"rotation":{"radians":-0.009258944862072073}},"curvature":-0.10197795517826011},{"time":0.10580687754114987,"velocity":4.447511566534589,"acceleration":-6.795909334949117,"pose":{"translation":{"x":0.3627153187438831,"y":-0.0012758091071502224},"rotation":{"radians":-0.019770411994646908}},"curvature":-0.15440454953617785},{"time":0.12310628206035071,"velocity":4.329946381873491,"acceleration":-10.696663117552502,"pose":{"translation":{"x":0.4386110942223797,"y":-0.0032862219490998323},"rotation":{"radians":-0.034161978708522875}},"curvature":-0.2312920659185204},{"time":0.13909221520104129,"velocity":4.158950240447806,"acceleration":-21.683082829690306,"pose":{"translation":{"x":0.5063993506628987,"y":-0.006214336040275707},"rotation":{"radians":-0.05351578822542692}},"curvature":-0.3508825915332652},{"time":0.16770650689654784,"velocity":3.5385041835012174,"acceleration":-39.57935184498636,"pose":{"translation":{"x":0.6161803814685892,"y":-0.01495701846440868},"rotation":{"radians":-0.11475473627775676}},"curvature":-0.8818615338803364},{"time":0.1806292830179099,"velocity":3.0270290805798403,"acceleration":-50.24054622708399,"pose":{"translation":{"x":0.6582059080438363,"y":-0.02074667126770655},"rotation":{"radians":-0.16324504296814954}},"curvature":-1.483263576326746},{"time":0.19340362507468264,"velocity":2.3852391579559655,"acceleration":-52.31573221352215,"pose":{"translation":{"x":0.6921263390654158,"y":-0.027411943297960463},"rotation":{"radians":-0.23115572109507088}},"curvature":-2.60275578859484},{"time":0.19998960390162554,"velocity":2.0406888532816945,"acceleration":-48.82847096237592,"pose":{"translation":{"x":0.7062403338681601,"y":-0.03104680155187179},"rotation":{"radians":-0.2751182294430506}},"curvature":-3.4942543002833997},{"time":0.20689192397686854,"velocity":1.703659117914667,"acceleration":-42.09584948509217,"pose":{"translation":{"x":0.7185853332235053,"y":-0.03486622134698884},"rotation":{"radians":-0.3275998859857463}},"curvature":-4.7151693077318395},{"time":0.21425782386030356,"velocity":1.3935853050993279,"acceleration":-33.47946457803886,"pose":{"translation":{"x":0.7292718824627865,"y":-0.03885586129509029},"rotation":{"radians":-0.3901345476725628}},"curvature":-6.3600164187933075},{"time":0.2222279700596823,"velocity":1.126749077735436,"acceleration":-24.610040250706277,"pose":{"translation":{"x":0.7384206894000815,"y":-0.04300020416261273},"rotation":{"radians":-0.4641218974499291}},"curvature":-8.500247808028147},{"time":0.23090083280185988,"velocity":0.9133095765615955,"acceleration":-18.440304315324298,"pose":{"translation":{"x":0.7461616386925873,"y":-0.047282677949354555},"rotation":{"radians":-0.5503602998422257}},"curvature":-11.112446943670053},{"time":0.23553048468936674,"velocity":0.8279373868819537,"acceleration":-14.835842318158711,"pose":{"translation":{"x":0.7495470224107086,"y":-0.04947027657132941},"rotation":{"radians":-0.5979788357637982}},"curvature":-12.534374994362405},{"time":0.240324617264116,"velocity":0.7568123919506256,"acceleration":-11.58790247830829,"pose":{"translation":{"x":0.7526328062009993,"y":-0.05168577696717986},"rotation":{"radians":-0.6482969874931133}},"curvature":-13.963970672320935},{"time":0.24525422853929355,"velocity":0.6996885372378991,"acceleration":-8.647190267378619,"pose":{"translation":{"x":0.7554373677150925,"y":-0.05392686490162407},"rotation":{"radians":-0.7008848489380142}},"curvature":-15.322600732311253},{"time":0.25027551780064833,"velocity":0.6562684936074192,"acceleration":-5.918966766574035,"pose":{"translation":{"x":0.7579794733498865,"y":-0.05619118291872226},"rotation":{"radians":-0.755126924459009}},"curvature":-16.51351541146729},{"time":0.2553297602340695,"velocity":0.6263526006137912,"acceleration":-3.2583415516964456,"pose":{"translation":{"x":0.7602782474463078,"y":-0.05847633412558619},"rotation":{"radians":-0.8102222731392336}},"curvature":-17.43011200335713},{"time":0.2603448643600171,"velocity":0.6100116784541318,"acceleration":-0.45058533020046615,"pose":{"translation":{"x":0.7623531414880714,"y":-0.060779885976088806},"rotation":{"radians":-0.8652058620146231}},"curvature":-17.96874906670296},{"time":0.26523868990697563,"velocity":0.6078065924541121,"acceleration":2.838676367740909,"pose":{"translation":{"x":0.7642239033004439,"y":-0.0630993740545735},"rotation":{"radians":-0.9189918386699523}},"curvature":-18.043651975428034},{"time":0.26992376390329426,"velocity":0.6211060012885792,"acceleration":7.178619781995618,"pose":{"translation":{"x":0.7659105462490051,"y":-0.06543230585956386},"rotation":{"radians":-0.9704339975539432}},"curvature":-17.59996374149888},{"time":0.27431262644288845,"velocity":0.6526119767357696,"acceleration":13.64650641241847,"pose":{"translation":{"x":0.7674333184384092,"y":-0.06777616458747299},"rotation":{"radians":-1.0183938104212367}},"curvature":-16.62103997637882},{"time":0.27832284304939786,"velocity":0.7073374233716874,"acceleration":34.89941850575053,"pose":{"translation":{"x":0.7688126719111472,"y":-0.07012841291631304},"rotation":{"radians":-1.0618041901214113}},"curvature":-15.127955617832983},{"time":0.28478505274868793,"velocity":0.9328647841391318,"acceleration":90.0,"pose":{"translation":{"x":0.7712237657583411,"y":-0.0748478491990869},"rotation":{"radians":-1.1313409817992186}},"curvature":-10.823377339953991},{"time":0.2893249992112036,"velocity":1.3414599657655384,"acceleration":-12.80109227685977,"pose":{"translation":{"x":0.773310352440193,"y":-0.07957004954492501},"rotation":{"radians":-1.1733125860353835}},"curvature":-5.257202203461599},{"time":0.29717683547403406,"velocity":1.2409478852222515,"acceleration":-89.99999999999999,"pose":{"translation":{"x":0.7771815758973708,"y":-0.0889401721676204},"rotation":{"radians":-1.163264957282139}},"curvature":7.350827017612046},{"time":0.30216619678585166,"velocity":0.7919053671586695,"acceleration":-24.141277586135022,"pose":{"translation":{"x":0.7793017780441172,"y":-0.09354701774833644},"rotation":{"radians":-1.110693522282319}},"curvature":13.226515925286156},{"time":0.3094946108790295,"velocity":0.6149880882691183,"acceleration":-9.620813276102691,"pose":{"translation":{"x":0.7817666324891173,"y":-0.0980747161572421},"rotation":{"radians":-1.0298958907924822}},"curvature":17.801683098701417},{"time":0.31393884611835055,"velocity":0.572230930876535,"acceleration":-4.7603816460118065,"pose":{"translation":{"x":0.7831794119739595,"y":-0.1003026834761503},"rotation":{"radians":-0.9807744552003372}},"curvature":19.33188063472145},{"time":0.31874914858868675,"velocity":0.5493320552849812,"acceleration":-1.2913418998277,"pose":{"translation":{"x":0.7847392661164512,"y":-0.10250348233337975},"rotation":{"radians":-0.9272341292463634}},"curvature":20.249335257323747},{"time":0.32382953272793485,"velocity":0.54277154237875,"acceleration":1.5149005788220835,"pose":{"translation":{"x":0.786466009878046,"y":-0.10467472167606819},"rotation":{"radians":-0.8705182174463368}},"curvature":20.52645182383729},{"time":0.32907875805121695,"velocity":0.5507235968593576,"acceleration":4.073750284338515,"pose":{"translation":{"x":0.7883791693382243,"y":-0.1068140504723042},"rotation":{"radians":-0.8119439001422153}},"curvature":20.191405158997352},{"time":0.33439746652144214,"velocity":0.572390687002251,"acceleration":6.649928956638461,"pose":{"translation":{"x":0.790497950893253,"y":-0.10891916149483713},"rotation":{"radians":-0.752812046478218}},"curvature":19.32573777866687},{"time":0.3396952426045526,"velocity":0.6076205215831139,"acceleration":9.427672849021297,"pose":{"translation":{"x":0.7928412104549485,"y":-0.11098779510478617},"rotation":{"radians":-0.6943176112032055}},"curvature":18.049997349914722},{"time":0.34489622214377913,"velocity":0.6566536551733952,"acceleration":12.539605822155819,"pose":{"translation":{"x":0.7954274226494369,"y":-0.11301774303535},"rotation":{"radians":-0.6374776374807097}},"curvature":16.502258954130472},{"time":0.3499423658366993,"velocity":0.7199303080045716,"acceleration":16.074833656780893,"pose":{"translation":{"x":0.7982746500159175,"y":-0.11500685217551643},"rotation":{"radians":-0.5830880857863493}},"curvature":14.816508125515433},{"time":0.35479422130106963,"velocity":0.797923077521068,"acceleration":20.075938649280452,"pose":{"translation":{"x":0.8014005122054229,"y":-0.11695302835377154},"rotation":{"radians":-0.5317120677457426}},"curvature":13.106573265437618},{"time":0.3594296059890115,"velocity":0.8909827761320033,"acceleration":27.031632412604434,"pose":{"translation":{"x":0.8048221551795822,"y":-0.11885424012180959},"rotation":{"radians":-0.4836944624103153}},"curvature":11.458000905986898},{"time":0.3679857823054175,"velocity":1.122270189174522,"acceleration":37.07977099078728,"pose":{"translation":{"x":0.8126188140739359,"y":-0.12251398095230785},"rotation":{"radians":-0.39822174396935706}},"curvature":8.544856791374903},{"time":0.37572947667308,"velocity":1.4094046029500964,"acceleration":46.73052172232043,"pose":{"translation":{"x":0.8217911501568782,"y":-0.12597122132568533},"rotation":{"radians":-0.3264106097137632}},"curvature":6.258579822887073},{"time":0.38280764194463,"velocity":1.7401709589264391,"acceleration":53.99352163669088,"pose":{"translation":{"x":0.8324561365766101,"y":-0.12921235362935143},"rotation":{"radians":-0.2668026651980122}},"curvature":4.560060728416664},{"time":0.3893921871591751,"velocity":2.0956937434357488,"acceleration":57.338094099900296,"pose":{"translation":{"x":0.8447202105319951,"y":-0.13222513705815475},"rotation":{"radians":-0.2175490703860894}},"curvature":3.3322698227198093},{"time":0.3956474942524084,"velocity":2.4543611301713324,"acceleration":54.033889692800706,"pose":{"translation":{"x":0.8586782876329462,"y":-0.1349988186930875},"rotation":{"radians":-0.17684463619654262}},"curvature":2.454051863103874},{"time":0.40774888489087263,"velocity":3.1082463370595987,"acceleration":34.02353513583602,"pose":{"translation":{"x":0.891992591928696,"y":-0.13979403080824876},"rotation":{"radians":-0.11502534929420889}},"curvature":1.374547693200579},{"time":0.43313121668559906,"velocity":3.9718429947069205,"acceleration":13.958738672188188,"pose":{"translation":{"x":0.9816159890576985,"y":-0.14623559285438018},"rotation":{"radians":-0.04099530984338595}},"curvature":0.4935390755053831},{"time":0.46200601712802636,"velocity":4.374898788294347,"acceleration":7.038967811765633,"pose":{"translation":{"x":1.10209947920371,"y":-0.14852563235535807},"rotation":{"radians":-0.0026781264287293605}},"curvature":0.20140528611573624},{"time":0.47796725967000164,"velocity":4.4872494607830955,"acceleration":4.899081715135554,"pose":{"translation":{"x":1.172824497414727,"y":-0.14827883223553354},"rotation":{"radians":0.008812928858250024}},"curvature":0.1293270485402829},{"time":0.4948444972765215,"velocity":4.569932426943195,"acceleration":-36.8359231286635,"pose":{"translation":{"x":1.2492480968879178,"y":-0.14728160993700762},"rotation":{"radians":0.016639141473716066}},"curvature":0.07854587156191066},{"time":0.5139714587263028,"velocity":3.8653731452941438,"acceleration":-90.0,"pose":{"translation":{"x":1.3299040512445215,"y":-0.14572974989123033},"rotation":{"radians":0.02129758319027541}},"curvature":0.03825258696437647},{"time":0.5569200492295711,"velocity":0.0,"acceleration":-90.0,"pose":{"translation":{"x":1.4128894649391648,"y":-0.14387383885613683},"rotation":{"radians":0.022896761221383708}},"curvature":-8.845744847864971E-16}] \ No newline at end of file diff --git a/PathWeaver/output/second.wpilib.json b/PathWeaver/output/second.wpilib.json new file mode 100644 index 0000000..2ca20f2 --- /dev/null +++ b/PathWeaver/output/second.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":83.30480144572904,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.04790884983473335,"velocity":3.9910372229757103,"acceleration":-14.082930109046776,"pose":{"translation":{"x":0.0955998040326329,"y":-7.818981819843626E-4},"rotation":{"radians":-0.02400002589048359}},"curvature":-0.4782890871768382},{"time":0.0735435268163344,"velocity":3.6300258586758325,"acceleration":-6.339714077123961,"pose":{"translation":{"x":0.1931430210692008,"y":-0.005982297304585016},"rotation":{"radians":-0.08763923276392496}},"curvature":-0.7921245981643055},{"time":0.08756939337524731,"velocity":3.54110587500843,"acceleration":-2.88970669046291,"pose":{"translation":{"x":0.24313855951282481,"y":-0.011422652301742692},"rotation":{"radians":-0.1298709491308107}},"curvature":-0.8792465207074154},{"time":0.1022359667328668,"velocity":3.498723779850752,"acceleration":-0.2990496194645968,"pose":{"translation":{"x":0.2941603263116874,"y":-0.019292158638340728},"rotation":{"radians":-0.1765630848679798}},"curvature":-0.9223299793796668},{"time":0.11746527282944563,"velocity":3.4941694616578602,"acceleration":1.616141219945633,"pose":{"translation":{"x":0.3463341792013517,"y":-0.02993580104868767},"rotation":{"radians":-0.2259608640439421}},"curvature":-0.9270218546282027},{"time":0.1331945962954518,"velocity":3.519590269673131,"acceleration":2.9732015786000194,"pose":{"translation":{"x":0.39976171731079674,"y":-0.043655031987381764},"rotation":{"radians":-0.2765009463314426}},"curvature":-0.9009885089235691},{"time":0.14937955158479116,"velocity":3.5677114042889655,"acceleration":3.8591438601814994,"pose":{"translation":{"x":0.4545212980357279,"y":-0.06070936209778108},"rotation":{"radians":-0.3268739360705536}},"curvature":-0.8527236833894503},{"time":0.1659946079486878,"velocity":3.631831297042267,"acceleration":4.351389610536463,"pose":{"translation":{"x":0.5106690539118872,"y":-0.08131795068047361},"rotation":{"radians":-0.37605466675551286}},"curvature":-0.7903998567626989},{"time":0.1830313246768096,"velocity":3.705964689210669,"acceleration":4.526585993892844,"pose":{"translation":{"x":0.5682399094883642,"y":-0.10566119616174736},"rotation":{"radians":-0.42330050164419036}},"curvature":-0.7210311439433731},{"time":0.20049497258244098,"velocity":3.785015393222576,"acceleration":4.461130286881011,"pose":{"translation":{"x":0.6272485982009058,"y":-0.1338823265620606},"rotation":{"radians":-0.4681246341647698}},"curvature":-0.6500548167996696},{"time":0.21840036958514114,"velocity":3.86489370208995,"acceleration":4.2273393653295255,"pose":{"translation":{"x":0.6876906792452273,"y":-0.1660889899645117},"rotation":{"radians":-0.5102545052917534}},"curvature":-0.581284604552246},{"time":0.23676766333502675,"velocity":3.9425384859934125,"acceleration":3.8887650393817457,"pose":{"translation":{"x":0.7495435544503221,"y":-0.20235484498330963},"rotation":{"radians":-0.5495850357688999}},"curvature":-0.517108183026198},{"time":0.2556185663693227,"velocity":4.015845218673958,"acceleration":3.496914226741421,"pose":{"translation":{"x":0.8127674851517729,"y":-0.24272115123224366},"rotation":{"radians":-0.5861338508069992}},"curvature":-0.4587948771423823},{"time":0.27497330419242827,"velocity":4.083527076722426,"acceleration":3.0901778566969678,"pose":{"translation":{"x":0.8773066090650617,"y":-0.2871983597931539},"rotation":{"radians":-0.620002636668836}},"curvature":-0.40681484132239626},{"time":0.2948483425858446,"velocity":4.144944480266763,"acceleration":2.6946953568570557,"pose":{"translation":{"x":0.9430899571588806,"y":-0.335767703684401},"rotation":{"radians":-0.651346224317205}},"curvature":-0.3611150726198112},{"time":0.31525483809493615,"velocity":4.199933768964836,"acceleration":2.3263993327215156,"pose":{"translation":{"x":1.0100324705284414,"y":-0.3883827883293365},"rotation":{"radians":-0.6803493072638312}},"curvature":-0.32133242808003293},{"time":0.3361976962834516,"velocity":4.24865522027988,"acceleration":1.9934769566249384,"pose":{"translation":{"x":1.0780360172687873,"y":-0.444971182024773},"rotation":{"radians":-0.7072098100536789}},"curvature":-0.2869447389265671},{"time":0.3576751065476877,"velocity":4.291469942729615,"acceleration":1.6987088903168355,"pose":{"translation":{"x":1.1469904093481023,"y":-0.5054360064094543},"rotation":{"radians":-0.7321276037045539}},"curvature":-0.2573705886425743},{"time":0.3796784312106474,"velocity":4.328847185951112,"acceleration":1.4414073084234558,"pose":{"translation":{"x":1.2167744194810217,"y":-0.5696575269325248},"rotation":{"radians":-0.7552972804336517}},"curvature":-0.2320306450664142},{"time":0.40219234646656876,"velocity":4.361298907942223,"acceleration":1.2188736309966142,"pose":{"translation":{"x":1.2872567980019438,"y":-0.637494743322001},"rotation":{"radians":-0.7769038755888381}},"curvature":-0.21038221803621895},{"time":0.42519515508136246,"velocity":4.389336424801657,"acceleration":1.0274125470317639,"pose":{"translation":{"x":1.3582972897383383,"y":-0.7087869800532404},"rotation":{"radians":-0.7971206498347542}},"curvature":-0.1919362465515646},{"time":0.44865921124945285,"velocity":4.413443690513011,"acceleration":0.8629881993361621,"pose":{"translation":{"x":1.4297476508840585,"y":-0.783355476817412},"rotation":{"radians":-0.8161082612677013}},"curvature":-0.17626338841224423},{"time":0.47255141495936853,"velocity":4.434062380370804,"acceleration":0.7216165154038006,"pose":{"translation":{"x":1.501452665872651,"y":-0.8610049789899666},"rotation":{"radians":-0.8340148406737597}},"curvature":-0.16299377152341016},{"time":0.49683374637011796,"velocity":4.451584911749309,"acceleration":0.5995757584813853,"pose":{"translation":{"x":1.573251164250666,"y":-0.9415253280991068},"rotation":{"radians":-0.850976627672666}},"curvature":-0.15181337792488883},{"time":0.5214638204597207,"velocity":4.466352507103036,"acceleration":0.49349890033902816,"pose":{"translation":{"x":1.6449770375509676,"y":-1.0246930522942574},"rotation":{"radians":-0.8671189339716496}},"curvature":-0.14245891555850157},{"time":0.546395449215562,"velocity":4.478656238477704,"acceleration":0.4003933639934723,"pose":{"translation":{"x":1.716460256166045,"y":-1.110272956814534},"rotation":{"radians":-0.8825572786467797}},"curvature":-0.13471228541257965},{"time":0.5715792035371225,"velocity":4.488739646588499,"acceleration":0.3176188452348022,"pose":{"translation":{"x":1.7875278862213229,"y":-1.1980197144572158},"rotation":{"radians":-0.8973985959790374}},"curvature":-0.1283952704405118},{"time":0.5969629703694583,"velocity":4.496802009297495,"acceleration":0.24284284370781173,"pose":{"translation":{"x":1.8580051064484708,"y":-1.287679456046213},"rotation":{"radians":-0.9117424548192813}},"curvature":-0.12336477387973296},{"time":0.6224925028199472,"velocity":4.5030016735563025,"acceleration":0.17398577808019555,"pose":{"translation":{"x":1.9277162250587152,"y":-1.37899136090054},"rotation":{"radians":-0.9256822544966383}},"curvature":-0.11950875631742593},{"time":0.6481119624617552,"velocity":4.507459095176077,"acceleration":0.1091623894281527,"pose":{"translation":{"x":1.9964856966161473,"y":-1.471689247302781},"rotation":{"radians":-0.9393063795255954}},"curvature":-0.11674291971605638},{"time":0.6737644539342392,"velocity":4.510259382439998,"acceleration":0.046622841379177625,"pose":{"translation":{"x":2.064139138911037,"y":-1.5655031629675649},"rotation":{"radians":-0.9526993064329413}},"curvature":-0.11500813343412736},{"time":0.6993925524796755,"velocity":4.511454237213332,"acceleration":-0.015305062299735755,"pose":{"translation":{"x":2.13050434983314,"y":-1.6601609755100326},"rotation":{"radians":-0.9659426627584111}},"curvature":-0.11426857285340941},{"time":0.7249388253189625,"velocity":4.511063249916001,"acceleration":-0.0782722021092782,"pose":{"translation":{"x":2.195412324245011,"y":-1.7553899629143066},"rotation":{"radians":-0.9791162419189855}},"curvature":-0.11451053302403358},{"time":0.7503463478347091,"velocity":4.509074547178552,"acceleration":-0.14396308686186837,"pose":{"translation":{"x":2.258698270855312,"y":-1.8509184040019648},"rotation":{"radians":-0.9922989789369833}},"curvature":-0.11574187942861028},{"time":0.7755592154345571,"velocity":4.505444824930239,"acceleration":-0.21414936175679436,"pose":{"translation":{"x":2.3202026290921243,"y":-1.9464771689005071},"rotation":{"radians":-1.0055698914183968}},"curvature":-0.11799209957890208},{"time":0.8005230517172867,"velocity":4.500098835323291,"acceleration":-0.2907411270709412,"pose":{"translation":{"x":2.379772085976258,"y":-2.0418013095118255},"rotation":{"radians":-1.0190089877214836}},"curvature":-0.12131291769220312},{"time":0.8251855131419745,"velocity":4.492928443492334,"acceleration":-0.37583391488982765,"pose":{"translation":{"x":2.437260592994562,"y":-2.1366316499806772},"rotation":{"radians":-1.0326981397792783}},"curvature":-0.12577942492325916},{"time":0.8494967897596863,"velocity":4.483791441225129,"acceleration":-0.47174679896538096,"pose":{"translation":{"x":2.4925303829732366,"y":-2.2307163771631506},"rotation":{"radians":-1.04672191103805}},"curvature":-0.13149165292811377},{"time":0.873410100633482,"velocity":4.472510413367752,"acceleration":-0.5810433434957571,"pose":{"translation":{"x":2.5454529869511404,"y":-2.3238126310951372},"rotation":{"radians":-1.0611683196138983}},"curvature":-0.13857646956234318},{"time":0.8968821812334089,"velocity":4.458872117177169,"acceleration":-0.7065213464806441,"pose":{"translation":{"x":2.595910251053105,"y":-2.4156880954608067},"rotation":{"radians":-1.0761295018153896}},"curvature":-0.14718958856781933},{"time":0.9198737581930426,"velocity":4.442628077265935,"acceleration":-0.8511488894308598,"pose":{"translation":{"x":2.6437953533632417,"y":-2.506122588061068},"rotation":{"radians":-1.0917022199076452}},"curvature":-0.1575173401009345},{"time":0.9423500041450612,"velocity":4.4234974454852996,"acceleration":-1.0179123537522614,"pose":{"translation":{"x":2.689013820798255,"y":-2.5949096512820446},"rotation":{"radians":-1.1079881281053245}},"curvature":-0.16977761708160108},{"time":0.9642809616502223,"velocity":4.40117365291118,"acceleration":-1.209526412330288,"pose":{"translation":{"x":2.731484545980749,"y":-2.681858142563545},"rotation":{"radians":-1.1250936693610196}},"curvature":-0.1842190537555596},{"time":0.9856419201796252,"velocity":4.3753370093771755,"acceleration":-1.4279371353934838,"pose":{"translation":{"x":2.7711408041125445,"y":-2.766793824867534},"rotation":{"radians":-1.1431294190935237}},"curvature":-0.20111695570260074},{"time":1.006413723361488,"velocity":4.345676180244709,"acceleration":-1.673529946771687,"pose":{"translation":{"x":2.80793126984798,"y":-2.8495609571465934},"rotation":{"radians":-1.1622086168970278}},"curvature":-0.2207637239520797},{"time":1.0265829749636037,"velocity":4.3119223336845955,"acceleration":-1.943940614410558,"pose":{"translation":{"x":2.8418210341672334,"y":-2.9300238848124067},"rotation":{"radians":-1.182444530462987}},"curvature":-0.2434504427205616},{"time":1.0461421012491954,"velocity":4.273900553715649,"acceleration":-2.2323714459746737,"pose":{"translation":{"x":2.872792621249619,"y":-3.008068630204219},"rotation":{"radians":-1.2039461768868822}},"curvature":-0.26943490947451204},{"time":1.0650892147890907,"velocity":4.2316035584655465,"acceleration":-2.5253535019218467,"pose":{"translation":{"x":2.900847005346914,"y":-3.083604483057311},"rotation":{"radians":-1.2268117905549052}},"curvature":-0.29888976094312886},{"time":1.0834277118501454,"velocity":4.185292370692428,"acceleration":-2.7999870674947758,"pose":{"translation":{"x":2.926004627656654,"y":-3.1565655909714607},"rotation":{"radians":-1.2511192908358104}},"curvature":-0.3318228031885032},{"time":1.1011655250652148,"velocity":4.135626723084596,"acceleration":-3.02084285427441,"pose":{"translation":{"x":2.948306413195452,"y":-3.226912549879435},"rotation":{"radians":-1.2769129039489122}},"curvature":-0.36796093311622313},{"time":1.1183139507287514,"velocity":4.083824023956845,"acceleration":-3.136885408452861,"pose":{"translation":{"x":2.967814787672307,"y":-3.294633994515438},"rotation":{"radians":-1.3041850999284632}},"curvature":-0.40659058043694596},{"time":1.1348859846864212,"velocity":4.031839452446645,"acceleration":-2.9224199449007644,"pose":{"translation":{"x":2.9846146943619103,"y":-3.3597481888835823},"rotation":{"radians":-1.3328532272449005}},"curvature":-0.4463537436368519},{"time":1.1663342623364754,"velocity":3.93993437860935,"acceleration":-1.4771802634085083,"pose":{"translation":{"x":3.0105475665464985,"y":-3.482385571993179},"rotation":{"radians":-1.393494650947527}},"curvature":-0.5192195837491828},{"time":1.1955472301355397,"velocity":3.896781559140984,"acceleration":2.326581524371592,"pose":{"translation":{"x":3.0272735684464873,"y":-3.5956238344413407},"rotation":{"radians":-1.4555026751903997}},"curvature":-0.5546185706925614},{"time":1.2224327994299549,"velocity":3.9593330279335825,"acceleration":7.942783881416398,"pose":{"translation":{"x":3.036386599702155,"y":-3.70083796976191},"rotation":{"radians":-1.512416338130062}},"curvature":-0.5035579458806192},{"time":1.2469009828226998,"velocity":4.153678520593017,"acceleration":-89.99999999999999,"pose":{"translation":{"x":3.0399384608427287,"y":-3.8000297247805115},"rotation":{"radians":-1.5545508047561158}},"curvature":-0.31938683773167886},{"time":1.2930529663848445,"velocity":0.0,"acceleration":-89.99999999999999,"pose":{"translation":{"x":3.040471393232295,"y":-3.8958784946055616},"rotation":{"radians":-1.5707963267948972}},"curvature":-1.5296436709931294E-15}] \ No newline at end of file diff --git a/src/Autonomous/Actions/PathFinder.cpp b/src/Autonomous/Actions/PathFinder.cpp index 4865b02..83940c6 100644 --- a/src/Autonomous/Actions/PathFinder.cpp +++ b/src/Autonomous/Actions/PathFinder.cpp @@ -15,6 +15,7 @@ CORE::COREAutonAction::actionStatus PathFinderAction::Action() { if (m_autonomousCommand != nullptr) { m_autonomousCommand->Schedule(); } + cout << "running path finder action" << endl; return COREAutonAction::actionStatus::END; } diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index e512561..db473a8 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -50,10 +50,10 @@ void DriveSubsystem::Periodic() { void DriveSubsystem::teleop() { // Code for teleop. Sets motor speed based on the values for the joystick, runs compressor, // toggles gears - double mag = -m_controller.GetY(frc::GenericHID::kLeftHand); + double mag = -driverJoystick->GetAxis(CORE::COREJoystick::LEFT_STICK_Y); SmartDashboard::PutNumber("mag", mag); std::cout << mag << endl; - double rot = m_controller.GetX(frc::GenericHID::kRightHand); + double rot = driverJoystick->GetAxis(CORE::COREJoystick::RIGHT_STICK_X); SmartDashboard::PutNumber("rot", rot); VelocityPair speeds = COREEtherDrive::Calculate(mag, rot, .1); diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 699d886..016a0a0 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -58,7 +58,6 @@ class DriveSubsystem : public CORESubsystem, public frc2::SubsystemBase { COREConstant m_driveTurnkP; COREVector path; private: - XboxController m_controller{0}; double m_wheelCircumference = 0.4787787204; WPI_TalonSRX m_leftMaster, m_rightMaster, m_leftSlave, m_rightSlave; SpeedControllerGroup m_leftMotors{m_leftSlave, m_leftMaster}; diff --git a/src/Robot.cpp b/src/Robot.cpp index 50baa8f..b286036 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -11,8 +11,14 @@ void Robot::robotInit() { frc::filesystem::GetDeployDirectory(deployDirectory); wpi::sys::path::append(deployDirectory, "paths"); wpi::sys::path::append(deployDirectory, "example.wpilib.json"); - frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); + wpi::SmallString<64> deployDirectory1; + frc::filesystem::GetDeployDirectory(deployDirectory1); + wpi::sys::path::append(deployDirectory1, "paths"); + wpi::sys::path::append(deployDirectory1, "first.wpilib.json"); + frc::Trajectory trajectory1 = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory1); + frc::Trajectory trajectory2 = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); + frc::Trajectory trajectory = trajectory2; } void Robot::RobotPeriodic() { diff --git a/src/main/deploy/paths/example.wpilib.json b/src/main/deploy/paths/example.wpilib.json index 667ae69..42fb442 100644 --- a/src/main/deploy/paths/example.wpilib.json +++ b/src/main/deploy/paths/example.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":82.04386788688518,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.003960837658956053}},"curvature":0.0},{"time":0.04861705599062372,"velocity":3.988731318744032,"acceleration":-14.986162120671922,"pose":{"translation":{"x":0.09695929073566933,"y":-4.16880132877712E-4},"rotation":{"radians":-0.02033040485690381}},"curvature":-0.48011339202264347},{"time":0.07447317296123704,"velocity":3.6012473580113644,"acceleration":-7.700425189411032,"pose":{"translation":{"x":0.19495981624216482,"y":-0.0053316734503858374},"rotation":{"radians":-0.08545062977466551}},"curvature":-0.8198502777066392},{"time":0.08855487040799276,"velocity":3.4928123002827016,"acceleration":-4.2851292698411925,"pose":{"translation":{"x":0.24462277107317196,"y":-0.010662122724874212},"rotation":{"radians":-0.12929952046633988}},"curvature":-0.9284223735685312},{"time":0.10323765312894014,"velocity":3.4298946782824515,"acceleration":-1.5645670869950543,"pose":{"translation":{"x":0.2948471423927566,"y":-0.01843507745101975},"rotation":{"radians":-0.17835307356051847}},"curvature":-0.9945667573290181},{"time":0.1184344076772456,"velocity":3.4061183362870304,"acceleration":0.6065764305371881,"pose":{"translation":{"x":0.3457074680596518,"y":-0.028983138147212293},"rotation":{"radians":-0.23085524023122095}},"curvature":-1.0201986826587648},{"time":0.13406821199091645,"velocity":3.415601433503334,"acceleration":2.304621027593365,"pose":{"translation":{"x":0.39726669237201556,"y":-0.04259091984913327},"rotation":{"radians":-0.28513455840977064}},"curvature":-1.0099327126714004},{"time":0.15007672441038006,"velocity":3.452494987845719,"acceleration":3.5731137837875306,"pose":{"translation":{"x":0.44957662374616525,"y":-0.0594968990491558},"rotation":{"radians":-0.3396883031848305}},"curvature":-0.9705299239146334},{"time":0.16641505004784743,"velocity":3.510873684384963,"acceleration":4.446660630426792,"pose":{"translation":{"x":0.5026783923953116,"y":-0.07989526063574501},"rotation":{"radians":-0.3932492699961454}},"curvature":-0.9098726567829792},{"time":0.18305641927624738,"velocity":3.584872205769285,"acceleration":4.965060662537582,"pose":{"translation":{"x":0.5566029080082937,"y":-0.10393774483285809},"rotation":{"radians":-0.44482289890825155}},"curvature":-0.835825077432052},{"time":0.1999906598326739,"velocity":3.668951737405947,"acceleration":5.178872118939808,"pose":{"translation":{"x":0.6113713174283122,"y":-0.13173549413934466},"rotation":{"radians":-0.4936918141390549}},"curvature":-0.7553148018316558},{"time":0.21722099414443607,"velocity":3.758185435373144,"acceleration":5.148057472944306,"pose":{"translation":{"x":0.6669954623316645,"y":-0.16336090026834685},"rotation":{"radians":-0.5393932214102857}},"curvature":-0.6738095874713677},{"time":0.234759951539094,"velocity":3.8484769960563643,"acceleration":4.93643001229542,"pose":{"translation":{"x":0.7234783369064792,"y":-0.1988494510866995},"rotation":{"radians":-0.5816790884865704}},"curvature":-0.5951852920387548},{"time":0.25262515031495936,"velocity":3.9366672994691694,"acceleration":4.604994697195861,"pose":{"translation":{"x":0.7808145455314498,"y":-0.23820157755433044},"rotation":{"radians":-0.6204693772224047}},"curvature":-0.5218724701926193},{"time":0.2708354955656566,"velocity":4.020525842782736,"acceleration":4.206588872506236,"pose":{"translation":{"x":0.838990760454569,"y":-0.28138450066366055},"rotation":{"radians":-0.655806281947034}},"curvature":-0.45514380303097307},{"time":0.289408087212753,"velocity":4.098653100139014,"acceleration":3.7829567821827563,"pose":{"translation":{"x":0.8979861794718639,"y":-0.3283340783790041},"rotation":{"radians":-0.6878142616676054}},"curvature":-0.39543267641623114},{"time":0.3083559240142426,"velocity":4.170331947874901,"acceleration":3.3642257650536935,"pose":{"translation":{"x":0.9577729836061292,"y":-0.37895665257596894},"rotation":{"radians":-0.7166678668322568}},"curvature":-0.34261784050540955},{"time":0.3276863537879395,"velocity":4.235363877769133,"acceleration":2.9700899332606645,"pose":{"translation":{"x":1.0183167947856622,"y":-0.4331308959808565},"rotation":{"radians":-0.742567453488204}},"curvature":-0.29624731732770176},{"time":0.3474001523523855,"velocity":4.293915632431723,"acceleration":2.6118590831086155,"pose":{"translation":{"x":1.079577133522997,"y":-0.4907096591100624},"rotation":{"radians":-0.7657218390020194}},"curvature":-0.25569904207677707},{"time":0.3674910940504928,"velocity":4.34639034099413,"acceleration":2.294695858761864,"pose":{"translation":{"x":1.1415078765936388,"y":-0.551521817209476},"rotation":{"radians":-0.7863365551744559}},"curvature":-0.22028752701688126},{"time":0.38794588486170145,"velocity":4.393327864760451,"acceleration":2.0196292959925226,"pose":{"translation":{"x":1.2040577147147982,"y":-0.6153741171938814},"rotation":{"radians":-0.8046063412012733}},"curvature":-0.1893294098683867},{"time":0.4087443497529076,"velocity":4.435333053766403,"acceleration":1.7851661520501068,"pose":{"translation":{"x":1.2671706102241251,"y":-0.6820530245863567},"rotation":{"radians":-0.8207106925835705}},"curvature":-0.1621800372499478},{"time":0.4298597896122911,"velocity":4.473027622289024,"acceleration":1.5884760015640393,"pose":{"translation":{"x":1.3307862547584441,"y":-0.7513265704576756},"rotation":{"radians":-0.834811517419783}},"curvature":-0.13825086553063487},{"time":0.4512594449630652,"velocity":4.50702046125547,"acceleration":1.42620605398305,"pose":{"translation":{"x":1.3948405269324877,"y":-0.8229461983657058},"rotation":{"radians":-0.8470521815066807}},"curvature":-0.11701485001282146},{"time":0.4729050217177735,"velocity":4.53789151386499,"acceleration":1.2950098135221093,"pose":{"translation":{"x":1.459265950017631,"y":-0.8966486112948104},"rotation":{"radians":-0.8575574194275142}},"curvature":-0.09800474543703949},{"time":0.494753248187605,"velocity":4.566185181551475,"acceleration":1.1918730332462482,"pose":{"translation":{"x":1.5239921496206263,"y":-0.972157618595248},"rotation":{"radians":-0.8664337427984783}},"curvature":-0.0808075223195219},{"time":0.5167564428436503,"velocity":4.592410195907283,"acceleration":1.114307380106349,"pose":{"translation":{"x":1.5889463113623374,"y":-1.0491859829225723},"rotation":{"radians":-0.8737700918600187}},"curvature":-0.06505688074422102},{"time":0.5388630796355971,"velocity":4.61704378443388,"acceleration":1.0604664491834883,"pose":{"translation":{"x":1.654053638556473,"y":-1.127437267177034},"rotation":{"radians":-0.8796385592970702}},"curvature":-0.05042501444162249},{"time":0.5610183427137745,"velocity":4.640538697601121,"acceleration":1.0292249031308387,"pose":{"translation":{"x":1.7192378098883225,"y":-1.206607681442978},"rotation":{"radians":-0.8840950728279422}},"curvature":-0.036614235957898436},{"time":0.5831646657820858,"velocity":4.663332244815808,"acceleration":1.0202513060755258,"pose":{"translation":{"x":1.784421437093489,"y":-1.2863879299282457},"rotation":{"radians":-0.887179962196901}},"curvature":-0.02334872853924968},{"time":0.6052422535180257,"velocity":4.685856932538398,"acceleration":0.6190297289205114,"pose":{"translation":{"x":1.8495265226366242,"y":-1.3664650579035758},"rotation":{"radians":-0.8889183619964093}},"curvature":-0.010366474520298714},{"time":0.6272108558372299,"velocity":4.699456150476817,"acceleration":-1.0504967716010856,"pose":{"translation":{"x":1.9144749173901634,"y":-1.4465242986420022},"rotation":{"radians":-0.8893204182932911}},"curvature":0.002588723896986337},{"time":0.6491148904032975,"velocity":4.676446032880125,"acceleration":-1.081508394360102,"pose":{"translation":{"x":1.9791887783130577,"y":-1.5262509203582562},"rotation":{"radians":-0.8883812774243289}},"curvature":0.015775299121229783},{"time":0.6709789593575614,"velocity":4.65279985877122,"acceleration":-1.1371104719694012,"pose":{"translation":{"x":2.043591026129511,"y":-1.605332073148167},"rotation":{"radians":-0.8860808419436056}},"curvature":0.02946226836672896},{"time":0.6927449034691424,"velocity":4.628049575789641,"acceleration":-1.219194441272511,"pose":{"translation":{"x":2.107605803007713,"y":-1.6834586359280597},"rotation":{"radians":-0.8823832835043174}},"curvature":0.04393813260960995},{"time":0.714357285036688,"velocity":4.601699880319829,"acceleration":-1.3306248642662981,"pose":{"translation":{"x":2.1711589302385734,"y":-1.7603270633741557},"rotation":{"radians":-0.8772363072499006}},"curvature":0.05952059236403715},{"time":0.7357639577379572,"velocity":4.573215629362309,"acceleration":-1.475253889594832,"pose":{"translation":{"x":2.2341783659144543,"y":-1.8356412328619742},"rotation":{"radians":-0.8705701690175973}},"curvature":0.07656734033760348},{"time":0.7569166610487092,"velocity":4.542010021527677,"acceleration":-1.6579143384256556,"pose":{"translation":{"x":2.2965946626079106,"y":-1.9091142914057355},"rotation":{"radians":-0.8622964577260398}},"curvature":0.09548814430263139},{"time":0.7777716383807286,"velocity":4.50743425558138,"acceleration":-1.8843466586654065,"pose":{"translation":{"x":2.3583414250504164,"y":-1.9804705025977558},"rotation":{"radians":-0.8523066739840298}},"curvature":0.11675831756366055},{"time":0.7982902755620526,"velocity":4.468770030168384,"acceleration":-2.1609911912303006,"pose":{"translation":{"x":2.4193557678111066,"y":-2.049447093547844},"rotation":{"radians":-0.8404706668248598}},"curvature":0.14093343621696822},{"time":0.818439752146611,"velocity":4.425227188761252,"acceleration":-2.494544357783928,"pose":{"translation":{"x":2.4795787729755046,"y":-2.115796101822716},"rotation":{"radians":-0.8266350401034745}},"curvature":0.16866471487091822},{"time":0.8381936914844454,"velocity":4.3759501108420515,"acceleration":-2.8911376736798027,"pose":{"translation":{"x":2.5389559478242623,"y":-2.1792862223853824},"rotation":{"radians":-0.8106217177148143}},"curvature":0.20071365851955927},{"time":0.8575327854022509,"velocity":4.320038127841452,"acceleration":-3.354961102939187,"pose":{"translation":{"x":2.597437682511891,"y":-2.23970465453455},"rotation":{"radians":-0.7922269749141588}},"curvature":0.23796326254617617},{"time":0.8764453543171904,"velocity":4.256587194775173,"acceleration":-3.8861395961432224,"pose":{"translation":{"x":2.654979707745497,"y":-2.2968589488440285},"rotation":{"radians":-0.7712214176061186}},"curvature":0.2814208492984974},{"time":0.8949277819897445,"velocity":4.184761900764007,"acceleration":-4.4777260255035625,"pose":{"translation":{"x":2.7115435524635143,"y":-2.3505788541021255},"rotation":{"radians":-0.7473516406900496}},"curvature":0.33220425608892623},{"time":0.912984734386199,"velocity":4.103907815077124,"acceleration":-5.11185842177919,"pose":{"translation":{"x":2.767097001514443,"y":-2.400718164251047},"rotation":{"radians":-0.7203446363245664}},"curvature":0.3914981985278621},{"time":0.9306290336987828,"velocity":4.0137126550397,"acceleration":-5.755509512267635,"pose":{"translation":{"x":2.821614553335579,"y":-2.4471565653262983},"rotation":{"radians":-0.6899164560608424}},"curvature":0.46046118584548174},{"time":0.9478810135495537,"velocity":3.9144187209031385,"acceleration":-6.356839268896832,"pose":{"translation":{"x":2.8750778776317483,"y":-2.489801482396083},"rotation":{"radians":-0.6557871246247801}},"curvature":0.5400562006079622},{"time":0.9647671374724911,"velocity":3.8070763452503513,"acceleration":-6.8437882315068626,"pose":{"translation":{"x":2.9274762730540473,"y":-2.528589926500712},"rotation":{"radians":-0.6177042511649705}},"curvature":0.6307732766495935},{"time":0.981317637459908,"velocity":3.6938082282109135,"acceleration":-7.126794452842301,"pose":{"translation":{"x":2.9788071248785712,"y":-2.563490341591984},"rotation":{"radians":-0.5754779499559356}},"curvature":0.7322154294929463},{"time":0.9975629544099581,"velocity":3.5780311934866313,"acceleration":-7.10674688337942,"pose":{"translation":{"x":3.029076362685149,"y":-2.594504451472612},"rotation":{"radians":-0.5290291461838743}},"curvature":0.8425421381827005},{"time":1.0135288841201933,"velocity":3.4645653722781624,"acceleration":-6.6870818297374965,"pose":{"translation":{"x":3.0782989180360785,"y":-2.621669106735596},"rotation":{"radians":-0.478451501975481}},"curvature":0.9578207889404049},{"time":1.0292306002321454,"velocity":3.3595667117702304,"acceleration":-5.785774257210771,"pose":{"translation":{"x":3.126499182154865,"y":-2.645058131703647},"rotation":{"radians":-0.4240834522171856}},"curvature":1.0714338957068112},{"time":1.0446661559449735,"velocity":3.2702600708812066,"acceleration":-4.340553001474387,"pose":{"translation":{"x":3.173711463604948,"y":-2.664784171368569},"rotation":{"radians":-0.3665810929551392}},"curvature":1.1738091280013403},{"time":1.059810582885297,"velocity":3.2045248830697757,"acceleration":-2.30081053720373,"pose":{"translation":{"x":3.2199804459684396,"y":-2.6810005383306725},"rotation":{"radians":-0.3069761459696382}},"curvature":1.2528094160899457},{"time":1.0746120846913012,"velocity":3.170469431748081,"acceleration":0.3977579187639632,"pose":{"translation":{"x":3.2653616455248597,"y":-2.693903059738172},"rotation":{"radians":-0.24669911820251192}},"curvature":1.2950253234940936},{"time":1.0889917302829935,"velocity":3.176189049651196,"acceleration":3.8780505815630546,"pose":{"translation":{"x":3.3099218689298664,"y":-2.703731924226575},"rotation":{"radians":-0.18755053544781314}},"curvature":1.2878719020972225},{"time":1.1028472499648765,"velocity":3.2299214558113807,"acceleration":8.392529795697191,"pose":{"translation":{"x":3.3537396708939986,"y":-2.710773528858087},"rotation":{"radians":-0.13161552235012597}},"curvature":1.2219067314503889},{"time":1.1160601938775772,"velocity":3.340811481287596,"acceleration":18.700043425813895,"pose":{"translation":{"x":3.3969058118613997,"y":-2.715362326061045},"rotation":{"radians":-0.08113614721932995}},"curvature":1.0924796198481246},{"time":1.1398773728434104,"velocity":3.786193762229057,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.4817099273230365,"y":-2.7187706663614057},"rotation":{"radians":-0.005486303923341652}},"curvature":0.6490192275525587},{"time":1.184047961373033,"velocity":0.0,"acceleration":-85.71753033559611,"pose":{"translation":{"x":3.565321805332028,"y":-2.7176638555734356},"rotation":{"radians":0.022896761221391358}},"curvature":7.928831080838964E-15}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":71.6754486328193,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.052504537201690564,"velocity":3.763286259189722,"acceleration":3.393027875765885,"pose":{"translation":{"x":0.0987840856718992,"y":-0.0014550809384724233},"rotation":{"radians":-0.0406235201304543}},"curvature":-0.669267331858832},{"time":0.08369849591678691,"velocity":3.869128230665534,"acceleration":8.940395462782044,"pose":{"translation":{"x":0.21743610778889016,"y":-0.011090481290308164},"rotation":{"radians":-0.11922715157584657}},"curvature":-0.5777181959580991},{"time":0.10210103517690408,"velocity":4.033654209170354,"acceleration":7.7520539423460715,"pose":{"translation":{"x":0.2894547521368349,"y":-0.021134285931893225},"rotation":{"radians":-0.15629119482489962}},"curvature":-0.4449483653936229},{"time":0.12254133010230119,"velocity":4.192108478029495,"acceleration":5.75700633123382,"pose":{"translation":{"x":0.3722655413186195,"y":-0.035621769310835674},"rotation":{"radians":-0.18844460732445098}},"curvature":-0.3269300330427504},{"time":0.14533768211239437,"velocity":4.3233472208806365,"acceleration":3.944401761401226,"pose":{"translation":{"x":0.4673396090946371,"y":-0.055158757396353585},"rotation":{"radians":-0.21542702352704587}},"curvature":-0.2357318596690303},{"time":0.17082259532410582,"velocity":4.423869957442069,"acceleration":2.8844388002223487,"pose":{"translation":{"x":0.5759365232228123,"y":-0.08026398863855952},"rotation":{"radians":-0.23772289170313524}},"curvature":-0.16953787250521077},{"time":0.18466411165336516,"velocity":4.4637949641960954,"acceleration":2.326862827367757,"pose":{"translation":{"x":0.635643814194672,"y":-0.09504381204755785},"rotation":{"radians":-0.24733668078881516}},"curvature":-0.14407454738817005},{"time":0.1992899012288189,"velocity":4.497827170280122,"acceleration":1.8726028175616212,"pose":{"translation":{"x":0.6991124192700513,"y":-0.11137246160318348},"rotation":{"radians":-0.2560512882871814}},"curvature":-0.12272641890725453},{"time":0.21473112059424881,"velocity":4.526742441170413,"acceleration":1.5061957817442015,"pose":{"translation":{"x":0.766443903568408,"y":-0.1292917769905396},"rotation":{"radians":-0.2639545845640026}},"curvature":-0.1048403284194074},{"time":0.23101567055964584,"velocity":4.551270161635896,"acceleration":1.2125328488063274,"pose":{"translation":{"x":0.8377281344236926,"y":-0.14883878260629593},"rotation":{"radians":-0.27112822180522567}},"curvature":-0.08984639789950959},{"time":0.2481681966511829,"velocity":4.572068162961893,"acceleration":0.9780339853892758,"pose":{"translation":{"x":0.9130435355659563,"y":-0.1700457921722737},"rotation":{"radians":-0.2776468756372453}},"curvature":-0.07725850624670107},{"time":0.2662101398397362,"velocity":4.58971379656276,"acceleration":0.7910806745495272,"pose":{"translation":{"x":0.9924573413029585,"y":-0.19294051334903078},"rotation":{"radians":-0.2835780974936386}},"curvature":-0.06666802579853986},{"time":0.28515981743654306,"velocity":4.604704520298538,"acceleration":0.6420396874172175,"pose":{"translation":{"x":1.0760258507017746,"y":-0.21754615234944685},"rotation":{"radians":-0.2889825347232104}},"curvature":-0.057734725453877866},{"time":0.30503252074980275,"velocity":4.617463584521919,"acceleration":0.5230871945044425,"pose":{"translation":{"x":1.1637946817704043,"y":-0.24388151855230836},"rotation":{"radians":-0.29391435676502015}},"curvature":-0.050177014396362525},{"time":0.32584062079799275,"velocity":4.628348035199094,"acceleration":0.42795546527859657,"pose":{"translation":{"x":1.2557990256393792,"y":-0.2719611291158937},"rotation":{"radians":-0.29842178249670276}},"curvature":-0.04376264842952715},{"time":0.3475936765970335,"velocity":4.637657374314804,"acceleration":0.35166819045207165,"pose":{"translation":{"x":1.3520639007433704,"y":-0.3017953135915584},"rotation":{"radians":-0.30254764263473954}},"curvature":-0.03830040704132812},{"time":0.37029854270166584,"velocity":4.645641953492277,"acceleration":0.29029645766093237,"pose":{"translation":{"x":1.4526044070027964,"y":-0.33339031853731993},"rotation":{"radians":-0.3063299370432376}},"curvature":-0.03363290685993953},{"time":0.3939594741066458,"velocity":4.652510638064101,"acceleration":0.24074807079349372,"pose":{"translation":{"x":1.5574259800054309,"y":-0.36674841213144305},"rotation":{"radians":-0.3098023639018164}},"curvature":-0.02963053745593578},{"time":0.4185782275335135,"velocity":4.65843755545696,"acceleration":0.2005926419332328,"pose":{"translation":{"x":1.666524645188012,"y":-0.4018679887860249},"rotation":{"radians":-0.3129948087165449}},"curvature":-0.026186420205458822},{"time":0.4441541587084636,"velocity":4.6635678990612455,"acceleration":0.16791995076836871,"pose":{"translation":{"x":1.7798872720178476,"y":-0.4387436737605798},"rotation":{"radians":-0.31593378811677125}},"curvature":-0.023212258501245673},{"time":0.4706843155906152,"velocity":4.6680228416987735,"acceleration":0.1473081055449243,"pose":{"translation":{"x":1.8974918281744246,"y":-0.477366427775625},"rotation":{"radians":-0.3186428476369191}},"curvature":-0.020634943232970684},{"time":0.48430557417763576,"velocity":4.670029363496365,"acceleration":0.13525227729273576,"pose":{"translation":{"x":1.9578755731199786,"y":-0.49732915462086014},"rotation":{"radians":-0.31991779085791866}},"curvature":-0.01947571752148467},{"time":0.4981632894321226,"velocity":4.671903651042609,"acceleration":0.12432688548768328,"pose":{"translation":{"x":2.019307633731017,"y":-0.5177236516262647},"rotation":{"radians":-0.3211429151700534}},"curvature":-0.018393786838207256},{"time":0.5122564819575298,"velocity":4.673655813775871,"acceleration":0.11441569818551017,"pose":{"translation":{"x":2.081782865529898,"y":-0.538547804816047},"rotation":{"radians":-0.3223204787561041}},"curvature":-0.017383137392378067},{"time":0.5265840442775498,"velocity":4.675295111822012,"acceleration":0.10541529555668874,"pose":{"translation":{"x":2.145295615336293,"y":-0.5597992907957762},"rotation":{"radians":-0.3234526131282243}},"curvature":-0.01643827432726884},{"time":0.5411447433384899,"velocity":4.676830032217033,"acceleration":0.0972335891691984,"pose":{"translation":{"x":2.20983972921036,"y":-0.5814755800215547},"rotation":{"radians":-0.3245413308852529}},"curvature":-0.015554173193681813},{"time":0.5559372229684437,"velocity":4.678268358104166,"acceleration":0.08978851658604482,"pose":{"translation":{"x":2.275408560395923,"y":-0.6035739400691946},"rotation":{"radians":-0.3255885329724584}},"curvature":-0.014726236202830386},{"time":0.5709600062957906,"velocity":4.679617231534122,"acceleration":0.0830068906946886,"pose":{"translation":{"x":2.3419949772636413,"y":-0.6260914389033911},"rotation":{"radians":-0.32659601547299605}},"curvature":-0.013950252777561888},{"time":0.5862114981295551,"velocity":4.680883210449698,"acceleration":0.07682338543969686,"pose":{"translation":{"x":2.4095913712541885,"y":-0.6490249481468979},"rotation":{"radians":-0.3275654759594006}},"curvature":-0.013222363967972418},{"time":0.6016899873039058,"velocity":4.682072320389564,"acceleration":0.07117964169334849,"pose":{"translation":{"x":2.4781896648214286,"y":-0.6723711463497003},"rotation":{"radians":-0.3284985194323406}},"curvature":-0.012539030340552192},{"time":0.6173936489891477,"velocity":4.683190101401593,"acceleration":0.06602347886871857,"pose":{"translation":{"x":2.547781319375588,"y":-0.6961265222581916},"rotation":{"radians":-0.32939666387264166}},"curvature":-0.011897002989255367},{"time":0.6333205469712927,"velocity":4.684241650613961,"acceleration":0.061308199557898,"pose":{"translation":{"x":2.618357343226433,"y":-0.7202873780843462},"rotation":{"radians":-0.3302613454313242}},"curvature":-0.011293297352516853},{"time":0.6494686359022924,"velocity":4.685231660872621,"acceleration":0.056991975988469196,"pose":{"translation":{"x":2.6899082995264454,"y":-0.7448498327748948},"rotation":{"radians":-0.33109392328110016}},"curvature":-0.010725169552478188},{"time":0.6658357635228018,"velocity":4.68616445581697,"acceleration":0.05303730842556608,"pose":{"translation":{"x":2.762424314213996,"y":-0.7698098252804986},"rotation":{"radians":-0.33189568415147325}},"curvature":-0.010190095001780771},{"time":0.6824196728593326,"velocity":4.687044021731353,"acceleration":0.04941054684157204,"pose":{"translation":{"x":2.8358950839565202,"y":-0.7951631178249241},"rotation":{"radians":-0.332667846568304}},"curvature":-0.009685749049497792},{"time":0.699218004397476,"velocity":4.687874036478679,"acceleration":0.046081468224634096,"pose":{"translation":{"x":2.9103098840936954,"y":-0.8209052991742178},"rotation":{"radians":-0.3334115648174423}},"curvature":-0.009209989461344641},{"time":0.7162282982327365,"velocity":4.68865789579354,"acceleration":0.04302290282954284,"pose":{"translation":{"x":2.9856575765806124,"y":-0.8470317879058803},"rotation":{"radians":-0.3341279326508223}},"curvature":-0.008760840550476132},{"time":0.7334479962006001,"velocity":4.689398737185965,"acceleration":0.04021040348993698,"pose":{"translation":{"x":3.061926617930954,"y":-0.8735378356780407},"rotation":{"radians":-0.3348179867522378}},"curvature":-0.008336478794167414},{"time":0.7508744439870677,"velocity":4.6900994616828555,"acceleration":0.03762195283333545,"pose":{"translation":{"x":3.13910506716017,"y":-0.9004185304986319},"rotation":{"radians":-0.33548270997890794}},"curvature":-0.007935219788693488},{"time":0.7685048932210419,"velocity":4.690762753612367,"acceleration":0.03523770386995457,"pose":{"translation":{"x":3.2171805937286497,"y":-0.927668799994564},"rotation":{"radians":-0.33612303439387825}},"curvature":-0.007555506409969931},{"time":0.7863365035498443,"velocity":4.691391098616657,"acceleration":0.033039749987155066,"pose":{"translation":{"x":3.296140485484901,"y":-0.9552834146809005},"rotation":{"radians":-0.3367398441032938}},"curvature":-0.007195898061161926},{"time":0.8043663446988317,"velocity":4.691986800060528,"acceleration":0.03101192085748364,"pose":{"translation":{"x":3.3759716566087206,"y":-0.983256991230031},"rotation":{"radians":-0.3373339779116408}},"curvature":-0.006855060900686268},{"time":0.8225913985163283,"velocity":4.69255199398714,"acceleration":0.029139601208403573,"pose":{"translation":{"x":3.4566606555543737,"y":-1.011583995740847},"rotation":{"radians":-0.3379062318071501}},"curvature":-0.00653175895495657},{"time":0.8410085610047663,"velocity":4.693088662757443,"acceleration":0.027409569760689707,"pose":{"translation":{"x":3.5381936729937724,"y":-1.0402587470079157},"rotation":{"radians":-0.3384573612887194}},"curvature":-0.006224846030001168},{"time":0.8596146443389476,"velocity":4.6935986474965645,"acceleration":0.025809855984173163,"pose":{"translation":{"x":3.6205565497596375,"y":-1.069275419790655},"rotation":{"radians":-0.3389880835449301}},"curvature":-0.005933258344827627},{"time":0.8784063788723748,"velocity":4.694083659458565,"acceleration":0.02432961259209342,"pose":{"translation":{"x":3.70373478478869,"y":-1.0986280480825084},"rotation":{"radians":-0.3394990794949884}},"curvature":-0.0056560078172345615},{"time":0.897380415132286,"velocity":4.694545290410077,"acceleration":0.022959001958506343,"pose":{"translation":{"x":3.7877135430648137,"y":-1.1283105283801182},"rotation":{"radians":-0.3399909957007404}},"curvature":-0.005392175939770404},{"time":0.9165333258042762,"velocity":4.694985022123706,"acceleration":0.021689094852614006,"pose":{"translation":{"x":3.872477663562239,"y":-1.1583166229525013},"rotation":{"radians":-0.34046444615826527}},"curvature":-0.00514090818980659},{"time":0.9358616077071303,"velocity":4.6954042350632355,"acceleration":0.020511780085435836,"pose":{"translation":{"x":3.9580116671887158,"y":-1.1886399631102225},"rotation":{"radians":-0.34092001397695176}},"curvature":-0.004901408923299515},{"time":0.9553616837584529,"velocity":4.6958042163348495,"acceleration":0.01941968382425391,"pose":{"translation":{"x":4.044299764728684,"y":-1.2192740524745713},"rotation":{"radians":-0.34135825295340627}},"curvature":-0.004672936706836661},{"time":0.9750299049318558,"velocity":4.696186166971422,"acceleration":0.018406097485132958,"pose":{"translation":{"x":4.131325864786455,"y":-1.250212270246734},"rotation":{"radians":-0.34177968904702144}},"curvature":-0.004454800047062241},{"time":0.9948625522059731,"velocity":4.696551208610538,"acceleration":0.017464913239636663,"pose":{"translation":{"x":4.219073581729384,"y":-1.281447874476969},"rotation":{"radians":-0.3421848217635512}},"curvature":-0.004246353480603635},{"time":1.0148558385061224,"velocity":4.696900389621145,"acceleration":0.01659056628522065,"pose":{"translation":{"x":4.3075262436310435,"y":-1.312974005333782},"rotation":{"radians":-0.3425741254525841}},"curvature":-0.00404699399123586},{"time":1.0350059106388894,"velocity":4.697234690728516,"acceleration":0.015777983132407462,"pose":{"translation":{"x":4.396666900214407,"y":-1.3447836883730995},"rotation":{"radians":-0.3429480505243987}},"curvature":-0.0038561577242561726},{"time":1.0553088512201658,"velocity":4.697555030182546,"acceleration":0.015022535243084308,"pose":{"translation":{"x":4.48647833079501,"y":-1.3768698378074444},"rotation":{"radians":-0.34330702459128587}},"curvature":-0.003673316970948526},{"time":1.0757606805969266,"velocity":4.697862268510144,"acceleration":0.014319997438426777,"pose":{"translation":{"x":4.576943052224139,"y":-1.4092252597751103},"rotation":{"radians":-0.34365145353806514}},"curvature":-0.003497977398624211},{"time":1.0963573587634323,"velocity":4.698157212888728,"acceleration":0.013666510556798168,"pose":{"translation":{"x":4.668043326831998,"y":-1.4418426556093347},"rotation":{"radians":-0.3439817225261905}},"curvature":-0.00332967550406501},{"time":1.117094787271751,"velocity":4.698440621174358,"acceleration":0.013058547904707297,"pose":{"translation":{"x":4.759761170370888,"y":-1.474714625107476},"rotation":{"radians":-0.3442981969355225}},"curvature":-0.0031679762702993635},{"time":1.1379688111373605,"velocity":4.698713205614971,"acceleration":0.012492885094505708,"pose":{"translation":{"x":4.852078359958381,"y":-1.507833669800185},"rotation":{"radians":-0.3446012232475584}},"curvature":-0.00301247100853054},{"time":1.1589752207398896,"velocity":4.6989756362763835,"acceleration":0.011966572911404053,"pose":{"translation":{"x":4.944976442020495,"y":-1.5411921962205826},"rotation":{"radians":-0.34489112987363685}},"curvature":-0.0028627753687348653},{"time":1.1801097537194458,"velocity":4.699228544206232,"acceleration":0.011476912888864071,"pose":{"translation":{"x":5.03843674023487,"y":-1.5747825191734315},"rotation":{"radians":-0.3451682279313891}},"curvature":-0.002718527503976295},{"time":1.201368096868549,"velocity":4.699472524358716,"acceleration":0.011021435311205923,"pose":{"translation":{"x":5.13244036347394,"y":-1.608596865004313},"rotation":{"radians":-0.3454328119724706}},"curvature":-0.0025793863748584827},{"time":1.2227458880201547,"velocity":4.6997081383009895,"acceleration":0.010597879392235597,"pose":{"translation":{"x":5.226968213748115,"y":-1.6426273748688005},"rotation":{"radians":-0.3456851606643893}},"curvature":-0.002445030181772817},{"time":1.2442387179320789,"velocity":4.699935916720194,"acceleration":0.01020417540646546,"pose":{"translation":{"x":5.322000994148948,"y":-1.676866108001632},"rotation":{"radians":-0.34592553742904764}},"curvature":-0.0023151549137154226},{"time":1.2658421321675262,"velocity":4.700156361748431,"acceleration":0.009838428575118652,"pose":{"translation":{"x":5.41751921679232,"y":-1.7113050449858913},"rotation":{"radians":-0.34615419104042433}},"curvature":-0.002189473003451237},{"time":1.2875516329725323,"velocity":4.7003699491215025,"acceleration":0.009498904530761338,"pose":{"translation":{"x":5.513503210761603,"y":-1.7459360910221728},"rotation":{"radians":-0.3463713561836444}},"curvature":-0.002067712079705491},{"time":1.3093626811503483,"velocity":4.700577130185859,"acceleration":0.009184016203396412,"pose":{"translation":{"x":5.609933130050849,"y":-1.7807510791977645},"rotation":{"radians":-0.34657725397752587}},"curvature":-0.001949613807880811},{"time":1.3312706979323152,"velocity":4.700778333766969,"acceleration":0.008892311988809397,"pose":{"translation":{"x":5.70678896150795,"y":-1.8157417737558181},"rotation":{"radians":-0.3467720924625369}},"curvature":-0.0018349328115315432},{"time":1.353271066846537,"velocity":4.7009739679112235,"acceleration":0.008622465074958126,"pose":{"translation":{"x":5.804050532777829,"y":-1.8508998733645248},"rotation":{"radians":-0.34695606705594856}},"curvature":-0.0017234356674891186},{"time":1.3753591355835073,"velocity":4.701164421512481,"acceleration":0.00837326381556048,"pose":{"translation":{"x":5.901697520245603,"y":-1.8862170143862897},"rotation":{"radians":-0.3471293609758433}},"curvature":-0.0016148999681312745},{"time":1.3975302178590974,"velocity":4.701350065833451,"acceleration":0.008143603052542164,"pose":{"translation":{"x":5.999709456979765,"y":-1.9216847741469065},"rotation":{"radians":-0.34729214563550515}},"curvature":-0.0015091134448230758},{"time":1.419779595275509,"velocity":4.701531255931297,"acceleration":0.007932476300126834,"pose":{"translation":{"x":6.098065740675358,"y":-1.9572946742047326},"rotation":{"radians":-0.34744458100960596}},"curvature":-0.001405873147046175},{"time":1.442102519179547,"velocity":4.701708331996115,"acceleration":0.007738968711621765,"pose":{"translation":{"x":6.196745641597146,"y":-1.9930381836198596},"rotation":{"radians":-0.34758681597348584}},"curvature":-0.001304984672166229},{"time":1.4644942125187514,"velocity":4.701881620610267,"acceleration":0.007562250761078728,"pose":{"translation":{"x":6.295728310522794,"y":-2.028906722223296},"rotation":{"radians":-0.34771898861672773}},"curvature":-0.001206261441183089},{"time":1.4869498716956224,"velocity":4.702051435935968,"acceleration":0.007401572575570495,"pose":{"translation":{"x":6.394992786686045,"y":-2.064891663886134},"rotation":{"radians":-0.34784122653211924}},"curvature":-0.001109524016160343},{"time":1.5094646684197912,"velocity":4.702218080837946,"acceleration":0.007256258868360784,"pose":{"translation":{"x":6.494518005719888,"y":-2.1009843397887265},"rotation":{"radians":-0.34795364708101434}},"curvature":-0.0010145994553500933},{"time":1.5320337515578726,"velocity":4.702381847947618,"acceleration":0.007125704417549445,"pose":{"translation":{"x":6.594282807599738,"y":-2.1371760416898637},"rotation":{"radians":-0.348056357636004}},"curvature":-9.213207023082924E-4},{"time":1.5546522489821248,"velocity":4.702543020674632,"acceleration":0.007009370055230198,"pose":{"translation":{"x":6.694265944586614,"y":-2.173458025195944},"rotation":{"radians":-0.3481494558017369}},"curvature":-8.295260055553096E-4},{"time":1.5773152694167862,"velocity":4.702701874171428,"acceleration":0.006906779123471565,"pose":{"translation":{"x":6.794446089170307,"y":-2.2098215130301524},"rotation":{"radians":-0.34823302961464364}},"curvature":-7.390583655584746E-4},{"time":1.6000179042829614,"velocity":4.702858676255969,"acceleration":0.00681751436758972,"pose":{"translation":{"x":6.894801842012562,"y":-2.246257698301633},"rotation":{"radians":-0.3483071577222395}},"curvature":-6.497650060150667E-4},{"time":1.6227552295418346,"velocity":4.703013688297602,"acceleration":0.0067412152377363125,"pose":{"translation":{"x":6.995311739890247,"y":-2.282757747774662},"rotation":{"radians":-0.3483719095426188}},"curvature":-5.614968665936572E-4},{"time":1.6455223075360237,"velocity":4.7031671660706955,"acceleration":0.006677575573078309,"pose":{"translation":{"x":7.095954263638535,"y":-2.319312805137826},"rotation":{"radians":-0.3484273454046753}},"curvature":-4.7410811444260957E-4},{"time":1.6683141888298572,"velocity":4.703319360580488,"acceleration":0.006626341648883162,"pose":{"translation":{"x":7.196707846094072,"y":-2.355913994273193},"rotation":{"radians":-0.3484735166695209}},"curvature":-3.8745567191490635E-4},{"time":1.691125914047767,"velocity":4.703470518865382,"acceleration":0.006587310568012005,"pose":{"translation":{"x":7.2975508800381625,"y":-2.3925524225254877},"rotation":{"radians":-0.34851046583350903}},"curvature":-3.013987580703957E-4},{"time":1.7139525157111006,"velocity":4.703620884779751,"acceleration":0.006560328983487329,"pose":{"translation":{"x":7.398461726139931,"y":-2.429219183971269},"rotation":{"radians":-0.3485382266132044}},"curvature":-2.1579844161684353E-4},{"time":1.7367890200739886,"velocity":4.703770699761204,"acceleration":0.0065452921394948465,"pose":{"translation":{"x":7.499418720899509,"y":-2.465905362688101},"rotation":{"radians":-0.34855682401258936}},"curvature":-1.3051720303238805E-4},{"time":1.759630448957244,"velocity":4.7039202035861285,"acceleration":4.449473299374387E-4,"pose":{"translation":{"x":7.600400184591206,"y":-2.5026020360237293},"rotation":{"radians":-0.3485662743727219}},"curvature":-4.541850367600483E-5},{"time":1.7824721597108582,"velocity":4.7039303669443395,"acceleration":-0.00654966633545872,"pose":{"translation":{"x":7.701384429206682,"y":-2.5393002778652534},"rotation":{"radians":-0.3485665854040169}},"curvature":3.963364025820933E-5},{"time":1.8053098968726535,"velocity":4.703780787386073,"acceleration":-0.006569054232772703,"pose":{"translation":{"x":7.802349766398126,"y":-2.5759911619083042},"rotation":{"radians":-0.34855775620125407}},"curvature":1.2477508105031952E-4},{"time":1.828139068949373,"velocity":4.703630821316612,"acceleration":-0.006600426578437126,"pose":{"translation":{"x":7.9032745154214314,"y":-2.612665764926218},"rotation":{"radians":-0.34853977724137036}},"curvature":2.101419621190588E-4},{"time":1.850954701227469,"velocity":4.703480228410919,"acceleration":-0.00664390882496388,"pose":{"translation":{"x":8.004137011079372,"y":-2.649315170039208},"rotation":{"radians":-0.3485126303640174}},"curvature":2.958711421266519E-4},{"time":1.8737518250882366,"velocity":4.703328766398517,"acceleration":-0.006699675404599612,"pose":{"translation":{"x":8.10491561166477,"y":-2.6859304699835427},"rotation":{"radians":-0.34847628873483827}},"curvature":3.8210062261826935E-4},{"time":1.8965254798420614,"velocity":4.70317619030389,"acceleration":-0.006767950827795425,"pose":{"translation":{"x":8.205588706903683,"y":-2.7225027703807188},"rotation":{"radians":-0.34843071679132664}},"curvature":4.689699813158928E-4},{"time":1.919270714564398,"velocity":4.703022251673723,"acceleration":-0.0068490111044155035,"pose":{"translation":{"x":8.306134725898573,"y":-2.7590231930066356},"rotation":{"radians":-0.348375870171102}},"curvature":5.566208132271923E-4},{"time":1.9419825899332837,"velocity":4.702866697787119,"acceleration":-0.006943185502400931,"pose":{"translation":{"x":8.406532145071477,"y":-2.795482879060766},"rotation":{"radians":-0.3483116956223592}},"curvature":6.451971817814837E-4},{"time":1.9646561800679763,"velocity":4.702709270844808,"acceleration":-0.0070508586574038225,"pose":{"translation":{"x":8.50675949610719,"y":-2.8318729924353425},"rotation":{"radians":-0.3482381308961976}},"curvature":7.34846082278786E-4},{"time":1.9872865743693844,"velocity":4.702549707133228,"acceleration":-0.007172473054539557,"pose":{"translation":{"x":8.606795373896436,"y":-2.868184722984517},"rotation":{"radians":-0.34815510462047056}},"curvature":8.257179200227773E-4},{"time":2.009868879362072,"velocity":4.702387736159158,"acceleration":-0.007308531901937402,"pose":{"translation":{"x":8.706618444479046,"y":-2.904409289793546},"rotation":{"radians":-0.34806253615474037}},"curvature":9.179670056143282E-4},{"time":2.0323982205378757,"velocity":4.702223079750445,"acceleration":-0.007459602426343874,"pose":{"translation":{"x":8.806207452987135,"y":-2.940537944447957},"rotation":{"radians":-0.3479603354258481}},"curvature":0.0010117520700021036},{"time":2.0548697442008126,"velocity":4.702055451118006,"acceleration":-0.007626319616182957,"pose":{"translation":{"x":8.905541231588264,"y":-2.976561974302734},"rotation":{"radians":-0.3478484027435526}},"curvature":0.001107236802033505},{"time":2.0772786193144706,"velocity":4.70188455387415,"acceleration":-0.007809390451326412,"pose":{"translation":{"x":9.004598707428634,"y":-3.0124727057514793},"rotation":{"radians":-0.347726628595613}},"curvature":0.0012045904114051415},{"time":2.0996200393503432,"velocity":4.701710081001853,"acceleration":-0.008009598655879972,"pose":{"translation":{"x":9.10335891057625,"y":-3.0482615074955994},"rotation":{"radians":-0.34759489342162275}},"curvature":0.0013039882201029346},{"time":2.121889224138702,"velocity":4.701531713769304,"acceleration":-0.00822781002135825,"pose":{"translation":{"x":9.201800981964098,"y":-3.08391979381347},"rotation":{"radians":-0.34745306736482856}},"curvature":0.0014056122856276633},{"time":2.1440814217209203,"velocity":4.701349120583641,"acceleration":-0.008464978348691914,"pose":{"translation":{"x":9.299904181333321,"y":-3.119439027829614},"rotation":{"radians":-0.3473010100010797}},"curvature":0.0015096520595355926},{"time":2.1661919102041907,"velocity":4.701161955777351,"acceleration":-0.008722152069124894,"pose":{"translation":{"x":9.397647895176398,"y":-3.1548107247838875},"rotation":{"radians":-0.3471385700439829}},"curvature":0.0016163050850910667},{"time":2.188215999618132,"velocity":4.700969858320299,"acceleration":-0.009000481606593141,"pose":{"translation":{"x":9.495011644680316,"y":-3.190026455300628},"rotation":{"radians":-0.34696558502523067}},"curvature":0.001725777738118011},{"time":2.210149033773783,"velocity":4.700772450449804,"acceleration":-0.00930122755461837,"pose":{"translation":{"x":9.591975093669726,"y":-3.2250778486578557},"rotation":{"radians":-0.3467818809490062}},"curvature":0.001838286015466734},{"time":2.2319863921246013,"velocity":4.700569336210592,"acceleration":-0.009625769750443165,"pose":{"translation":{"x":9.68851805655017,"y":-3.2599565960564316},"rotation":{"radians":-0.3465872719192283}},"curvature":0.0019540563758784833},{"time":2.2537234916304514,"velocity":4.700360099895706,"acceleration":-0.009975617338042204,"pose":{"translation":{"x":9.78462050625119,"y":-3.294654453889242},"rotation":{"radians":-0.34638155973835105}},"curvature":0.002073326638432182},{"time":2.275355788623497,"velocity":4.70014430437876,"acceleration":-0.010352419921175708,"pose":{"translation":{"x":9.880262582169562,"y":-3.3291632470103636},"rotation":{"radians":-0.3461645334762574}},"curvature":0.002196346944214573},{"time":2.296878780677523,"velocity":4.699921489327057,"acceleration":-0.010757979926080005,"pose":{"translation":{"x":9.975424598112431,"y":-3.3634748720042476},"rotation":{"radians":-0.34593596900772544}},"curvature":0.0023233807873473296},{"time":2.318288008479419,"velocity":4.699691169284131,"acceleration":-0.011194266298869378,"pose":{"translation":{"x":10.07008705024051,"y":-3.3975813004548874},"rotation":{"radians":-0.3456956285167822}},"curvature":0.0024547061220649216},{"time":2.3395790577042384,"velocity":4.699452831609326,"acceleration":-0.011663429689199518,"pose":{"translation":{"x":10.164230625011236,"y":-3.4314745822149924},"rotation":{"radians":-0.34544325996614667}},"curvature":0.002590616553150375},{"time":2.360747560893146,"velocity":4.699205934260757,"acceleration":-0.0121678192788589,"pose":{"translation":{"x":10.257836207121956,"y":-3.46514684867517},"rotation":{"radians":-0.345178596529807}},"curvature":0.0027314226177157816},{"time":2.3817891993347553,"velocity":4.698949903406868,"acceleration":-0.012710001443912312,"pose":{"translation":{"x":10.350884887453121,"y":-3.498590316033094},"rotation":{"radians":-0.34490135598663285}},"curvature":0.002877453167072652},{"time":2.4026997049501913,"velocity":4.698684130850303,"acceleration":-0.013292780455117918,"pose":{"translation":{"x":10.44335797101142,"y":-3.5317972885626787},"rotation":{"radians":-0.3446112400727581}},"curvature":0.0030290568582754976},{"time":2.423474862181822,"velocity":4.6984079712463025,"acceleration":-0.013919221449873004,"pose":{"translation":{"x":10.53523698487298,"y":-3.5647601618832567},"rotation":{"radians":-0.3443079337902877}},"curvature":0.0031866037658480804},{"time":2.4441105098860723,"velocity":4.6981207390961455,"acceleration":-0.014592675939876076,"pose":{"translation":{"x":10.626503686126556,"y":-3.597471426228756},"rotation":{"radians":-0.3439911046697081}},"curvature":0.0033504871252351643},{"time":2.4646025432303795,"velocity":4.697821705494203,"acceleration":-0.015316810146859804,"pose":{"translation":{"x":10.717140069816656,"y":-3.629923669716865},"rotation":{"radians":-0.34366040198316133}},"curvature":0.0035211252206675107},{"time":2.4849469155949153,"velocity":4.697510094605138,"acceleration":-0.0160956365025476,"pose":{"translation":{"x":10.807128376886784,"y":-3.6621095816182105},"rotation":{"radians":-0.34331545590554663}},"curvature":0.0036989634313900604},{"time":2.505139640478907,"velocity":4.69718507984541,"acceleration":-0.016933548684983864,"pose":{"translation":{"x":10.896451102122565,"y":-3.694021955625546},"rotation":{"radians":-0.3429558766201623}},"curvature":0.0038844764516212213},{"time":2.5251767934121814,"velocity":4.6968457797407055,"acceleration":-0.017835360616437822,"pose":{"translation":{"x":10.985091002094928,"y":-3.7256536931229007},"rotation":{"radians":-0.34258125336537437}},"curvature":0.004078170701167172},{"time":2.545054513872177,"velocity":4.696491253428069,"acceleration":-0.018806349899489008,"pose":{"translation":{"x":11.073031103103302,"y":-3.756997806454782},"rotation":{"radians":-0.3421911534185059}},"curvature":0.004280586945357151},{"time":2.5647690072067633,"velocity":4.696120495768327,"acceleration":-0.019852306232666976,"pose":{"translation":{"x":11.16025470911876,"y":-3.7880474221953246},"rotation":{"radians":-0.3417851210128856}},"curvature":0.004492303144895317},{"time":2.5843165465631714,"velocity":4.695732432030929,"acceleration":-0.020979585412727316,"pose":{"translation":{"x":11.246745409727243,"y":-3.8187957844174782},"rotation":{"radians":-0.3413626761836514}},"curvature":0.004713937558374009},{"time":2.603693474823708,"velocity":4.695325912109451,"acceleration":-0.022195169616132677,"pose":{"translation":{"x":11.33248708807267,"y":-3.849236257962188},"rotation":{"radians":-0.34092331353761457}},"curvature":0.004946152122576614},{"time":2.62289620654834,"velocity":4.694899704221729,"acceleration":-0.02350673473946075,"pose":{"translation":{"x":11.417463928800158,"y":-3.8793623317075525},"rotation":{"radians":-0.3404665009421011}},"curvature":0.005189656138359233},{"time":2.6419212299249346,"velocity":4.694452488043804,"acceleration":-0.024922725682528783,"pose":{"translation":{"x":11.501660425999223,"y":-3.9091676218380123},"rotation":{"radians":-0.33999167812732334}},"curvature":0.005445210292855843},{"time":2.660765108727339,"velocity":4.6939828472216165,"acceleration":-0.026452440575377722,"pose":{"translation":{"x":11.585061391146851,"y":-3.9386458751135187},"rotation":{"radians":-0.33949825519644855}},"curvature":0.00571363105204153},{"time":2.679424484282301,"velocity":4.693489261198575,"acceleration":-0.028106125087259022,"pose":{"translation":{"x":11.667651961050796,"y":-3.967790972138708},"rotation":{"radians":-0.33898561103703356}},"curvature":0.005995795461361073},{"time":2.697896077445319,"velocity":4.6929700962905745,"acceleration":-0.02989507810188587,"pose":{"translation":{"x":11.749417605792681,"y":-3.9965969306320748},"rotation":{"radians":-0.3384530916271089}},"curvature":0.006292646396205132},{"time":2.716176690586381,"velocity":4.692423595932972,"acceleration":-0.031831770225640814,"pose":{"translation":{"x":11.830344136671187,"y":-4.025057908695155},"rotation":{"radians":-0.3379000082286223}},"curvature":0.006605198308581373},{"time":2.7342632095861976,"velocity":4.691847870015988,"acceleration":-0.033929976783624,"pose":{"translation":{"x":11.910417714145257,"y":-4.053168208081688},"rotation":{"radians":-0.33732563546046274}},"curvature":0.006934543521389735},{"time":2.752152605843496,"velocity":4.691240883216305,"acceleration":-0.03620492719374585,"pose":{"translation":{"x":11.989624855777217,"y":-4.0809222774667955},"rotation":{"radians":-0.33672920924269195}},"curvature":0.0072818591273748415},{"time":2.769841938294482,"velocity":4.690600442222811,"acceleration":-0.03867347285947374,"pose":{"translation":{"x":12.067952444176013,"y":-4.108314715716173},"rotation":{"radians":-0.3361099246030069}},"curvature":0.007648414556132973},{"time":2.7873283554448736,"velocity":4.689924181743736,"acceleration":-0.04135427601665364,"pose":{"translation":{"x":12.145387734940332,"y":-4.135340275155226},"rotation":{"radians":-0.3354669333358014}},"curvature":0.008035579879585916},{"time":2.80460909741585,"velocity":4.689209549170496,"acceleration":-0.04426802230643189,"pose":{"translation":{"x":12.221918364601805,"y":-4.161993864838287},"rotation":{"radians":-0.3347993415035072}},"curvature":0.008444834934168088},{"time":2.8216814980044727,"velocity":4.688453787760414,"acceleration":-0.047437660221822595,"pose":{"translation":{"x":12.297532358568203,"y":-4.1882705538177625},"rotation":{"radians":-0.3341062067691632}},"curvature":0.008877779346723532},{"time":2.838542986759918,"velocity":4.687653918185999,"acceleration":-0.05088867101258431,"pose":{"translation":{"x":12.372218139066542,"y":-4.214165574413309},"rotation":{"radians":-0.3333865355483635}},"curvature":0.009336143560852333},{"time":2.8551910910764002,"velocity":4.686806718282455,"acceleration":-0.054649373121779386,"pose":{"translation":{"x":12.445964533086354,"y":-4.239674325481033},"rotation":{"radians":-0.3326392799679521}},"curvature":0.009821800971294984},{"time":2.871623438304054,"velocity":4.685908700807544,"acceleration":-0.05875126578953377,"pose":{"translation":{"x":12.518760780322776,"y":-4.264792375682632},"rotation":{"radians":-0.33186333461791867}},"curvature":0.010336781286057863},{"time":2.8878377578790704,"velocity":4.684956089008596,"acceleration":-0.06322941709174404,"pose":{"translation":{"x":12.590596541119782,"y":-4.289515466754583},"rotation":{"radians":-0.3310575330820859}},"curvature":0.01088328524943052},{"time":2.903831883474275,"velocity":4.683944789770319,"acceleration":-0.06812290240327248,"pose":{"translation":{"x":12.661461904413306,"y":-4.313839516777328},"rotation":{"radians":-0.3302206442322277}},"curvature":0.011463700874031485},{"time":2.9196037551717033,"velocity":4.682870364093958,"acceleration":-0.07347530008608452,"pose":{"translation":{"x":12.731347395674508,"y":-4.337760623444428},"rotation":{"radians":-0.32935136826924993}},"curvature":0.012080621346673854},{"time":2.935151421658612,"velocity":4.681727994633194,"acceleration":-0.0793352521256913,"pose":{"translation":{"x":12.800243984852827,"y":-4.361275067331761},"rotation":{"radians":-0.32844833249412186}},"curvature":0.01273686479130493},{"time":2.950473042448533,"velocity":4.680512449984851,"acceleration":-0.08575709846545777,"pose":{"translation":{"x":12.86814309431925,"y":-4.3843793151666635},"rotation":{"radians":-0.3275100867901435}},"curvature":0.013435496092784157},{"time":2.965566890129039,"velocity":4.679218045403092,"acceleration":-0.09280159495653127,"pose":{"translation":{"x":12.935036606809449,"y":-4.40707002309715},"rotation":{"radians":-0.3265350987972188}},"curvature":0.01417985100789982},{"time":2.980431352638047,"velocity":4.677838599574084,"acceleration":-0.10053672612980348,"pose":{"translation":{"x":13.000916873366975,"y":-4.4293440399610375},"rotation":{"radians":-0.32552174875765966}},"curvature":0.014973562815084425},{"time":2.9950649355704617,"velocity":4.67636738705451,"acceleration":-0.10903862543674586,"pose":{"translation":{"x":13.06577672128643,"y":-4.451198410555165},"rotation":{"radians":-0.32446832401217235}},"curvature":0.015820591781829072},{"time":3.0094662645171266,"velocity":4.674797085941703,"acceleration":-0.11839261719725701,"pose":{"translation":{"x":13.129609462056594,"y":-4.472630378904537},"rotation":{"radians":-0.32337301312369243}},"curvature":0.016725257759070637},{"time":3.0236340874381407,"velocity":4.673119720306097,"acceleration":-0.12869439622974374,"pose":{"translation":{"x":13.192408899303656,"y":-4.493637391531511},"rotation":{"radians":-0.32223389960592}},"curvature":0.017692276244898913},{"time":3.037567277072596,"velocity":4.6713265968785365,"acceleration":-0.1400513630315125,"pose":{"translation":{"x":13.254169336734417,"y":-4.514217100724977},"rotation":{"radians":-0.32104895523272536}},"curvature":0.018726798295979317},{"time":3.0512648333868566,"velocity":4.669408235446523,"acceleration":-0.15944310911691464,"pose":{"translation":{"x":13.31488558607937,"y":-4.534367367809519},"rotation":{"radians":-0.3198160329040922}},"curvature":0.01983445470401043},{"time":3.077949955319033,"velocity":4.665153476638493,"acceleration":-0.1901269962237044,"pose":{"translation":{"x":13.433167355211653,"y":-4.573372085743699},"rotation":{"radians":-0.3171970255059308}},"curvature":0.022294391065331428},{"time":3.103683870896565,"velocity":4.660260764568663,"acceleration":-0.22775501837782047,"pose":{"translation":{"x":13.547223162860146,"y":-4.61063874087338},"rotation":{"radians":-0.31435702175215313}},"curvature":0.025128719746191984},{"time":3.1284634250193823,"velocity":4.654617096764026,"acceleration":-0.27407522987829763,"pose":{"translation":{"x":13.657030601927586,"y":-4.6461580825362425},"rotation":{"radians":-0.3112737242049294}},"curvature":0.02840547474637604},{"time":3.1522877493248997,"velocity":4.648087439603296,"acceleration":-0.33130354234391324,"pose":{"translation":{"x":13.762576156241451,"y":-4.679924518481943},"rotation":{"radians":-0.30792207344212147}},"curvature":0.03220657073056085},{"time":3.175158351948469,"velocity":4.640510327938568,"acceleration":-0.4022481120027285,"pose":{"translation":{"x":13.863855454735537,"y":-4.711936219485672},"rotation":{"radians":-0.3042738902734083}},"curvature":0.03663082788132656},{"time":3.197079210639608,"velocity":4.6316927039165785,"acceleration":-0.4904616550168139,"pose":{"translation":{"x":13.960873525631587,"y":-4.74219522396174},"rotation":{"radians":-0.3002974800220574}},"curvature":0.041797641580355344},{"time":3.2180568690647227,"velocity":4.621403966847019,"acceleration":-0.6004230195223179,"pose":{"translation":{"x":14.053645050620927,"y":-4.770707542577206},"rotation":{"radians":-0.29595720118383684}},"curvature":0.047851400266761906},{"time":3.238100535762091,"velocity":4.609369287966286,"acceleration":-0.7377446298927908,"pose":{"translation":{"x":14.14219461904598,"y":-4.797483262865374},"rotation":{"radians":-0.2912130051670268}},"curvature":0.05496674222623008},{"time":3.2572221846333433,"velocity":4.5952623941968245,"acceleration":-0.9093929586820941,"pose":{"translation":{"x":14.226556982082004,"y":-4.822536653839496},"rotation":{"radians":-0.28601996080331615}},"curvature":0.06335470093611098},{"time":3.2754366549525287,"velocity":4.578698283142433,"acceleration":-1.1238917562461512,"pose":{"translation":{"x":14.306777306918573,"y":-4.845886270606236},"rotation":{"radians":-0.2803277881560503}},"curvature":0.07326969592626409},{"time":3.292761747501338,"velocity":4.559226754450624,"acceleration":-1.3914476517067018,"pose":{"translation":{"x":14.382911430941283,"y":-4.867555058979352},"rotation":{"radians":-0.27408044263325626}},"curvature":0.08501714408146493},{"time":3.3092183113897087,"velocity":4.53632830727299,"acceleration":-1.7238886333663872,"pose":{"translation":{"x":14.455026115913277,"y":-4.887570460093219},"rotation":{"radians":-0.2672158150436699}},"curvature":0.098961134271922},{"time":3.324830313117469,"velocity":4.509414954950408,"acceleration":-2.134230780024759,"pose":{"translation":{"x":14.523199302156948,"y":-4.90596451501645},"rotation":{"radians":-0.2596656494177151}},"curvature":0.11553103187927309},{"time":3.3396248751158573,"velocity":4.477839945356463,"acceleration":-2.635582574494589,"pose":{"translation":{"x":14.587520362735464,"y":-4.922773969365473},"rotation":{"radians":-0.2513558325781181}},"curvature":0.1352249183989282},{"time":3.3536322649503463,"velocity":4.44092231279453,"acceleration":-3.582519105845448,"pose":{"translation":{"x":14.6480903576344,"y":-4.938040377918078},"rotation":{"radians":-0.24220728295076446}},"curvature":0.1586062266635573},{"time":3.3794347583579305,"velocity":4.348484387183408,"acceleration":-5.186635757116057,"pose":{"translation":{"x":14.758441350037616,"y":-4.964134950233838},"rotation":{"radians":-0.2210651007715408}},"curvature":0.21889213471806965},{"time":3.402523334073605,"velocity":4.228732354795608,"acceleration":-6.925099334184698,"pose":{"translation":{"x":14.855304156600658,"y":-4.984680828730376},"rotation":{"radians":-0.19561593010305592}},"curvature":0.3009105711885031},{"time":3.423220591137756,"velocity":4.085401793681209,"acceleration":-7.899727949539971,"pose":{"translation":{"x":14.939933912939077,"y":-5.000194252026091},"rotation":{"radians":-0.16547937300014395}},"curvature":0.40539956187435466},{"time":3.4418379315812926,"velocity":3.9383298690332986,"acceleration":-2.659333139312578,"pose":{"translation":{"x":15.01379714686142,"y":-5.01127844822588},"rotation":{"radians":-0.13098495469222307}},"curvature":0.5205219044461243},{"time":3.4733958669977514,"velocity":3.8544068055720233,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.136195922525479,"y":-5.023027104998107},"rotation":{"radians":-0.05862956694538753}},"curvature":0.5901506220921002},{"time":3.526652624736256,"velocity":0.0,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.238769634755512,"y":-5.02661962373552},"rotation":{"radians":-0.02161825323650912}},"curvature":-7.335559861346185E-16}] \ No newline at end of file diff --git a/src/main/deploy/paths/first.wpilib.json b/src/main/deploy/paths/first.wpilib.json new file mode 100644 index 0000000..832f6c6 --- /dev/null +++ b/src/main/deploy/paths/first.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":89.99999999999999,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.003960837658956053}},"curvature":0.0},{"time":0.046268155422340224,"velocity":4.16413398801062,"acceleration":20.122343156600795,"pose":{"translation":{"x":0.09633282642131955,"y":3.32220114244968E-4},"rotation":{"radians":0.0024357124642793598}},"curvature":-0.03131873164373634},{"time":0.06769694599968468,"velocity":4.595331465438878,"acceleration":-3.2657388277819996,"pose":{"translation":{"x":0.19018519082278293,"y":3.776271428801176E-4},"rotation":{"radians":-0.0019667245489377147}},"curvature":-0.06331350571724444},{"time":0.08727201667016053,"velocity":4.531404397093729,"acceleration":-4.52621852103831,"pose":{"translation":{"x":0.27951217351503466,"y":-9.815272475990487E-5},"rotation":{"radians":-0.009258944862072073}},"curvature":-0.10197795517826011},{"time":0.10580687754114987,"velocity":4.447511566534589,"acceleration":-6.795909334949117,"pose":{"translation":{"x":0.3627153187438831,"y":-0.0012758091071502224},"rotation":{"radians":-0.019770411994646908}},"curvature":-0.15440454953617785},{"time":0.12310628206035071,"velocity":4.329946381873491,"acceleration":-10.696663117552502,"pose":{"translation":{"x":0.4386110942223797,"y":-0.0032862219490998323},"rotation":{"radians":-0.034161978708522875}},"curvature":-0.2312920659185204},{"time":0.13909221520104129,"velocity":4.158950240447806,"acceleration":-21.683082829690306,"pose":{"translation":{"x":0.5063993506628987,"y":-0.006214336040275707},"rotation":{"radians":-0.05351578822542692}},"curvature":-0.3508825915332652},{"time":0.16770650689654784,"velocity":3.5385041835012174,"acceleration":-39.57935184498636,"pose":{"translation":{"x":0.6161803814685892,"y":-0.01495701846440868},"rotation":{"radians":-0.11475473627775676}},"curvature":-0.8818615338803364},{"time":0.1806292830179099,"velocity":3.0270290805798403,"acceleration":-50.24054622708399,"pose":{"translation":{"x":0.6582059080438363,"y":-0.02074667126770655},"rotation":{"radians":-0.16324504296814954}},"curvature":-1.483263576326746},{"time":0.19340362507468264,"velocity":2.3852391579559655,"acceleration":-52.31573221352215,"pose":{"translation":{"x":0.6921263390654158,"y":-0.027411943297960463},"rotation":{"radians":-0.23115572109507088}},"curvature":-2.60275578859484},{"time":0.19998960390162554,"velocity":2.0406888532816945,"acceleration":-48.82847096237592,"pose":{"translation":{"x":0.7062403338681601,"y":-0.03104680155187179},"rotation":{"radians":-0.2751182294430506}},"curvature":-3.4942543002833997},{"time":0.20689192397686854,"velocity":1.703659117914667,"acceleration":-42.09584948509217,"pose":{"translation":{"x":0.7185853332235053,"y":-0.03486622134698884},"rotation":{"radians":-0.3275998859857463}},"curvature":-4.7151693077318395},{"time":0.21425782386030356,"velocity":1.3935853050993279,"acceleration":-33.47946457803886,"pose":{"translation":{"x":0.7292718824627865,"y":-0.03885586129509029},"rotation":{"radians":-0.3901345476725628}},"curvature":-6.3600164187933075},{"time":0.2222279700596823,"velocity":1.126749077735436,"acceleration":-24.610040250706277,"pose":{"translation":{"x":0.7384206894000815,"y":-0.04300020416261273},"rotation":{"radians":-0.4641218974499291}},"curvature":-8.500247808028147},{"time":0.23090083280185988,"velocity":0.9133095765615955,"acceleration":-18.440304315324298,"pose":{"translation":{"x":0.7461616386925873,"y":-0.047282677949354555},"rotation":{"radians":-0.5503602998422257}},"curvature":-11.112446943670053},{"time":0.23553048468936674,"velocity":0.8279373868819537,"acceleration":-14.835842318158711,"pose":{"translation":{"x":0.7495470224107086,"y":-0.04947027657132941},"rotation":{"radians":-0.5979788357637982}},"curvature":-12.534374994362405},{"time":0.240324617264116,"velocity":0.7568123919506256,"acceleration":-11.58790247830829,"pose":{"translation":{"x":0.7526328062009993,"y":-0.05168577696717986},"rotation":{"radians":-0.6482969874931133}},"curvature":-13.963970672320935},{"time":0.24525422853929355,"velocity":0.6996885372378991,"acceleration":-8.647190267378619,"pose":{"translation":{"x":0.7554373677150925,"y":-0.05392686490162407},"rotation":{"radians":-0.7008848489380142}},"curvature":-15.322600732311253},{"time":0.25027551780064833,"velocity":0.6562684936074192,"acceleration":-5.918966766574035,"pose":{"translation":{"x":0.7579794733498865,"y":-0.05619118291872226},"rotation":{"radians":-0.755126924459009}},"curvature":-16.51351541146729},{"time":0.2553297602340695,"velocity":0.6263526006137912,"acceleration":-3.2583415516964456,"pose":{"translation":{"x":0.7602782474463078,"y":-0.05847633412558619},"rotation":{"radians":-0.8102222731392336}},"curvature":-17.43011200335713},{"time":0.2603448643600171,"velocity":0.6100116784541318,"acceleration":-0.45058533020046615,"pose":{"translation":{"x":0.7623531414880714,"y":-0.060779885976088806},"rotation":{"radians":-0.8652058620146231}},"curvature":-17.96874906670296},{"time":0.26523868990697563,"velocity":0.6078065924541121,"acceleration":2.838676367740909,"pose":{"translation":{"x":0.7642239033004439,"y":-0.0630993740545735},"rotation":{"radians":-0.9189918386699523}},"curvature":-18.043651975428034},{"time":0.26992376390329426,"velocity":0.6211060012885792,"acceleration":7.178619781995618,"pose":{"translation":{"x":0.7659105462490051,"y":-0.06543230585956386},"rotation":{"radians":-0.9704339975539432}},"curvature":-17.59996374149888},{"time":0.27431262644288845,"velocity":0.6526119767357696,"acceleration":13.64650641241847,"pose":{"translation":{"x":0.7674333184384092,"y":-0.06777616458747299},"rotation":{"radians":-1.0183938104212367}},"curvature":-16.62103997637882},{"time":0.27832284304939786,"velocity":0.7073374233716874,"acceleration":34.89941850575053,"pose":{"translation":{"x":0.7688126719111472,"y":-0.07012841291631304},"rotation":{"radians":-1.0618041901214113}},"curvature":-15.127955617832983},{"time":0.28478505274868793,"velocity":0.9328647841391318,"acceleration":90.0,"pose":{"translation":{"x":0.7712237657583411,"y":-0.0748478491990869},"rotation":{"radians":-1.1313409817992186}},"curvature":-10.823377339953991},{"time":0.2893249992112036,"velocity":1.3414599657655384,"acceleration":-12.80109227685977,"pose":{"translation":{"x":0.773310352440193,"y":-0.07957004954492501},"rotation":{"radians":-1.1733125860353835}},"curvature":-5.257202203461599},{"time":0.29717683547403406,"velocity":1.2409478852222515,"acceleration":-89.99999999999999,"pose":{"translation":{"x":0.7771815758973708,"y":-0.0889401721676204},"rotation":{"radians":-1.163264957282139}},"curvature":7.350827017612046},{"time":0.30216619678585166,"velocity":0.7919053671586695,"acceleration":-24.141277586135022,"pose":{"translation":{"x":0.7793017780441172,"y":-0.09354701774833644},"rotation":{"radians":-1.110693522282319}},"curvature":13.226515925286156},{"time":0.3094946108790295,"velocity":0.6149880882691183,"acceleration":-9.620813276102691,"pose":{"translation":{"x":0.7817666324891173,"y":-0.0980747161572421},"rotation":{"radians":-1.0298958907924822}},"curvature":17.801683098701417},{"time":0.31393884611835055,"velocity":0.572230930876535,"acceleration":-4.7603816460118065,"pose":{"translation":{"x":0.7831794119739595,"y":-0.1003026834761503},"rotation":{"radians":-0.9807744552003372}},"curvature":19.33188063472145},{"time":0.31874914858868675,"velocity":0.5493320552849812,"acceleration":-1.2913418998277,"pose":{"translation":{"x":0.7847392661164512,"y":-0.10250348233337975},"rotation":{"radians":-0.9272341292463634}},"curvature":20.249335257323747},{"time":0.32382953272793485,"velocity":0.54277154237875,"acceleration":1.5149005788220835,"pose":{"translation":{"x":0.786466009878046,"y":-0.10467472167606819},"rotation":{"radians":-0.8705182174463368}},"curvature":20.52645182383729},{"time":0.32907875805121695,"velocity":0.5507235968593576,"acceleration":4.073750284338515,"pose":{"translation":{"x":0.7883791693382243,"y":-0.1068140504723042},"rotation":{"radians":-0.8119439001422153}},"curvature":20.191405158997352},{"time":0.33439746652144214,"velocity":0.572390687002251,"acceleration":6.649928956638461,"pose":{"translation":{"x":0.790497950893253,"y":-0.10891916149483713},"rotation":{"radians":-0.752812046478218}},"curvature":19.32573777866687},{"time":0.3396952426045526,"velocity":0.6076205215831139,"acceleration":9.427672849021297,"pose":{"translation":{"x":0.7928412104549485,"y":-0.11098779510478617},"rotation":{"radians":-0.6943176112032055}},"curvature":18.049997349914722},{"time":0.34489622214377913,"velocity":0.6566536551733952,"acceleration":12.539605822155819,"pose":{"translation":{"x":0.7954274226494369,"y":-0.11301774303535},"rotation":{"radians":-0.6374776374807097}},"curvature":16.502258954130472},{"time":0.3499423658366993,"velocity":0.7199303080045716,"acceleration":16.074833656780893,"pose":{"translation":{"x":0.7982746500159175,"y":-0.11500685217551643},"rotation":{"radians":-0.5830880857863493}},"curvature":14.816508125515433},{"time":0.35479422130106963,"velocity":0.797923077521068,"acceleration":20.075938649280452,"pose":{"translation":{"x":0.8014005122054229,"y":-0.11695302835377154},"rotation":{"radians":-0.5317120677457426}},"curvature":13.106573265437618},{"time":0.3594296059890115,"velocity":0.8909827761320033,"acceleration":27.031632412604434,"pose":{"translation":{"x":0.8048221551795822,"y":-0.11885424012180959},"rotation":{"radians":-0.4836944624103153}},"curvature":11.458000905986898},{"time":0.3679857823054175,"velocity":1.122270189174522,"acceleration":37.07977099078728,"pose":{"translation":{"x":0.8126188140739359,"y":-0.12251398095230785},"rotation":{"radians":-0.39822174396935706}},"curvature":8.544856791374903},{"time":0.37572947667308,"velocity":1.4094046029500964,"acceleration":46.73052172232043,"pose":{"translation":{"x":0.8217911501568782,"y":-0.12597122132568533},"rotation":{"radians":-0.3264106097137632}},"curvature":6.258579822887073},{"time":0.38280764194463,"velocity":1.7401709589264391,"acceleration":53.99352163669088,"pose":{"translation":{"x":0.8324561365766101,"y":-0.12921235362935143},"rotation":{"radians":-0.2668026651980122}},"curvature":4.560060728416664},{"time":0.3893921871591751,"velocity":2.0956937434357488,"acceleration":57.338094099900296,"pose":{"translation":{"x":0.8447202105319951,"y":-0.13222513705815475},"rotation":{"radians":-0.2175490703860894}},"curvature":3.3322698227198093},{"time":0.3956474942524084,"velocity":2.4543611301713324,"acceleration":54.033889692800706,"pose":{"translation":{"x":0.8586782876329462,"y":-0.1349988186930875},"rotation":{"radians":-0.17684463619654262}},"curvature":2.454051863103874},{"time":0.40774888489087263,"velocity":3.1082463370595987,"acceleration":34.02353513583602,"pose":{"translation":{"x":0.891992591928696,"y":-0.13979403080824876},"rotation":{"radians":-0.11502534929420889}},"curvature":1.374547693200579},{"time":0.43313121668559906,"velocity":3.9718429947069205,"acceleration":13.958738672188188,"pose":{"translation":{"x":0.9816159890576985,"y":-0.14623559285438018},"rotation":{"radians":-0.04099530984338595}},"curvature":0.4935390755053831},{"time":0.46200601712802636,"velocity":4.374898788294347,"acceleration":7.038967811765633,"pose":{"translation":{"x":1.10209947920371,"y":-0.14852563235535807},"rotation":{"radians":-0.0026781264287293605}},"curvature":0.20140528611573624},{"time":0.47796725967000164,"velocity":4.4872494607830955,"acceleration":4.899081715135554,"pose":{"translation":{"x":1.172824497414727,"y":-0.14827883223553354},"rotation":{"radians":0.008812928858250024}},"curvature":0.1293270485402829},{"time":0.4948444972765215,"velocity":4.569932426943195,"acceleration":-36.8359231286635,"pose":{"translation":{"x":1.2492480968879178,"y":-0.14728160993700762},"rotation":{"radians":0.016639141473716066}},"curvature":0.07854587156191066},{"time":0.5139714587263028,"velocity":3.8653731452941438,"acceleration":-90.0,"pose":{"translation":{"x":1.3299040512445215,"y":-0.14572974989123033},"rotation":{"radians":0.02129758319027541}},"curvature":0.03825258696437647},{"time":0.5569200492295711,"velocity":0.0,"acceleration":-90.0,"pose":{"translation":{"x":1.4128894649391648,"y":-0.14387383885613683},"rotation":{"radians":0.022896761221383708}},"curvature":-8.845744847864971E-16}] \ No newline at end of file From 874769d2ff7b4a7fbd78a1827b5558fd1cb4c875 Mon Sep 17 00:00:00 2001 From: CORE Programmers Date: Tue, 3 Mar 2020 20:39:28 -0600 Subject: [PATCH 21/31] added two test paths --- PathWeaver/Groups/Unnamed | 0 PathWeaver/Paths/foreward.path | 3 +++ PathWeaver/Paths/right.path | 3 +++ PathWeaver/output/foreward.wpilib.json | 1 + PathWeaver/output/right.wpilib.json | 1 + src/Robot.cpp | 4 ++-- src/main/deploy/paths/foreward.wpilib.json | 1 + src/main/deploy/paths/right.wpilib.json | 1 + 8 files changed, 12 insertions(+), 2 deletions(-) create mode 100644 PathWeaver/Groups/Unnamed create mode 100644 PathWeaver/Paths/foreward.path create mode 100644 PathWeaver/Paths/right.path create mode 100644 PathWeaver/output/foreward.wpilib.json create mode 100644 PathWeaver/output/right.wpilib.json create mode 100644 src/main/deploy/paths/foreward.wpilib.json create mode 100644 src/main/deploy/paths/right.wpilib.json diff --git a/PathWeaver/Groups/Unnamed b/PathWeaver/Groups/Unnamed new file mode 100644 index 0000000..e69de29 diff --git a/PathWeaver/Paths/foreward.path b/PathWeaver/Paths/foreward.path new file mode 100644 index 0000000..e6295be --- /dev/null +++ b/PathWeaver/Paths/foreward.path @@ -0,0 +1,3 @@ +X,Y,Tangent X,Tangent Y,Fixed Theta,Name +3.139010635462718,-0.7857308912612436,3.048,0.0,true, +3.707905208015698,-0.7857308912612436,0.44522183938928794,-0.01236727331636922,true, diff --git a/PathWeaver/Paths/right.path b/PathWeaver/Paths/right.path new file mode 100644 index 0000000..cc83250 --- /dev/null +++ b/PathWeaver/Paths/right.path @@ -0,0 +1,3 @@ +X,Y,Tangent X,Tangent Y,Fixed Theta,Name +3.1884797287281947,-1.11964727080321,0.828607312196731,-0.01236727331636911,true, +3.4729270150046854,-1.552501836876129,0.03710181994910755,-0.9893818653095297,true, diff --git a/PathWeaver/output/foreward.wpilib.json b/PathWeaver/output/foreward.wpilib.json new file mode 100644 index 0000000..2d6b65f --- /dev/null +++ b/PathWeaver/output/foreward.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":90.00000000000001,"pose":{"translation":{"x":3.139010635462718,"y":-0.7857308912612436},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.045905467332406524,"velocity":4.131492059916588,"acceleration":27.195128294263547,"pose":{"translation":{"x":3.2338396723472616,"y":-0.7857294630390612},"rotation":{"radians":4.472450891313205E-5}},"curvature":9.276662745827367E-4},{"time":0.06683848129466095,"velocity":4.700768060205707,"acceleration":-0.09998687667157592,"pose":{"translation":{"x":3.3262825840794297,"y":-0.7857200994301465},"rotation":{"radians":1.7187578139907824E-4}},"curvature":0.00184078824601756},{"time":0.0855717783283503,"velocity":4.698894976345548,"acceleration":-0.14268613573850739,"pose":{"translation":{"x":3.4143259207697856,"y":-0.785696548691362},"rotation":{"radians":3.7871150569400913E-4}},"curvature":0.0029087836087896765},{"time":0.10303027644826515,"velocity":4.696403890713019,"acceleration":-0.22947015915521518,"pose":{"translation":{"x":3.496339813678259,"y":-0.7856542751576296},"rotation":{"radians":6.715026130162066E-4}},"curvature":0.004330471244214398},{"time":0.11894500173982889,"velocity":4.692751936167452,"acceleration":-0.41037597991465935,"pose":{"translation":{"x":3.571052704162918,"y":-0.7855903265554834},"rotation":{"radians":0.0010661429050122817}},"curvature":0.006417406777249305},{"time":0.13311891263114356,"velocity":4.686935303596206,"acceleration":-11.869177951857159,"pose":{"translation":{"x":3.637526072628745,"y":-0.7855032013166211},"rotation":{"radians":0.0015917497098839673}},"curvature":0.00974807812854124},{"time":0.15641985975591766,"velocity":4.410372215725448,"acceleration":-90.0,"pose":{"translation":{"x":3.743513734051032,"y":-0.785259872062671},"rotation":{"radians":0.003280034069158219}},"curvature":0.02666464595429507},{"time":0.19467354647582824,"velocity":0.9675404109334969,"acceleration":-90.0,"pose":{"translation":{"x":3.846373838709148,"y":-0.7845590045532563},"rotation":{"radians":0.022126764220783735}},"curvature":2.198058466233127},{"time":0.19927135599596166,"velocity":0.5537375541214894,"acceleration":-90.0,"pose":{"translation":{"x":3.849869724361052,"y":-0.7844605005876413},"rotation":{"radians":0.03833865663750966}},"curvature":10.474757649183204},{"time":0.20495391513957345,"velocity":0.042307231196426986,"acceleration":-8.127146835406759,"pose":{"translation":{"x":3.8515603635657674,"y":-0.7843615940246216},"rotation":{"radians":0.1196146774409119}},"curvature":295.0111549349735},{"time":0.20795929102031324,"velocity":0.01788210011806468,"acceleration":-2.2566117440366193,"pose":{"translation":{"x":3.8516499610931474,"y":-0.7843492359250838},"rotation":{"radians":0.16035705492601032}},"curvature":701.6234289290957},{"time":0.21350091850489672,"velocity":0.005376798455277498,"acceleration":-0.5161959577287843,"pose":{"translation":{"x":3.85171321228033,"y":-0.7843368834352253},"rotation":{"radians":0.2414428298028381}},"curvature":2339.678881887571},{"time":0.21937153885525884,"velocity":0.002346407961060226,"acceleration":-0.19460981444752634,"pose":{"translation":{"x":3.8517350254497353,"y":-0.7843307097143288},"rotation":{"radians":0.3211437117992815}},"curvature":5364.836593712613},{"time":0.22416410434184642,"velocity":0.0014137276809877974,"acceleration":-0.10971500188325159,"pose":{"translation":{"x":3.8517434907918204,"y":-0.7843276235585984},"rotation":{"radians":0.3832734005167584}},"curvature":8905.95310437488},{"time":0.22734195905319637,"velocity":0.0010650693453473359,"acceleration":-0.0727477770700109,"pose":{"translation":{"x":3.851747114640129,"y":-0.7843260806661382},"rotation":{"radians":0.4236619192568799}},"curvature":11822.259248902921},{"time":0.23120192670179074,"velocity":7.842652793499383E-4,"acceleration":-0.04637785712254716,"pose":{"translation":{"x":3.85175033317445,"y":-0.7843245379007978},"rotation":{"radians":0.4728070591402796}},"curvature":16056.145883841957},{"time":0.23596386572974987,"velocity":5.634167514849686E-4,"acceleration":-0.028254089132246654,"pose":{"translation":{"x":3.851753146821129,"y":-0.7843229952652162},"rotation":{"radians":0.5335669095761805}},"curvature":22350.895670489415},{"time":0.24193534255630544,"velocity":3.946981129763216E-4,"acceleration":-0.018597081133462527,"pose":{"translation":{"x":3.8517555560068883,"y":-0.7843214527620327},"rotation":{"radians":0.6099555380362651}},"curvature":31906.209684548245},{"time":0.24555012856181768,"velocity":3.2747364435170567E-4,"acceleration":-0.013923451531174818,"pose":{"translation":{"x":3.851756609060377,"y":-0.7843206815609153},"rotation":{"radians":0.6556822748781164}},"curvature":38456.53217320645},{"time":0.24964870575195625,"velocity":2.7040730349803255E-4,"acceleration":-0.010266037461806347,"pose":{"translation":{"x":3.8517575611588266,"y":-0.7843199103938877},"rotation":{"radians":0.707549023262855}},"curvature":46572.90452235532},{"time":0.25430836811721375,"velocity":2.225710350969301E-4,"acceleration":-0.007447854773923607,"pose":{"translation":{"x":3.851758412355683,"y":-0.78431913926128},"rotation":{"radians":0.7665385217845972}},"curvature":56583.200946092846},{"time":0.25961330519829917,"velocity":1.8306063413220386E-4,"acceleration":-0.005310880986123949,"pose":{"translation":{"x":3.851759162704415,"y":-0.7843183681634225},"rotation":{"radians":0.8337199791554958}},"curvature":68796.26221980967},{"time":0.265649226031357,"velocity":1.5100457694616765E-4,"acceleration":-0.003715644413520527,"pose":{"translation":{"x":3.851759812258515,"y":-0.7843175971006454},"rotation":{"radians":0.9101792815294496}},"curvature":83401.26815160742},{"time":0.27249281850722773,"velocity":1.2557622079478747E-4,"acceleration":-0.002785680869218963,"pose":{"translation":{"x":3.8517603610714986,"y":-0.7843168260732791},"rotation":{"radians":0.9968831256542522}},"curvature":100290.01681613881},{"time":0.2762516442382699,"velocity":1.151053318650952E-4,"acceleration":-0.002286903550375423,"pose":{"translation":{"x":3.851760597716802,"y":-0.7843164405729783},"rotation":{"radians":1.0442929283243139}},"curvature":109413.43138273002},{"time":0.280228659762849,"velocity":1.0601028094203713E-4,"acceleration":-0.0018606440283870252,"pose":{"translation":{"x":3.8517608091969047,"y":-0.784316055081654},"rotation":{"radians":1.0944542917281388}},"curvature":118800.68205404523},{"time":0.2844217109426492,"velocity":9.82085053036208E-5,"acceleration":-0.001495791047417784,"pose":{"translation":{"x":3.8517609955185033,"y":-0.7843156695993477},"rotation":{"radians":1.1473394272597957}},"curvature":128238.53219189229},{"time":0.28882358803320074,"velocity":9.162421695974032E-5,"acceleration":-0.0011821104669365744,"pose":{"translation":{"x":3.8517611566882954,"y":-0.7843152841261006},"rotation":{"radians":1.202856764228224}},"curvature":137454.18640884254},{"time":0.2934212216558681,"velocity":8.618930613124576E-5,"acceleration":-9.10166127726058E-4,"pose":{"translation":{"x":3.85176129271298,"y":-0.784314898661954},"rotation":{"radians":1.2608408975754095}},"curvature":146121.91830028637},{"time":0.2981951210387533,"velocity":8.184426461577132E-5,"acceleration":-6.712272375217975E-4,"pose":{"translation":{"x":3.851761403599256,"y":-0.7843145132069492},"rotation":{"radians":1.321045608746215}},"curvature":153879.54722685105},{"time":0.30311919829406525,"velocity":7.853908984234437E-5,"acceleration":-4.571620226274313E-4,"pose":{"translation":{"x":3.8517614893538275,"y":-0.7843141277611276},"rotation":{"radians":1.3831417521306877}},"curvature":160355.40081599023},{"time":0.3081611044594174,"velocity":7.623412182189426E-5,"acceleration":-2.6031820552800797E-4,"pose":{"translation":{"x":3.8517615499833955,"y":-0.7843137423245305},"rotation":{"radians":1.4467215645907465}},"curvature":165203.8890423113},{"time":0.31328314882614516,"velocity":7.490076042371285E-5,"acceleration":-7.339189251839403E-5,"pose":{"translation":{"x":3.8517615854946663,"y":-0.7843133568971993},"rotation":{"radians":1.511310270848789}},"curvature":168144.84794743382},{"time":0.3184437853205848,"velocity":7.452201154478644E-5,"acceleration":1.1071256075514668E-4,"pose":{"translation":{"x":3.8517615958943456,"y":-0.7843129714791752},"rotation":{"radians":1.576384764438419}},"curvature":168999.43688464654},{"time":0.32359954574379013,"velocity":7.509281898387954E-5,"acceleration":2.9902823420181046E-4,"pose":{"translation":{"x":3.8517615811891406,"y":-0.7843125860704996},"rotation":{"radians":1.6413978538853173}},"curvature":167714.79122347364},{"time":0.3287072071253734,"velocity":7.662015394771515E-5,"acceleration":4.986728239771152E-4,"pose":{"translation":{"x":3.851761541385761,"y":-0.7843122006712138},"rotation":{"radians":1.705805421556595}},"curvature":164371.53568921657},{"time":0.33372592880360563,"velocity":7.912285405975439E-5,"acceleration":7.169930956469593E-4,"pose":{"translation":{"x":3.8517614764909163,"y":-0.7843118152813591},"rotation":{"radians":1.7690932057110025}},"curvature":159172.28742679203},{"time":0.3386191016076256,"velocity":8.263122517604415E-5,"acceleration":9.6170265634419E-4,"pose":{"translation":{"x":3.8517613865113196,"y":-0.7843114299009769},"rotation":{"radians":1.8308000000964084}},"curvature":152414.00872744145},{"time":0.3433557144775732,"velocity":8.718643835514683E-5,"acceleration":0.0012410097888180393,"pose":{"translation":{"x":3.8517612714536833,"y":-0.7843110445301086},"rotation":{"radians":1.890534841060949}},"curvature":144450.7232629091},{"time":0.3479111415612719,"velocity":9.283976795826376E-5,"acceleration":0.0015637330056986363,"pose":{"translation":{"x":3.8517611313247224,"y":-0.7843106591687955},"rotation":{"radians":1.9479869603310134}},"curvature":135654.46381497147},{"time":0.35226735542574256,"velocity":9.965172335801853E-5,"acceleration":0.0019394030257907226,"pose":{"translation":{"x":3.851760966131154,"y":-0.784310273817079},"rotation":{"radians":2.002928554249174}},"curvature":126381.26346919124},{"time":0.3564126531460586,"velocity":1.0769112629960276E-4,"acceleration":0.0023783508195431846,"pose":{"translation":{"x":3.8517607758796952,"y":-0.7843098884750003},"rotation":{"radians":2.055211434485014}},"curvature":116946.39672905911},{"time":0.3603410280695216,"velocity":1.1703418001829391E-4,"acceleration":0.002891782198748304,"pose":{"translation":{"x":3.8517605605770644,"y":-0.7843095031426008},"rotation":{"radians":2.1047592075597557}},"curvature":107610.1371716676},{"time":0.36405133066867124,"velocity":1.2776356702648428E-4,"acceleration":0.003848012966735964,"pose":{"translation":{"x":3.851760320229983,"y":-0.7843091178199221},"rotation":{"radians":2.151556773972847}},"curvature":98572.9792302838},{"time":0.37080179898796,"velocity":1.537394566506478E-4,"acceleration":0.0054853422673589725,"pose":{"translation":{"x":3.8517597644293584,"y":-0.784308347203892},"rotation":{"radians":2.237078051694726}},"curvature":81917.59074766494},{"time":0.3767522112706826,"velocity":1.863795046532779E-4,"acceleration":0.007673363168733599,"pose":{"translation":{"x":3.8517591085316134,"y":-0.7843075766272408},"rotation":{"radians":2.3124505674602815}},"curvature":67571.15555938672},{"time":0.3819809888013117,"velocity":2.265018135743091E-4,"acceleration":0.010551505145509992,"pose":{"translation":{"x":3.851758352590565,"y":-0.7843068060902996},"rotation":{"radians":2.3786636796836915}},"curvature":55601.19312404653},{"time":0.3865740802430194,"velocity":2.749658415552858E-4,"acceleration":0.014277276894402814,"pose":{"translation":{"x":3.8517574966600527,"y":-0.7843060355933994},"rotation":{"radians":2.4368067087778296}},"curvature":45800.74838319005},{"time":0.3906150983009136,"velocity":3.326605753031231E-4,"acceleration":0.019026589999720272,"pose":{"translation":{"x":3.8517565407939385,"y":-0.7843052651368713},"rotation":{"radians":2.4879417118598544}},"curvature":37856.86608960236},{"time":0.39418039364393004,"velocity":4.004959880226089E-4,"acceleration":0.028806945377216234,"pose":{"translation":{"x":3.851755485046108,"y":-0.7843044947210466},"rotation":{"radians":2.533039486043962}},"curvature":31444.27312193421},{"time":0.4000749011410937,"velocity":5.702987435189932E-4,"acceleration":0.047096725612869775,"pose":{"translation":{"x":3.8517530741209534,"y":-0.7843029540128321},"rotation":{"radians":2.608425718386986}},"curvature":22081.147379110564},{"time":0.40477973447678156,"velocity":7.918809881841682E-4,"acceleration":0.07360485766036914,"pose":{"translation":{"x":3.851750264316128,"y":-0.7843014134714063},"rotation":{"radians":2.668444494668615}},"curvature":15901.704340218665},{"time":0.40859680737008547,"velocity":0.001072836095175056,"acceleration":0.13685645112569875,"pose":{"translation":{"x":3.851747056063539,"y":-0.7842998730994203},"rotation":{"radians":2.7170348240218822}},"curvature":11736.653139162667},{"time":0.41422725430777096,"velocity":0.0018433990813182533,"acceleration":0.2713001524578744,"pose":{"translation":{"x":3.851739445944512,"y":-0.7842967928743765},"rotation":{"radians":2.7903532377332416}},"curvature":6829.471797427922},{"time":0.41828056430806565,"velocity":0.0029430627023572242,"acceleration":0.6668320341133934,"pose":{"translation":{"x":3.8517302472263966,"y":-0.7842937133589265},"rotation":{"radians":2.842660925553188}},"curvature":4276.666553522217},{"time":0.4234233959707022,"velocity":0.00637246760105592,"acceleration":2.6520405677717576,"pose":{"translation":{"x":3.8517070978719796,"y":-0.7842875565417728},"rotation":{"radians":2.911776236578576}},"curvature":1973.6963456742196},{"time":0.42849167787478654,"velocity":0.019813756819591077,"acceleration":8.984499789449828,"pose":{"translation":{"x":3.8516418889660993,"y":-0.7842752523579086},"rotation":{"radians":2.9847439440369117}},"curvature":632.960661819855},{"time":0.4312999297154105,"velocity":0.045044494890398745,"acceleration":90.00000000000135,"pose":{"translation":{"x":3.851551652967633,"y":-0.7842629619106193},"rotation":{"radians":3.0225269883003785}},"curvature":276.9212194102955},{"time":0.4367805579926848,"velocity":0.5383010398450934,"acceleration":90.00000000000024,"pose":{"translation":{"x":3.8499560891851043,"y":-0.7841652973250023},"rotation":{"radians":3.1003621440525393}},"curvature":11.247397230772256},{"time":0.4526205753393156,"velocity":1.9639026010418699,"acceleration":79.23256726649373,"pose":{"translation":{"x":3.8301420093346312,"y":-0.7837985048055609},"rotation":{"radians":3.12987179235241}},"curvature":0.30176263979709583},{"time":0.47831107663860617,"velocity":3.9994269733478567,"acceleration":-90.0,"pose":{"translation":{"x":3.753543010707668,"y":-0.7833248436723809},"rotation":{"radians":3.139009364028352}},"curvature":0.08388935629985557},{"time":0.5026122678124995,"velocity":1.8123197676974647,"acceleration":-90.0,"pose":{"translation":{"x":3.682926934250862,"y":-0.7834482597604684},"rotation":{"radians":-3.1315650187328625}},"curvature":0.5631600111545465},{"time":0.5167297737975327,"velocity":0.5417442290444762,"acceleration":-89.99999999999999,"pose":{"translation":{"x":3.6663136407505825,"y":-0.7837874770874453},"rotation":{"radians":-3.090212871797444}},"curvature":14.864983247841876},{"time":0.5216308885734858,"velocity":0.1006438992086931,"acceleration":-18.285644081758157,"pose":{"translation":{"x":3.664743548466244,"y":-0.7839012492780149},"rotation":{"radians":-3.026923077458199}},"curvature":122.46063625724759},{"time":0.5248130561893707,"velocity":0.04245591477612631,"acceleration":-5.079855903164719,"pose":{"translation":{"x":3.6645178740505915,"y":-0.78393143154953},"rotation":{"radians":-2.9841564085591434}},"curvature":293.9686289012376},{"time":0.5306978787418675,"velocity":0.012561864193748828,"acceleration":-1.136261554420965,"pose":{"translation":{"x":3.6643589588878283,"y":-0.7839622974312198},"rotation":{"radians":-2.897999549537208}},"curvature":999.9108795039187},{"time":0.5370114486552923,"velocity":0.005387997429975311,"acceleration":-0.4179967389832239,"pose":{"translation":{"x":3.6643045097969607,"y":-0.7839779846475876},"rotation":{"radians":-2.812094624008948}},"curvature":2334.810284823715},{"time":0.5422281045702659,"velocity":0.0032074522691187823,"acceleration":-0.23167458609594105,"pose":{"translation":{"x":3.664283530573952,"y":-0.7839858914466122},"rotation":{"radians":-2.7443971830752876}},"curvature":3923.921199058397},{"time":0.545713370900079,"velocity":0.002400004634725228,"acceleration":-0.15167513899624624,"pose":{"translation":{"x":3.664274601253251,"y":-0.7839898605953501},"rotation":{"radians":-2.700093036206735}},"curvature":5244.969785760789},{"time":0.5499669229800531,"velocity":0.0017548465317673845,"acceleration":-0.09530454440799681,"pose":{"translation":{"x":3.6642667116915404,"y":-0.7839938402248509},"rotation":{"radians":-2.6459158437811636}},"curvature":7174.233699553927},{"time":0.5552392451789496,"velocity":0.0012523702666293879,"acceleration":-0.0571248666593388,"pose":{"translation":{"x":3.664259861544444,"y":-0.7839978303209554},"rotation":{"radians":-2.5786064876297368}},"curvature":10053.755490079226},{"time":0.5618776166314029,"velocity":8.731541825728328E-4,"acceleration":-0.037075936236512286,"pose":{"translation":{"x":3.6642540504529824,"y":-0.7840018308694107},"rotation":{"radians":-2.4936310429428614}},"curvature":14421.324434057353},{"time":0.5659061722638513,"velocity":7.237917108189329E-4,"acceleration":-0.027502999859915958,"pose":{"translation":{"x":3.6642515344369304,"y":-0.7840038350587898},"rotation":{"radians":-2.4426654722113676}},"curvature":17397.877675491844},{"time":0.5704747738133626,"velocity":5.981414630427118E-4,"acceleration":-0.02008660417028765,"pose":{"translation":{"x":3.664249278043539,"y":-0.7840058418558689},"rotation":{"radians":-2.3848460492049255}},"curvature":21053.173602567214},{"time":0.5756627783247271,"velocity":4.939320699892669E-4,"acceleration":-0.014428933678911236,"pose":{"translation":{"x":3.664247281223815,"y":-0.7840078512588396},"rotation":{"radians":-2.3191652793679616}},"curvature":25495.520200497296},{"time":0.5815510410174265,"velocity":4.0897071811230035E-4,"acceleration":-0.010177654461040827,"pose":{"translation":{"x":3.6642455439278514,"y":-0.7840098632658877},"rotation":{"radians":-2.2445989524060472}},"curvature":30792.62642496039},{"time":0.5882124915045547,"velocity":3.4117277684497793E-4,"acceleration":-0.007684857175444079,"pose":{"translation":{"x":3.664244066104822,"y":-0.7840118778751932},"rotation":{"radians":-2.1602275254132213}},"curvature":36912.27705396234},{"time":0.5918657809626717,"velocity":3.130977691387926E-4,"acceleration":-0.006341371622965841,"pose":{"translation":{"x":3.664243424479521,"y":-0.784012886155122},"rotation":{"radians":-2.1141536010910844}},"curvature":40222.385691758725},{"time":0.595728699315394,"velocity":2.886015683150056E-4,"acceleration":-0.0051895547426711475,"pose":{"translation":{"x":3.66424284770298,"y":-0.7840138950849299},"rotation":{"radians":-2.0654360692729696}},"curvature":43636.64719014187},{"time":0.5997999376418786,"velocity":2.6747365414925284E-4,"acceleration":-0.004200976959185473,"pose":{"translation":{"x":3.6642423357685834,"y":-0.7840149046643877},"rotation":{"radians":-2.014091993385154}},"curvature":47083.74521032249},{"time":0.6040736636067117,"velocity":2.495198298411161E-4,"acceleration":-0.0033494017791718795,"pose":{"translation":{"x":3.664241888669662,"y":-0.7840159148932658},"rotation":{"radians":-1.960195513097017}},"curvature":50471.77797306924},{"time":0.6085387657197628,"velocity":2.345644088794785E-4,"acceleration":-0.0026106014500051665,"pose":{"translation":{"x":3.6642415063994904,"y":-0.7840169257713344},"rotation":{"radians":-1.903887302809682}},"curvature":53689.94193568191},{"time":0.6131782877796909,"velocity":2.2245246586249934E-4,"acceleration":-0.0019621406023246023,"pose":{"translation":{"x":3.6642411889512845,"y":-0.7840179372983631},"rotation":{"radians":-1.845381614079129}},"curvature":56613.36174570438},{"time":0.6179691785615897,"velocity":2.1305206453803294E-4,"acceleration":-0.0013831269084034143,"pose":{"translation":{"x":3.664240936318199,"y":-0.7840189494741213},"rotation":{"radians":-1.7849693402812188}},"curvature":59111.40601644545},{"time":0.6228824726415442,"velocity":2.062563552871488E-4,"acceleration":-8.539295658283349E-4,"pose":{"translation":{"x":3.6642407484933393,"y":-0.7840199622983779},"rotation":{"radians":-1.7230156647909987}},"curvature":61059.08962979245},{"time":0.6278839795131077,"velocity":2.0198542069582714E-4,"acceleration":-3.558686872510841E-4,"pose":{"translation":{"x":3.6642406254697457,"y":-0.7840209757709015},"rotation":{"radians":-1.6599513449563343}},"curvature":62350.22644543778},{"time":0.632935489603655,"velocity":2.0018774643126847E-4,"acceleration":1.2911906951840844E-4,"pose":{"translation":{"x":3.6642405672404004,"y":-0.7840219898914603},"rotation":{"radians":-1.596257540031257}},"curvature":62910.1518782517},{"time":0.6379964186853384,"velocity":2.0084120888519408E-4,"acceleration":6.18831061022732E-4,"pose":{"translation":{"x":3.6642405737982373,"y":-0.7840230046598221},"rotation":{"radians":-1.5324451743856793}},"curvature":62705.45697503062},{"time":0.643025727310457,"velocity":2.0395350127788703E-4,"acceleration":0.0011311562519046234,"pose":{"translation":{"x":3.66424064513612,"y":-0.7840240200757546},"rotation":{"radians":-1.4690308768217482}},"curvature":61748.5425396905},{"time":0.6479838942802174,"velocity":2.0956196284371842E-4,"acceleration":0.001684429966211262,"pose":{"translation":{"x":3.6642407812468636,"y":-0.7840250361390245},"rotation":{"radians":-1.4065122474002567}},"curvature":60095.90797371259},{"time":0.6528347115222313,"velocity":2.177328247667809E-4,"acceleration":0.0022977761940409028,"pose":{"translation":{"x":3.6642409821232236,"y":-0.7840260528493989},"rotation":{"radians":-1.3453453471872574}},"curvature":57840.58775178996},{"time":0.6575467058635939,"velocity":2.2855993319081946E-4,"acceleration":0.0029914290874418414,"pose":{"translation":{"x":3.664241247757894,"y":-0.784027070206644},"rotation":{"radians":-1.2859268358224432}},"curvature":55100.495495029645},{"time":0.6620940685609409,"velocity":2.4216304623481122E-4,"acceleration":0.003787027260522827,"pose":{"translation":{"x":3.6642415781435136,"y":-0.7840280882105256},"rotation":{"radians":-1.2285822511589828}},"curvature":52005.1648849209},{"time":0.6664570625918498,"velocity":2.586858235673617E-4,"acceleration":0.00470787682533917,"pose":{"translation":{"x":3.664241973272665,"y":-0.7840291068608096},"rotation":{"radians":-1.1735608198435061}},"curvature":48683.32070577291},{"time":0.6706219567904208,"velocity":2.7829363244480376E-4,"acceleration":0.005779181372427527,"pose":{"translation":{"x":3.664242433137871,"y":-0.7840301261572612},"rotation":{"radians":-1.1210362023448242}},"curvature":45253.038320252315},{"time":0.6745805889128479,"velocity":3.0117128546702787E-4,"acceleration":0.0070282391438150306,"pose":{"translation":{"x":3.6642429577315947,"y":-0.7840311460996451},"rotation":{"radians":-1.071111909998547}},"curvature":41815.31164797268},{"time":0.6783296818167085,"velocity":3.2752080696774044E-4,"acceleration":0.009347232409719361,"pose":{"translation":{"x":3.6642435470462438,"y":-0.7840321666877259},"rotation":{"radians":-1.023829847210145}},"curvature":38450.994091695226},{"time":0.6851762185220589,"velocity":3.9151697675432473E-4,"acceleration":0.013309959262423975,"pose":{"translation":{"x":3.6642449198076688,"y":-0.784034209800034},"rotation":{"radians":-0.9371133455817752}},"curvature":32165.474346036655},{"time":0.6912354885212121,"velocity":4.721656136030816E-4,"acceleration":0.01859916953103669,"pose":{"translation":{"x":3.6642465513602387,"y":-0.7840362554922942},"rotation":{"radians":-0.8603784380556495}},"curvature":26670.96667412578},{"time":0.6965766580858223,"velocity":5.715069318292798E-4,"acceleration":0.025554930558089585,"pose":{"translation":{"x":3.6642484416411296,"y":-0.7840383037626087},"rotation":{"radians":-0.7927545034206182}},"curvature":22034.461298123704},{"time":0.7012798021122773,"velocity":6.916954508300321E-4,"acceleration":0.03456200109704326,"pose":{"translation":{"x":3.6642505905865863,"y":-0.7840403546090741},"rotation":{"radians":-0.7332279992817718}},"curvature":18205.30345546575},{"time":0.7054251849883204,"velocity":8.349681783395013E-4,"acceleration":0.04605075448824015,"pose":{"translation":{"x":3.664252998131924,"y":-0.7840424080297809},"rotation":{"radians":-0.6807803050322688}},"curvature":15080.98429712439},{"time":0.709087516607084,"velocity":0.0010036213125697024,"acceleration":0.060497699784128105,"pose":{"translation":{"x":3.6642556642115274,"y":-0.7840444640228134},"rotation":{"radians":-0.6344620841273695}},"curvature":12546.25652180786},{"time":0.7123334591235545,"velocity":0.0011999933684476716,"acceleration":0.08973893268059224,"pose":{"translation":{"x":3.6642585887588566,"y":-0.7840465225862501},"rotation":{"radians":-0.5934258312593568}},"curvature":10492.695216036627},{"time":0.7177424455119071,"velocity":0.0016853900338222871,"acceleration":0.14346871101279474,"pose":{"translation":{"x":3.664265212985841,"y":-0.7840506474166204},"rotation":{"radians":-0.5243539886762357}},"curvature":7470.0009103366765},{"time":0.7220983425082198,"velocity":0.0023103249611877708,"acceleration":0.2199896007776265,"pose":{"translation":{"x":3.6642728702618883,"y":-0.7840547825053997},"rotation":{"radians":-0.4688611177052537}},"curvature":5448.667227562127},{"time":0.7256612751581851,"velocity":0.0030941330924512123,"acceleration":0.39890363017732156,"pose":{"translation":{"x":3.66428156002107,"y":-0.7840589278369995},"rotation":{"radians":-0.42356138240863994}},"curvature":4067.728496402634},{"time":0.7309803671972144,"velocity":0.005215938216067251,"acceleration":0.7722458693560452,"pose":{"translation":{"x":3.6643020346503,"y":-0.7840672491658256},"rotation":{"radians":-0.354501339492932}},"curvature":2411.91746531754},{"time":0.7348517474597189,"velocity":0.008205595632492901,"acceleration":1.8447752321181765,"pose":{"translation":{"x":3.6643266320465147,"y":-0.7840756112764639},"rotation":{"radians":-0.3046648486200171}},"curvature":1532.1749458426339},{"time":0.7398356061397846,"velocity":0.017399694685855227,"acceleration":7.056637039709774,"pose":{"translation":{"x":3.664388174628757,"y":-0.7840924573288989},"rotation":{"radians":-0.23803357831171906}},"curvature":721.1501241053157},{"time":0.7448445046474885,"velocity":0.0527456734234657,"acceleration":23.058879876892238,"pose":{"translation":{"x":3.6645604938242413,"y":-0.7841266330714044},"rotation":{"radians":-0.16667529316278054}},"curvature":236.0981800515628},{"time":0.7476622675500084,"velocity":0.11772012971423518,"acceleration":90.00000000000266,"pose":{"translation":{"x":3.664798123348533,"y":-0.7841614464118355},"rotation":{"radians":-0.1293160268301575}},"curvature":104.30838353357605},{"time":0.7524591472815689,"velocity":0.549439305554697,"acceleration":-3.6338253928342263,"pose":{"translation":{"x":3.666391641573475,"y":-0.7843068885078666},"rotation":{"radians":-0.07143425703513524}},"curvature":13.956021152155188},{"time":0.9036604974174812,"velocity":0.0,"acceleration":-3.6338253928342263,"pose":{"translation":{"x":3.707905208015694,"y":-0.7857308912612436},"rotation":{"radians":-0.027770636593421678}},"curvature":-3.978252216468362E-15}] \ No newline at end of file diff --git a/PathWeaver/output/right.wpilib.json b/PathWeaver/output/right.wpilib.json new file mode 100644 index 0000000..dd3d114 --- /dev/null +++ b/PathWeaver/output/right.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":71.89737745448778,"pose":{"translation":{"x":3.1884797287281947,"y":-1.11964727080321},"rotation":{"radians":-0.014924264990084975}},"curvature":0.0},{"time":0.05268142631895732,"velocity":3.7876563928948612,"acceleration":-59.21877194518338,"pose":{"translation":{"x":3.288224082733628,"y":-1.1218902732848743},"rotation":{"radians":-0.0403604301267946}},"curvature":-0.6477347161258742},{"time":0.065514378921308,"velocity":3.027704699352909,"acceleration":-60.80332122104294,"pose":{"translation":{"x":3.331877617444612,"y":-1.1244853725247268},"rotation":{"radians":-0.08438803131334119}},"curvature":-1.4823351481606475},{"time":0.08017189482943719,"velocity":2.1364790512883824,"acceleration":-49.06001447129655,"pose":{"translation":{"x":3.3694477203028774,"y":-1.129055577359315},"rotation":{"radians":-0.16848946991993805}},"curvature":-3.217545897949398},{"time":0.088805972713633,"velocity":1.7128910653434348,"acceleration":-36.874935338028024,"pose":{"translation":{"x":3.3857381692078086,"y":-1.1323381424087688},"rotation":{"radians":-0.23321582313921457}},"curvature":-4.67532579835257},{"time":0.09870430596676388,"velocity":1.347890666679981,"acceleration":-27.52374540467266,"pose":{"translation":{"x":3.4003246705429637,"y":-1.1364253836844578},"rotation":{"radians":-0.31820697087304906}},"curvature":-6.666391703427893},{"time":0.1042636529843187,"velocity":1.194876614752576,"acceleration":-21.87942884039311,"pose":{"translation":{"x":3.406980716935266,"y":-1.138803315325991},"rotation":{"radians":-0.36945663667725215}},"curvature":-7.862940171392727},{"time":0.11025203226317788,"velocity":1.0638542964514919,"acceleration":-16.847469869568364,"pose":{"translation":{"x":3.413216547742749,"y":-1.1414212366924745},"rotation":{"radians":-0.4269562853680734}},"curvature":-9.161065946190682},{"time":0.11668007251373871,"velocity":0.9555580820097955,"acceleration":-12.47056095030327,"pose":{"translation":{"x":3.419037704283193,"y":-1.144291749610191},"rotation":{"radians":-0.4907496613456893}},"curvature":-10.50275149137545},{"time":0.12353356839552536,"velocity":0.8700911438933228,"acceleration":-8.702140600437376,"pose":{"translation":{"x":3.4244512891515826,"y":-1.1474272131997965},"rotation":{"radians":-0.5605494558412518}},"curvature":-11.797403394481876},{"time":0.13076635109573062,"velocity":0.8071504519037256,"acceleration":-5.428847799907451,"pose":{"translation":{"x":3.429465866705271,"y":-1.150839698265352},"rotation":{"radians":-0.6356493581978337}},"curvature":-12.92613056067708},{"time":0.1382965103849562,"velocity":0.7662703632134606,"acceleration":-2.4925525256649843,"pose":{"translation":{"x":3.434091363549143,"y":-1.1545409416833587},"rotation":{"radians":-0.7148801185651648}},"curvature":-13.758568783146613},{"time":0.14600870089121665,"velocity":0.7470473232886716,"acceleration":0.2923563349047811,"pose":{"translation":{"x":3.4383389690207786,"y":-1.1585423007917905},"rotation":{"radians":-0.796643224733504}},"curvature":-14.181498919180148},{"time":0.15376398039420233,"velocity":0.7493146283803267,"acceleration":3.1274105162128683,"pose":{"translation":{"x":3.442221035675619,"y":-1.1628547077791276},"rotation":{"radians":-0.879039128670613}},"curvature":-14.13048668495357},{"time":0.1614159123291146,"velocity":0.7732453607829164,"acceleration":6.2224884154221245,"pose":{"translation":{"x":3.445750979772129,"y":-1.16748862407339},"rotation":{"radians":-0.9600732954344354}},"curvature":-13.610309663954157},{"time":0.16882882891931472,"velocity":0.8193721483899272,"acceleration":9.788836768369139,"pose":{"translation":{"x":3.4489431817569614,"y":-1.1724539947311718},"rotation":{"radians":-1.037888857922356}},"curvature":-12.693389767895697},{"time":0.17589307963882372,"velocity":0.8885229455740351,"acceleration":14.028806760935778,"pose":{"translation":{"x":3.4518128867501217,"y":-1.177760202826674},"rotation":{"radians":-1.1109617733901278}},"curvature":-11.497133978077434},{"time":0.18253357510806822,"velocity":0.9816811733089359,"acceleration":19.11904573956067,"pose":{"translation":{"x":3.454376105030131,"y":-1.1834160238407379},"rotation":{"radians":-1.1782123842054637}},"curvature":-10.152020839072915},{"time":0.18871089003190056,"velocity":1.099785539885357,"acceleration":25.185591459861286,"pose":{"translation":{"x":3.456649512519192,"y":-1.189429580049879},"rotation":{"radians":-1.2390233231447232}},"curvature":-8.774290588471855},{"time":0.19441671438734293,"velocity":1.2434901010432546,"acceleration":32.27206435015343,"pose":{"translation":{"x":3.458650351268351,"y":-1.1958082949153208},"rotation":{"radians":-1.2931851159063472}},"curvature":-7.450872939335512},{"time":0.1996664435011948,"velocity":1.4129096968263561,"acceleration":40.30568661605891,"pose":{"translation":{"x":3.460396329942662,"y":-1.2025588474720275},"rotation":{"radians":-1.340803982831074}},"curvature":-6.236411835290776},{"time":0.20449133814801623,"velocity":1.6073803884166407,"acceleration":53.740275685826795,"pose":{"translation":{"x":3.4619055243063532,"y":-1.209687126717738},"rotation":{"radians":-1.3822025931282806}},"curvature":-5.157967348327374},{"time":0.2129854894967538,"velocity":2.0638584236149353,"acceleration":71.3543118302435,"pose":{"translation":{"x":3.464287101565633,"y":-1.2250961974152026},"rotation":{"radians":-1.4482094847209641}},"curvature":-3.4249694963224426},{"time":0.22031724397529434,"velocity":2.5870107189395015,"acceleration":82.22663254477679,"pose":{"translation":{"x":3.4659432495796945,"y":-1.2420650850283956},"rotation":{"radians":-1.4953067179772608}},"curvature":-2.1909366724396966},{"time":0.2438218365064351,"velocity":4.5197142121123175,"acceleration":-7.5518339561036285,"pose":{"translation":{"x":3.468192668188263,"y":-1.325555125071546},"rotation":{"radians":-1.5652390742470428}},"curvature":-0.10916672029551365},{"time":0.2677899366670382,"velocity":4.338711099456182,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4692222678466824,"y":-1.431709944692168},"rotation":{"radians":-1.5514589466239832}},"curvature":0.22541620669281257},{"time":0.3234971221764526,"velocity":0.0,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4729270150046876,"y":-1.5525018368761265},"rotation":{"radians":-1.5333138901032233}},"curvature":4.454736102207827E-14}] \ No newline at end of file diff --git a/src/Robot.cpp b/src/Robot.cpp index b286036..171132f 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -10,12 +10,12 @@ void Robot::robotInit() { wpi::SmallString<64> deployDirectory; frc::filesystem::GetDeployDirectory(deployDirectory); wpi::sys::path::append(deployDirectory, "paths"); - wpi::sys::path::append(deployDirectory, "example.wpilib.json"); + wpi::sys::path::append(deployDirectory, "foreward.wpilib.json"); wpi::SmallString<64> deployDirectory1; frc::filesystem::GetDeployDirectory(deployDirectory1); wpi::sys::path::append(deployDirectory1, "paths"); - wpi::sys::path::append(deployDirectory1, "first.wpilib.json"); + wpi::sys::path::append(deployDirectory1, "right.wpilib.json"); frc::Trajectory trajectory1 = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory1); frc::Trajectory trajectory2 = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); frc::Trajectory trajectory = trajectory2; diff --git a/src/main/deploy/paths/foreward.wpilib.json b/src/main/deploy/paths/foreward.wpilib.json new file mode 100644 index 0000000..2d6b65f --- /dev/null +++ b/src/main/deploy/paths/foreward.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":90.00000000000001,"pose":{"translation":{"x":3.139010635462718,"y":-0.7857308912612436},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.045905467332406524,"velocity":4.131492059916588,"acceleration":27.195128294263547,"pose":{"translation":{"x":3.2338396723472616,"y":-0.7857294630390612},"rotation":{"radians":4.472450891313205E-5}},"curvature":9.276662745827367E-4},{"time":0.06683848129466095,"velocity":4.700768060205707,"acceleration":-0.09998687667157592,"pose":{"translation":{"x":3.3262825840794297,"y":-0.7857200994301465},"rotation":{"radians":1.7187578139907824E-4}},"curvature":0.00184078824601756},{"time":0.0855717783283503,"velocity":4.698894976345548,"acceleration":-0.14268613573850739,"pose":{"translation":{"x":3.4143259207697856,"y":-0.785696548691362},"rotation":{"radians":3.7871150569400913E-4}},"curvature":0.0029087836087896765},{"time":0.10303027644826515,"velocity":4.696403890713019,"acceleration":-0.22947015915521518,"pose":{"translation":{"x":3.496339813678259,"y":-0.7856542751576296},"rotation":{"radians":6.715026130162066E-4}},"curvature":0.004330471244214398},{"time":0.11894500173982889,"velocity":4.692751936167452,"acceleration":-0.41037597991465935,"pose":{"translation":{"x":3.571052704162918,"y":-0.7855903265554834},"rotation":{"radians":0.0010661429050122817}},"curvature":0.006417406777249305},{"time":0.13311891263114356,"velocity":4.686935303596206,"acceleration":-11.869177951857159,"pose":{"translation":{"x":3.637526072628745,"y":-0.7855032013166211},"rotation":{"radians":0.0015917497098839673}},"curvature":0.00974807812854124},{"time":0.15641985975591766,"velocity":4.410372215725448,"acceleration":-90.0,"pose":{"translation":{"x":3.743513734051032,"y":-0.785259872062671},"rotation":{"radians":0.003280034069158219}},"curvature":0.02666464595429507},{"time":0.19467354647582824,"velocity":0.9675404109334969,"acceleration":-90.0,"pose":{"translation":{"x":3.846373838709148,"y":-0.7845590045532563},"rotation":{"radians":0.022126764220783735}},"curvature":2.198058466233127},{"time":0.19927135599596166,"velocity":0.5537375541214894,"acceleration":-90.0,"pose":{"translation":{"x":3.849869724361052,"y":-0.7844605005876413},"rotation":{"radians":0.03833865663750966}},"curvature":10.474757649183204},{"time":0.20495391513957345,"velocity":0.042307231196426986,"acceleration":-8.127146835406759,"pose":{"translation":{"x":3.8515603635657674,"y":-0.7843615940246216},"rotation":{"radians":0.1196146774409119}},"curvature":295.0111549349735},{"time":0.20795929102031324,"velocity":0.01788210011806468,"acceleration":-2.2566117440366193,"pose":{"translation":{"x":3.8516499610931474,"y":-0.7843492359250838},"rotation":{"radians":0.16035705492601032}},"curvature":701.6234289290957},{"time":0.21350091850489672,"velocity":0.005376798455277498,"acceleration":-0.5161959577287843,"pose":{"translation":{"x":3.85171321228033,"y":-0.7843368834352253},"rotation":{"radians":0.2414428298028381}},"curvature":2339.678881887571},{"time":0.21937153885525884,"velocity":0.002346407961060226,"acceleration":-0.19460981444752634,"pose":{"translation":{"x":3.8517350254497353,"y":-0.7843307097143288},"rotation":{"radians":0.3211437117992815}},"curvature":5364.836593712613},{"time":0.22416410434184642,"velocity":0.0014137276809877974,"acceleration":-0.10971500188325159,"pose":{"translation":{"x":3.8517434907918204,"y":-0.7843276235585984},"rotation":{"radians":0.3832734005167584}},"curvature":8905.95310437488},{"time":0.22734195905319637,"velocity":0.0010650693453473359,"acceleration":-0.0727477770700109,"pose":{"translation":{"x":3.851747114640129,"y":-0.7843260806661382},"rotation":{"radians":0.4236619192568799}},"curvature":11822.259248902921},{"time":0.23120192670179074,"velocity":7.842652793499383E-4,"acceleration":-0.04637785712254716,"pose":{"translation":{"x":3.85175033317445,"y":-0.7843245379007978},"rotation":{"radians":0.4728070591402796}},"curvature":16056.145883841957},{"time":0.23596386572974987,"velocity":5.634167514849686E-4,"acceleration":-0.028254089132246654,"pose":{"translation":{"x":3.851753146821129,"y":-0.7843229952652162},"rotation":{"radians":0.5335669095761805}},"curvature":22350.895670489415},{"time":0.24193534255630544,"velocity":3.946981129763216E-4,"acceleration":-0.018597081133462527,"pose":{"translation":{"x":3.8517555560068883,"y":-0.7843214527620327},"rotation":{"radians":0.6099555380362651}},"curvature":31906.209684548245},{"time":0.24555012856181768,"velocity":3.2747364435170567E-4,"acceleration":-0.013923451531174818,"pose":{"translation":{"x":3.851756609060377,"y":-0.7843206815609153},"rotation":{"radians":0.6556822748781164}},"curvature":38456.53217320645},{"time":0.24964870575195625,"velocity":2.7040730349803255E-4,"acceleration":-0.010266037461806347,"pose":{"translation":{"x":3.8517575611588266,"y":-0.7843199103938877},"rotation":{"radians":0.707549023262855}},"curvature":46572.90452235532},{"time":0.25430836811721375,"velocity":2.225710350969301E-4,"acceleration":-0.007447854773923607,"pose":{"translation":{"x":3.851758412355683,"y":-0.78431913926128},"rotation":{"radians":0.7665385217845972}},"curvature":56583.200946092846},{"time":0.25961330519829917,"velocity":1.8306063413220386E-4,"acceleration":-0.005310880986123949,"pose":{"translation":{"x":3.851759162704415,"y":-0.7843183681634225},"rotation":{"radians":0.8337199791554958}},"curvature":68796.26221980967},{"time":0.265649226031357,"velocity":1.5100457694616765E-4,"acceleration":-0.003715644413520527,"pose":{"translation":{"x":3.851759812258515,"y":-0.7843175971006454},"rotation":{"radians":0.9101792815294496}},"curvature":83401.26815160742},{"time":0.27249281850722773,"velocity":1.2557622079478747E-4,"acceleration":-0.002785680869218963,"pose":{"translation":{"x":3.8517603610714986,"y":-0.7843168260732791},"rotation":{"radians":0.9968831256542522}},"curvature":100290.01681613881},{"time":0.2762516442382699,"velocity":1.151053318650952E-4,"acceleration":-0.002286903550375423,"pose":{"translation":{"x":3.851760597716802,"y":-0.7843164405729783},"rotation":{"radians":1.0442929283243139}},"curvature":109413.43138273002},{"time":0.280228659762849,"velocity":1.0601028094203713E-4,"acceleration":-0.0018606440283870252,"pose":{"translation":{"x":3.8517608091969047,"y":-0.784316055081654},"rotation":{"radians":1.0944542917281388}},"curvature":118800.68205404523},{"time":0.2844217109426492,"velocity":9.82085053036208E-5,"acceleration":-0.001495791047417784,"pose":{"translation":{"x":3.8517609955185033,"y":-0.7843156695993477},"rotation":{"radians":1.1473394272597957}},"curvature":128238.53219189229},{"time":0.28882358803320074,"velocity":9.162421695974032E-5,"acceleration":-0.0011821104669365744,"pose":{"translation":{"x":3.8517611566882954,"y":-0.7843152841261006},"rotation":{"radians":1.202856764228224}},"curvature":137454.18640884254},{"time":0.2934212216558681,"velocity":8.618930613124576E-5,"acceleration":-9.10166127726058E-4,"pose":{"translation":{"x":3.85176129271298,"y":-0.784314898661954},"rotation":{"radians":1.2608408975754095}},"curvature":146121.91830028637},{"time":0.2981951210387533,"velocity":8.184426461577132E-5,"acceleration":-6.712272375217975E-4,"pose":{"translation":{"x":3.851761403599256,"y":-0.7843145132069492},"rotation":{"radians":1.321045608746215}},"curvature":153879.54722685105},{"time":0.30311919829406525,"velocity":7.853908984234437E-5,"acceleration":-4.571620226274313E-4,"pose":{"translation":{"x":3.8517614893538275,"y":-0.7843141277611276},"rotation":{"radians":1.3831417521306877}},"curvature":160355.40081599023},{"time":0.3081611044594174,"velocity":7.623412182189426E-5,"acceleration":-2.6031820552800797E-4,"pose":{"translation":{"x":3.8517615499833955,"y":-0.7843137423245305},"rotation":{"radians":1.4467215645907465}},"curvature":165203.8890423113},{"time":0.31328314882614516,"velocity":7.490076042371285E-5,"acceleration":-7.339189251839403E-5,"pose":{"translation":{"x":3.8517615854946663,"y":-0.7843133568971993},"rotation":{"radians":1.511310270848789}},"curvature":168144.84794743382},{"time":0.3184437853205848,"velocity":7.452201154478644E-5,"acceleration":1.1071256075514668E-4,"pose":{"translation":{"x":3.8517615958943456,"y":-0.7843129714791752},"rotation":{"radians":1.576384764438419}},"curvature":168999.43688464654},{"time":0.32359954574379013,"velocity":7.509281898387954E-5,"acceleration":2.9902823420181046E-4,"pose":{"translation":{"x":3.8517615811891406,"y":-0.7843125860704996},"rotation":{"radians":1.6413978538853173}},"curvature":167714.79122347364},{"time":0.3287072071253734,"velocity":7.662015394771515E-5,"acceleration":4.986728239771152E-4,"pose":{"translation":{"x":3.851761541385761,"y":-0.7843122006712138},"rotation":{"radians":1.705805421556595}},"curvature":164371.53568921657},{"time":0.33372592880360563,"velocity":7.912285405975439E-5,"acceleration":7.169930956469593E-4,"pose":{"translation":{"x":3.8517614764909163,"y":-0.7843118152813591},"rotation":{"radians":1.7690932057110025}},"curvature":159172.28742679203},{"time":0.3386191016076256,"velocity":8.263122517604415E-5,"acceleration":9.6170265634419E-4,"pose":{"translation":{"x":3.8517613865113196,"y":-0.7843114299009769},"rotation":{"radians":1.8308000000964084}},"curvature":152414.00872744145},{"time":0.3433557144775732,"velocity":8.718643835514683E-5,"acceleration":0.0012410097888180393,"pose":{"translation":{"x":3.8517612714536833,"y":-0.7843110445301086},"rotation":{"radians":1.890534841060949}},"curvature":144450.7232629091},{"time":0.3479111415612719,"velocity":9.283976795826376E-5,"acceleration":0.0015637330056986363,"pose":{"translation":{"x":3.8517611313247224,"y":-0.7843106591687955},"rotation":{"radians":1.9479869603310134}},"curvature":135654.46381497147},{"time":0.35226735542574256,"velocity":9.965172335801853E-5,"acceleration":0.0019394030257907226,"pose":{"translation":{"x":3.851760966131154,"y":-0.784310273817079},"rotation":{"radians":2.002928554249174}},"curvature":126381.26346919124},{"time":0.3564126531460586,"velocity":1.0769112629960276E-4,"acceleration":0.0023783508195431846,"pose":{"translation":{"x":3.8517607758796952,"y":-0.7843098884750003},"rotation":{"radians":2.055211434485014}},"curvature":116946.39672905911},{"time":0.3603410280695216,"velocity":1.1703418001829391E-4,"acceleration":0.002891782198748304,"pose":{"translation":{"x":3.8517605605770644,"y":-0.7843095031426008},"rotation":{"radians":2.1047592075597557}},"curvature":107610.1371716676},{"time":0.36405133066867124,"velocity":1.2776356702648428E-4,"acceleration":0.003848012966735964,"pose":{"translation":{"x":3.851760320229983,"y":-0.7843091178199221},"rotation":{"radians":2.151556773972847}},"curvature":98572.9792302838},{"time":0.37080179898796,"velocity":1.537394566506478E-4,"acceleration":0.0054853422673589725,"pose":{"translation":{"x":3.8517597644293584,"y":-0.784308347203892},"rotation":{"radians":2.237078051694726}},"curvature":81917.59074766494},{"time":0.3767522112706826,"velocity":1.863795046532779E-4,"acceleration":0.007673363168733599,"pose":{"translation":{"x":3.8517591085316134,"y":-0.7843075766272408},"rotation":{"radians":2.3124505674602815}},"curvature":67571.15555938672},{"time":0.3819809888013117,"velocity":2.265018135743091E-4,"acceleration":0.010551505145509992,"pose":{"translation":{"x":3.851758352590565,"y":-0.7843068060902996},"rotation":{"radians":2.3786636796836915}},"curvature":55601.19312404653},{"time":0.3865740802430194,"velocity":2.749658415552858E-4,"acceleration":0.014277276894402814,"pose":{"translation":{"x":3.8517574966600527,"y":-0.7843060355933994},"rotation":{"radians":2.4368067087778296}},"curvature":45800.74838319005},{"time":0.3906150983009136,"velocity":3.326605753031231E-4,"acceleration":0.019026589999720272,"pose":{"translation":{"x":3.8517565407939385,"y":-0.7843052651368713},"rotation":{"radians":2.4879417118598544}},"curvature":37856.86608960236},{"time":0.39418039364393004,"velocity":4.004959880226089E-4,"acceleration":0.028806945377216234,"pose":{"translation":{"x":3.851755485046108,"y":-0.7843044947210466},"rotation":{"radians":2.533039486043962}},"curvature":31444.27312193421},{"time":0.4000749011410937,"velocity":5.702987435189932E-4,"acceleration":0.047096725612869775,"pose":{"translation":{"x":3.8517530741209534,"y":-0.7843029540128321},"rotation":{"radians":2.608425718386986}},"curvature":22081.147379110564},{"time":0.40477973447678156,"velocity":7.918809881841682E-4,"acceleration":0.07360485766036914,"pose":{"translation":{"x":3.851750264316128,"y":-0.7843014134714063},"rotation":{"radians":2.668444494668615}},"curvature":15901.704340218665},{"time":0.40859680737008547,"velocity":0.001072836095175056,"acceleration":0.13685645112569875,"pose":{"translation":{"x":3.851747056063539,"y":-0.7842998730994203},"rotation":{"radians":2.7170348240218822}},"curvature":11736.653139162667},{"time":0.41422725430777096,"velocity":0.0018433990813182533,"acceleration":0.2713001524578744,"pose":{"translation":{"x":3.851739445944512,"y":-0.7842967928743765},"rotation":{"radians":2.7903532377332416}},"curvature":6829.471797427922},{"time":0.41828056430806565,"velocity":0.0029430627023572242,"acceleration":0.6668320341133934,"pose":{"translation":{"x":3.8517302472263966,"y":-0.7842937133589265},"rotation":{"radians":2.842660925553188}},"curvature":4276.666553522217},{"time":0.4234233959707022,"velocity":0.00637246760105592,"acceleration":2.6520405677717576,"pose":{"translation":{"x":3.8517070978719796,"y":-0.7842875565417728},"rotation":{"radians":2.911776236578576}},"curvature":1973.6963456742196},{"time":0.42849167787478654,"velocity":0.019813756819591077,"acceleration":8.984499789449828,"pose":{"translation":{"x":3.8516418889660993,"y":-0.7842752523579086},"rotation":{"radians":2.9847439440369117}},"curvature":632.960661819855},{"time":0.4312999297154105,"velocity":0.045044494890398745,"acceleration":90.00000000000135,"pose":{"translation":{"x":3.851551652967633,"y":-0.7842629619106193},"rotation":{"radians":3.0225269883003785}},"curvature":276.9212194102955},{"time":0.4367805579926848,"velocity":0.5383010398450934,"acceleration":90.00000000000024,"pose":{"translation":{"x":3.8499560891851043,"y":-0.7841652973250023},"rotation":{"radians":3.1003621440525393}},"curvature":11.247397230772256},{"time":0.4526205753393156,"velocity":1.9639026010418699,"acceleration":79.23256726649373,"pose":{"translation":{"x":3.8301420093346312,"y":-0.7837985048055609},"rotation":{"radians":3.12987179235241}},"curvature":0.30176263979709583},{"time":0.47831107663860617,"velocity":3.9994269733478567,"acceleration":-90.0,"pose":{"translation":{"x":3.753543010707668,"y":-0.7833248436723809},"rotation":{"radians":3.139009364028352}},"curvature":0.08388935629985557},{"time":0.5026122678124995,"velocity":1.8123197676974647,"acceleration":-90.0,"pose":{"translation":{"x":3.682926934250862,"y":-0.7834482597604684},"rotation":{"radians":-3.1315650187328625}},"curvature":0.5631600111545465},{"time":0.5167297737975327,"velocity":0.5417442290444762,"acceleration":-89.99999999999999,"pose":{"translation":{"x":3.6663136407505825,"y":-0.7837874770874453},"rotation":{"radians":-3.090212871797444}},"curvature":14.864983247841876},{"time":0.5216308885734858,"velocity":0.1006438992086931,"acceleration":-18.285644081758157,"pose":{"translation":{"x":3.664743548466244,"y":-0.7839012492780149},"rotation":{"radians":-3.026923077458199}},"curvature":122.46063625724759},{"time":0.5248130561893707,"velocity":0.04245591477612631,"acceleration":-5.079855903164719,"pose":{"translation":{"x":3.6645178740505915,"y":-0.78393143154953},"rotation":{"radians":-2.9841564085591434}},"curvature":293.9686289012376},{"time":0.5306978787418675,"velocity":0.012561864193748828,"acceleration":-1.136261554420965,"pose":{"translation":{"x":3.6643589588878283,"y":-0.7839622974312198},"rotation":{"radians":-2.897999549537208}},"curvature":999.9108795039187},{"time":0.5370114486552923,"velocity":0.005387997429975311,"acceleration":-0.4179967389832239,"pose":{"translation":{"x":3.6643045097969607,"y":-0.7839779846475876},"rotation":{"radians":-2.812094624008948}},"curvature":2334.810284823715},{"time":0.5422281045702659,"velocity":0.0032074522691187823,"acceleration":-0.23167458609594105,"pose":{"translation":{"x":3.664283530573952,"y":-0.7839858914466122},"rotation":{"radians":-2.7443971830752876}},"curvature":3923.921199058397},{"time":0.545713370900079,"velocity":0.002400004634725228,"acceleration":-0.15167513899624624,"pose":{"translation":{"x":3.664274601253251,"y":-0.7839898605953501},"rotation":{"radians":-2.700093036206735}},"curvature":5244.969785760789},{"time":0.5499669229800531,"velocity":0.0017548465317673845,"acceleration":-0.09530454440799681,"pose":{"translation":{"x":3.6642667116915404,"y":-0.7839938402248509},"rotation":{"radians":-2.6459158437811636}},"curvature":7174.233699553927},{"time":0.5552392451789496,"velocity":0.0012523702666293879,"acceleration":-0.0571248666593388,"pose":{"translation":{"x":3.664259861544444,"y":-0.7839978303209554},"rotation":{"radians":-2.5786064876297368}},"curvature":10053.755490079226},{"time":0.5618776166314029,"velocity":8.731541825728328E-4,"acceleration":-0.037075936236512286,"pose":{"translation":{"x":3.6642540504529824,"y":-0.7840018308694107},"rotation":{"radians":-2.4936310429428614}},"curvature":14421.324434057353},{"time":0.5659061722638513,"velocity":7.237917108189329E-4,"acceleration":-0.027502999859915958,"pose":{"translation":{"x":3.6642515344369304,"y":-0.7840038350587898},"rotation":{"radians":-2.4426654722113676}},"curvature":17397.877675491844},{"time":0.5704747738133626,"velocity":5.981414630427118E-4,"acceleration":-0.02008660417028765,"pose":{"translation":{"x":3.664249278043539,"y":-0.7840058418558689},"rotation":{"radians":-2.3848460492049255}},"curvature":21053.173602567214},{"time":0.5756627783247271,"velocity":4.939320699892669E-4,"acceleration":-0.014428933678911236,"pose":{"translation":{"x":3.664247281223815,"y":-0.7840078512588396},"rotation":{"radians":-2.3191652793679616}},"curvature":25495.520200497296},{"time":0.5815510410174265,"velocity":4.0897071811230035E-4,"acceleration":-0.010177654461040827,"pose":{"translation":{"x":3.6642455439278514,"y":-0.7840098632658877},"rotation":{"radians":-2.2445989524060472}},"curvature":30792.62642496039},{"time":0.5882124915045547,"velocity":3.4117277684497793E-4,"acceleration":-0.007684857175444079,"pose":{"translation":{"x":3.664244066104822,"y":-0.7840118778751932},"rotation":{"radians":-2.1602275254132213}},"curvature":36912.27705396234},{"time":0.5918657809626717,"velocity":3.130977691387926E-4,"acceleration":-0.006341371622965841,"pose":{"translation":{"x":3.664243424479521,"y":-0.784012886155122},"rotation":{"radians":-2.1141536010910844}},"curvature":40222.385691758725},{"time":0.595728699315394,"velocity":2.886015683150056E-4,"acceleration":-0.0051895547426711475,"pose":{"translation":{"x":3.66424284770298,"y":-0.7840138950849299},"rotation":{"radians":-2.0654360692729696}},"curvature":43636.64719014187},{"time":0.5997999376418786,"velocity":2.6747365414925284E-4,"acceleration":-0.004200976959185473,"pose":{"translation":{"x":3.6642423357685834,"y":-0.7840149046643877},"rotation":{"radians":-2.014091993385154}},"curvature":47083.74521032249},{"time":0.6040736636067117,"velocity":2.495198298411161E-4,"acceleration":-0.0033494017791718795,"pose":{"translation":{"x":3.664241888669662,"y":-0.7840159148932658},"rotation":{"radians":-1.960195513097017}},"curvature":50471.77797306924},{"time":0.6085387657197628,"velocity":2.345644088794785E-4,"acceleration":-0.0026106014500051665,"pose":{"translation":{"x":3.6642415063994904,"y":-0.7840169257713344},"rotation":{"radians":-1.903887302809682}},"curvature":53689.94193568191},{"time":0.6131782877796909,"velocity":2.2245246586249934E-4,"acceleration":-0.0019621406023246023,"pose":{"translation":{"x":3.6642411889512845,"y":-0.7840179372983631},"rotation":{"radians":-1.845381614079129}},"curvature":56613.36174570438},{"time":0.6179691785615897,"velocity":2.1305206453803294E-4,"acceleration":-0.0013831269084034143,"pose":{"translation":{"x":3.664240936318199,"y":-0.7840189494741213},"rotation":{"radians":-1.7849693402812188}},"curvature":59111.40601644545},{"time":0.6228824726415442,"velocity":2.062563552871488E-4,"acceleration":-8.539295658283349E-4,"pose":{"translation":{"x":3.6642407484933393,"y":-0.7840199622983779},"rotation":{"radians":-1.7230156647909987}},"curvature":61059.08962979245},{"time":0.6278839795131077,"velocity":2.0198542069582714E-4,"acceleration":-3.558686872510841E-4,"pose":{"translation":{"x":3.6642406254697457,"y":-0.7840209757709015},"rotation":{"radians":-1.6599513449563343}},"curvature":62350.22644543778},{"time":0.632935489603655,"velocity":2.0018774643126847E-4,"acceleration":1.2911906951840844E-4,"pose":{"translation":{"x":3.6642405672404004,"y":-0.7840219898914603},"rotation":{"radians":-1.596257540031257}},"curvature":62910.1518782517},{"time":0.6379964186853384,"velocity":2.0084120888519408E-4,"acceleration":6.18831061022732E-4,"pose":{"translation":{"x":3.6642405737982373,"y":-0.7840230046598221},"rotation":{"radians":-1.5324451743856793}},"curvature":62705.45697503062},{"time":0.643025727310457,"velocity":2.0395350127788703E-4,"acceleration":0.0011311562519046234,"pose":{"translation":{"x":3.66424064513612,"y":-0.7840240200757546},"rotation":{"radians":-1.4690308768217482}},"curvature":61748.5425396905},{"time":0.6479838942802174,"velocity":2.0956196284371842E-4,"acceleration":0.001684429966211262,"pose":{"translation":{"x":3.6642407812468636,"y":-0.7840250361390245},"rotation":{"radians":-1.4065122474002567}},"curvature":60095.90797371259},{"time":0.6528347115222313,"velocity":2.177328247667809E-4,"acceleration":0.0022977761940409028,"pose":{"translation":{"x":3.6642409821232236,"y":-0.7840260528493989},"rotation":{"radians":-1.3453453471872574}},"curvature":57840.58775178996},{"time":0.6575467058635939,"velocity":2.2855993319081946E-4,"acceleration":0.0029914290874418414,"pose":{"translation":{"x":3.664241247757894,"y":-0.784027070206644},"rotation":{"radians":-1.2859268358224432}},"curvature":55100.495495029645},{"time":0.6620940685609409,"velocity":2.4216304623481122E-4,"acceleration":0.003787027260522827,"pose":{"translation":{"x":3.6642415781435136,"y":-0.7840280882105256},"rotation":{"radians":-1.2285822511589828}},"curvature":52005.1648849209},{"time":0.6664570625918498,"velocity":2.586858235673617E-4,"acceleration":0.00470787682533917,"pose":{"translation":{"x":3.664241973272665,"y":-0.7840291068608096},"rotation":{"radians":-1.1735608198435061}},"curvature":48683.32070577291},{"time":0.6706219567904208,"velocity":2.7829363244480376E-4,"acceleration":0.005779181372427527,"pose":{"translation":{"x":3.664242433137871,"y":-0.7840301261572612},"rotation":{"radians":-1.1210362023448242}},"curvature":45253.038320252315},{"time":0.6745805889128479,"velocity":3.0117128546702787E-4,"acceleration":0.0070282391438150306,"pose":{"translation":{"x":3.6642429577315947,"y":-0.7840311460996451},"rotation":{"radians":-1.071111909998547}},"curvature":41815.31164797268},{"time":0.6783296818167085,"velocity":3.2752080696774044E-4,"acceleration":0.009347232409719361,"pose":{"translation":{"x":3.6642435470462438,"y":-0.7840321666877259},"rotation":{"radians":-1.023829847210145}},"curvature":38450.994091695226},{"time":0.6851762185220589,"velocity":3.9151697675432473E-4,"acceleration":0.013309959262423975,"pose":{"translation":{"x":3.6642449198076688,"y":-0.784034209800034},"rotation":{"radians":-0.9371133455817752}},"curvature":32165.474346036655},{"time":0.6912354885212121,"velocity":4.721656136030816E-4,"acceleration":0.01859916953103669,"pose":{"translation":{"x":3.6642465513602387,"y":-0.7840362554922942},"rotation":{"radians":-0.8603784380556495}},"curvature":26670.96667412578},{"time":0.6965766580858223,"velocity":5.715069318292798E-4,"acceleration":0.025554930558089585,"pose":{"translation":{"x":3.6642484416411296,"y":-0.7840383037626087},"rotation":{"radians":-0.7927545034206182}},"curvature":22034.461298123704},{"time":0.7012798021122773,"velocity":6.916954508300321E-4,"acceleration":0.03456200109704326,"pose":{"translation":{"x":3.6642505905865863,"y":-0.7840403546090741},"rotation":{"radians":-0.7332279992817718}},"curvature":18205.30345546575},{"time":0.7054251849883204,"velocity":8.349681783395013E-4,"acceleration":0.04605075448824015,"pose":{"translation":{"x":3.664252998131924,"y":-0.7840424080297809},"rotation":{"radians":-0.6807803050322688}},"curvature":15080.98429712439},{"time":0.709087516607084,"velocity":0.0010036213125697024,"acceleration":0.060497699784128105,"pose":{"translation":{"x":3.6642556642115274,"y":-0.7840444640228134},"rotation":{"radians":-0.6344620841273695}},"curvature":12546.25652180786},{"time":0.7123334591235545,"velocity":0.0011999933684476716,"acceleration":0.08973893268059224,"pose":{"translation":{"x":3.6642585887588566,"y":-0.7840465225862501},"rotation":{"radians":-0.5934258312593568}},"curvature":10492.695216036627},{"time":0.7177424455119071,"velocity":0.0016853900338222871,"acceleration":0.14346871101279474,"pose":{"translation":{"x":3.664265212985841,"y":-0.7840506474166204},"rotation":{"radians":-0.5243539886762357}},"curvature":7470.0009103366765},{"time":0.7220983425082198,"velocity":0.0023103249611877708,"acceleration":0.2199896007776265,"pose":{"translation":{"x":3.6642728702618883,"y":-0.7840547825053997},"rotation":{"radians":-0.4688611177052537}},"curvature":5448.667227562127},{"time":0.7256612751581851,"velocity":0.0030941330924512123,"acceleration":0.39890363017732156,"pose":{"translation":{"x":3.66428156002107,"y":-0.7840589278369995},"rotation":{"radians":-0.42356138240863994}},"curvature":4067.728496402634},{"time":0.7309803671972144,"velocity":0.005215938216067251,"acceleration":0.7722458693560452,"pose":{"translation":{"x":3.6643020346503,"y":-0.7840672491658256},"rotation":{"radians":-0.354501339492932}},"curvature":2411.91746531754},{"time":0.7348517474597189,"velocity":0.008205595632492901,"acceleration":1.8447752321181765,"pose":{"translation":{"x":3.6643266320465147,"y":-0.7840756112764639},"rotation":{"radians":-0.3046648486200171}},"curvature":1532.1749458426339},{"time":0.7398356061397846,"velocity":0.017399694685855227,"acceleration":7.056637039709774,"pose":{"translation":{"x":3.664388174628757,"y":-0.7840924573288989},"rotation":{"radians":-0.23803357831171906}},"curvature":721.1501241053157},{"time":0.7448445046474885,"velocity":0.0527456734234657,"acceleration":23.058879876892238,"pose":{"translation":{"x":3.6645604938242413,"y":-0.7841266330714044},"rotation":{"radians":-0.16667529316278054}},"curvature":236.0981800515628},{"time":0.7476622675500084,"velocity":0.11772012971423518,"acceleration":90.00000000000266,"pose":{"translation":{"x":3.664798123348533,"y":-0.7841614464118355},"rotation":{"radians":-0.1293160268301575}},"curvature":104.30838353357605},{"time":0.7524591472815689,"velocity":0.549439305554697,"acceleration":-3.6338253928342263,"pose":{"translation":{"x":3.666391641573475,"y":-0.7843068885078666},"rotation":{"radians":-0.07143425703513524}},"curvature":13.956021152155188},{"time":0.9036604974174812,"velocity":0.0,"acceleration":-3.6338253928342263,"pose":{"translation":{"x":3.707905208015694,"y":-0.7857308912612436},"rotation":{"radians":-0.027770636593421678}},"curvature":-3.978252216468362E-15}] \ No newline at end of file diff --git a/src/main/deploy/paths/right.wpilib.json b/src/main/deploy/paths/right.wpilib.json new file mode 100644 index 0000000..dd3d114 --- /dev/null +++ b/src/main/deploy/paths/right.wpilib.json @@ -0,0 +1 @@ +[{"time":0.0,"velocity":0.0,"acceleration":71.89737745448778,"pose":{"translation":{"x":3.1884797287281947,"y":-1.11964727080321},"rotation":{"radians":-0.014924264990084975}},"curvature":0.0},{"time":0.05268142631895732,"velocity":3.7876563928948612,"acceleration":-59.21877194518338,"pose":{"translation":{"x":3.288224082733628,"y":-1.1218902732848743},"rotation":{"radians":-0.0403604301267946}},"curvature":-0.6477347161258742},{"time":0.065514378921308,"velocity":3.027704699352909,"acceleration":-60.80332122104294,"pose":{"translation":{"x":3.331877617444612,"y":-1.1244853725247268},"rotation":{"radians":-0.08438803131334119}},"curvature":-1.4823351481606475},{"time":0.08017189482943719,"velocity":2.1364790512883824,"acceleration":-49.06001447129655,"pose":{"translation":{"x":3.3694477203028774,"y":-1.129055577359315},"rotation":{"radians":-0.16848946991993805}},"curvature":-3.217545897949398},{"time":0.088805972713633,"velocity":1.7128910653434348,"acceleration":-36.874935338028024,"pose":{"translation":{"x":3.3857381692078086,"y":-1.1323381424087688},"rotation":{"radians":-0.23321582313921457}},"curvature":-4.67532579835257},{"time":0.09870430596676388,"velocity":1.347890666679981,"acceleration":-27.52374540467266,"pose":{"translation":{"x":3.4003246705429637,"y":-1.1364253836844578},"rotation":{"radians":-0.31820697087304906}},"curvature":-6.666391703427893},{"time":0.1042636529843187,"velocity":1.194876614752576,"acceleration":-21.87942884039311,"pose":{"translation":{"x":3.406980716935266,"y":-1.138803315325991},"rotation":{"radians":-0.36945663667725215}},"curvature":-7.862940171392727},{"time":0.11025203226317788,"velocity":1.0638542964514919,"acceleration":-16.847469869568364,"pose":{"translation":{"x":3.413216547742749,"y":-1.1414212366924745},"rotation":{"radians":-0.4269562853680734}},"curvature":-9.161065946190682},{"time":0.11668007251373871,"velocity":0.9555580820097955,"acceleration":-12.47056095030327,"pose":{"translation":{"x":3.419037704283193,"y":-1.144291749610191},"rotation":{"radians":-0.4907496613456893}},"curvature":-10.50275149137545},{"time":0.12353356839552536,"velocity":0.8700911438933228,"acceleration":-8.702140600437376,"pose":{"translation":{"x":3.4244512891515826,"y":-1.1474272131997965},"rotation":{"radians":-0.5605494558412518}},"curvature":-11.797403394481876},{"time":0.13076635109573062,"velocity":0.8071504519037256,"acceleration":-5.428847799907451,"pose":{"translation":{"x":3.429465866705271,"y":-1.150839698265352},"rotation":{"radians":-0.6356493581978337}},"curvature":-12.92613056067708},{"time":0.1382965103849562,"velocity":0.7662703632134606,"acceleration":-2.4925525256649843,"pose":{"translation":{"x":3.434091363549143,"y":-1.1545409416833587},"rotation":{"radians":-0.7148801185651648}},"curvature":-13.758568783146613},{"time":0.14600870089121665,"velocity":0.7470473232886716,"acceleration":0.2923563349047811,"pose":{"translation":{"x":3.4383389690207786,"y":-1.1585423007917905},"rotation":{"radians":-0.796643224733504}},"curvature":-14.181498919180148},{"time":0.15376398039420233,"velocity":0.7493146283803267,"acceleration":3.1274105162128683,"pose":{"translation":{"x":3.442221035675619,"y":-1.1628547077791276},"rotation":{"radians":-0.879039128670613}},"curvature":-14.13048668495357},{"time":0.1614159123291146,"velocity":0.7732453607829164,"acceleration":6.2224884154221245,"pose":{"translation":{"x":3.445750979772129,"y":-1.16748862407339},"rotation":{"radians":-0.9600732954344354}},"curvature":-13.610309663954157},{"time":0.16882882891931472,"velocity":0.8193721483899272,"acceleration":9.788836768369139,"pose":{"translation":{"x":3.4489431817569614,"y":-1.1724539947311718},"rotation":{"radians":-1.037888857922356}},"curvature":-12.693389767895697},{"time":0.17589307963882372,"velocity":0.8885229455740351,"acceleration":14.028806760935778,"pose":{"translation":{"x":3.4518128867501217,"y":-1.177760202826674},"rotation":{"radians":-1.1109617733901278}},"curvature":-11.497133978077434},{"time":0.18253357510806822,"velocity":0.9816811733089359,"acceleration":19.11904573956067,"pose":{"translation":{"x":3.454376105030131,"y":-1.1834160238407379},"rotation":{"radians":-1.1782123842054637}},"curvature":-10.152020839072915},{"time":0.18871089003190056,"velocity":1.099785539885357,"acceleration":25.185591459861286,"pose":{"translation":{"x":3.456649512519192,"y":-1.189429580049879},"rotation":{"radians":-1.2390233231447232}},"curvature":-8.774290588471855},{"time":0.19441671438734293,"velocity":1.2434901010432546,"acceleration":32.27206435015343,"pose":{"translation":{"x":3.458650351268351,"y":-1.1958082949153208},"rotation":{"radians":-1.2931851159063472}},"curvature":-7.450872939335512},{"time":0.1996664435011948,"velocity":1.4129096968263561,"acceleration":40.30568661605891,"pose":{"translation":{"x":3.460396329942662,"y":-1.2025588474720275},"rotation":{"radians":-1.340803982831074}},"curvature":-6.236411835290776},{"time":0.20449133814801623,"velocity":1.6073803884166407,"acceleration":53.740275685826795,"pose":{"translation":{"x":3.4619055243063532,"y":-1.209687126717738},"rotation":{"radians":-1.3822025931282806}},"curvature":-5.157967348327374},{"time":0.2129854894967538,"velocity":2.0638584236149353,"acceleration":71.3543118302435,"pose":{"translation":{"x":3.464287101565633,"y":-1.2250961974152026},"rotation":{"radians":-1.4482094847209641}},"curvature":-3.4249694963224426},{"time":0.22031724397529434,"velocity":2.5870107189395015,"acceleration":82.22663254477679,"pose":{"translation":{"x":3.4659432495796945,"y":-1.2420650850283956},"rotation":{"radians":-1.4953067179772608}},"curvature":-2.1909366724396966},{"time":0.2438218365064351,"velocity":4.5197142121123175,"acceleration":-7.5518339561036285,"pose":{"translation":{"x":3.468192668188263,"y":-1.325555125071546},"rotation":{"radians":-1.5652390742470428}},"curvature":-0.10916672029551365},{"time":0.2677899366670382,"velocity":4.338711099456182,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4692222678466824,"y":-1.431709944692168},"rotation":{"radians":-1.5514589466239832}},"curvature":0.22541620669281257},{"time":0.3234971221764526,"velocity":0.0,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4729270150046876,"y":-1.5525018368761265},"rotation":{"radians":-1.5333138901032233}},"curvature":4.454736102207827E-14}] \ No newline at end of file From 6a48ce4d0dbc84ce18a42c12a75c4c00952c32ff Mon Sep 17 00:00:00 2001 From: CORE Programmers Date: Thu, 5 Mar 2020 18:26:47 -0600 Subject: [PATCH 22/31] Figured out how to change paths in autonomous --- PathWeaver/Paths/right.path | 4 ++-- PathWeaver/output/right.wpilib.json | 2 +- src/Robot.cpp | 2 +- src/RobotContainer.cpp | 16 ++++++---------- src/RobotContainer.h | 4 ++++ src/main/deploy/paths/right.wpilib.json | 2 +- 6 files changed, 15 insertions(+), 15 deletions(-) diff --git a/PathWeaver/Paths/right.path b/PathWeaver/Paths/right.path index cc83250..b5174c1 100644 --- a/PathWeaver/Paths/right.path +++ b/PathWeaver/Paths/right.path @@ -1,3 +1,3 @@ X,Y,Tangent X,Tangent Y,Fixed Theta,Name -3.1884797287281947,-1.11964727080321,0.828607312196731,-0.01236727331636911,true, -3.4729270150046854,-1.552501836876129,0.03710181994910755,-0.9893818653095297,true, +1.0242068983635988,-0.1549999521264185,0.828607312196731,-0.01236727331636911,true, +3.5223961082701614,-2.257436415909169,0.03710181994910755,-0.9893818653095297,true, diff --git a/PathWeaver/output/right.wpilib.json b/PathWeaver/output/right.wpilib.json index dd3d114..9a2b641 100644 --- a/PathWeaver/output/right.wpilib.json +++ b/PathWeaver/output/right.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":71.89737745448778,"pose":{"translation":{"x":3.1884797287281947,"y":-1.11964727080321},"rotation":{"radians":-0.014924264990084975}},"curvature":0.0},{"time":0.05268142631895732,"velocity":3.7876563928948612,"acceleration":-59.21877194518338,"pose":{"translation":{"x":3.288224082733628,"y":-1.1218902732848743},"rotation":{"radians":-0.0403604301267946}},"curvature":-0.6477347161258742},{"time":0.065514378921308,"velocity":3.027704699352909,"acceleration":-60.80332122104294,"pose":{"translation":{"x":3.331877617444612,"y":-1.1244853725247268},"rotation":{"radians":-0.08438803131334119}},"curvature":-1.4823351481606475},{"time":0.08017189482943719,"velocity":2.1364790512883824,"acceleration":-49.06001447129655,"pose":{"translation":{"x":3.3694477203028774,"y":-1.129055577359315},"rotation":{"radians":-0.16848946991993805}},"curvature":-3.217545897949398},{"time":0.088805972713633,"velocity":1.7128910653434348,"acceleration":-36.874935338028024,"pose":{"translation":{"x":3.3857381692078086,"y":-1.1323381424087688},"rotation":{"radians":-0.23321582313921457}},"curvature":-4.67532579835257},{"time":0.09870430596676388,"velocity":1.347890666679981,"acceleration":-27.52374540467266,"pose":{"translation":{"x":3.4003246705429637,"y":-1.1364253836844578},"rotation":{"radians":-0.31820697087304906}},"curvature":-6.666391703427893},{"time":0.1042636529843187,"velocity":1.194876614752576,"acceleration":-21.87942884039311,"pose":{"translation":{"x":3.406980716935266,"y":-1.138803315325991},"rotation":{"radians":-0.36945663667725215}},"curvature":-7.862940171392727},{"time":0.11025203226317788,"velocity":1.0638542964514919,"acceleration":-16.847469869568364,"pose":{"translation":{"x":3.413216547742749,"y":-1.1414212366924745},"rotation":{"radians":-0.4269562853680734}},"curvature":-9.161065946190682},{"time":0.11668007251373871,"velocity":0.9555580820097955,"acceleration":-12.47056095030327,"pose":{"translation":{"x":3.419037704283193,"y":-1.144291749610191},"rotation":{"radians":-0.4907496613456893}},"curvature":-10.50275149137545},{"time":0.12353356839552536,"velocity":0.8700911438933228,"acceleration":-8.702140600437376,"pose":{"translation":{"x":3.4244512891515826,"y":-1.1474272131997965},"rotation":{"radians":-0.5605494558412518}},"curvature":-11.797403394481876},{"time":0.13076635109573062,"velocity":0.8071504519037256,"acceleration":-5.428847799907451,"pose":{"translation":{"x":3.429465866705271,"y":-1.150839698265352},"rotation":{"radians":-0.6356493581978337}},"curvature":-12.92613056067708},{"time":0.1382965103849562,"velocity":0.7662703632134606,"acceleration":-2.4925525256649843,"pose":{"translation":{"x":3.434091363549143,"y":-1.1545409416833587},"rotation":{"radians":-0.7148801185651648}},"curvature":-13.758568783146613},{"time":0.14600870089121665,"velocity":0.7470473232886716,"acceleration":0.2923563349047811,"pose":{"translation":{"x":3.4383389690207786,"y":-1.1585423007917905},"rotation":{"radians":-0.796643224733504}},"curvature":-14.181498919180148},{"time":0.15376398039420233,"velocity":0.7493146283803267,"acceleration":3.1274105162128683,"pose":{"translation":{"x":3.442221035675619,"y":-1.1628547077791276},"rotation":{"radians":-0.879039128670613}},"curvature":-14.13048668495357},{"time":0.1614159123291146,"velocity":0.7732453607829164,"acceleration":6.2224884154221245,"pose":{"translation":{"x":3.445750979772129,"y":-1.16748862407339},"rotation":{"radians":-0.9600732954344354}},"curvature":-13.610309663954157},{"time":0.16882882891931472,"velocity":0.8193721483899272,"acceleration":9.788836768369139,"pose":{"translation":{"x":3.4489431817569614,"y":-1.1724539947311718},"rotation":{"radians":-1.037888857922356}},"curvature":-12.693389767895697},{"time":0.17589307963882372,"velocity":0.8885229455740351,"acceleration":14.028806760935778,"pose":{"translation":{"x":3.4518128867501217,"y":-1.177760202826674},"rotation":{"radians":-1.1109617733901278}},"curvature":-11.497133978077434},{"time":0.18253357510806822,"velocity":0.9816811733089359,"acceleration":19.11904573956067,"pose":{"translation":{"x":3.454376105030131,"y":-1.1834160238407379},"rotation":{"radians":-1.1782123842054637}},"curvature":-10.152020839072915},{"time":0.18871089003190056,"velocity":1.099785539885357,"acceleration":25.185591459861286,"pose":{"translation":{"x":3.456649512519192,"y":-1.189429580049879},"rotation":{"radians":-1.2390233231447232}},"curvature":-8.774290588471855},{"time":0.19441671438734293,"velocity":1.2434901010432546,"acceleration":32.27206435015343,"pose":{"translation":{"x":3.458650351268351,"y":-1.1958082949153208},"rotation":{"radians":-1.2931851159063472}},"curvature":-7.450872939335512},{"time":0.1996664435011948,"velocity":1.4129096968263561,"acceleration":40.30568661605891,"pose":{"translation":{"x":3.460396329942662,"y":-1.2025588474720275},"rotation":{"radians":-1.340803982831074}},"curvature":-6.236411835290776},{"time":0.20449133814801623,"velocity":1.6073803884166407,"acceleration":53.740275685826795,"pose":{"translation":{"x":3.4619055243063532,"y":-1.209687126717738},"rotation":{"radians":-1.3822025931282806}},"curvature":-5.157967348327374},{"time":0.2129854894967538,"velocity":2.0638584236149353,"acceleration":71.3543118302435,"pose":{"translation":{"x":3.464287101565633,"y":-1.2250961974152026},"rotation":{"radians":-1.4482094847209641}},"curvature":-3.4249694963224426},{"time":0.22031724397529434,"velocity":2.5870107189395015,"acceleration":82.22663254477679,"pose":{"translation":{"x":3.4659432495796945,"y":-1.2420650850283956},"rotation":{"radians":-1.4953067179772608}},"curvature":-2.1909366724396966},{"time":0.2438218365064351,"velocity":4.5197142121123175,"acceleration":-7.5518339561036285,"pose":{"translation":{"x":3.468192668188263,"y":-1.325555125071546},"rotation":{"radians":-1.5652390742470428}},"curvature":-0.10916672029551365},{"time":0.2677899366670382,"velocity":4.338711099456182,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4692222678466824,"y":-1.431709944692168},"rotation":{"radians":-1.5514589466239832}},"curvature":0.22541620669281257},{"time":0.3234971221764526,"velocity":0.0,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4729270150046876,"y":-1.5525018368761265},"rotation":{"radians":-1.5333138901032233}},"curvature":4.454736102207827E-14}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":80.76699269765997,"pose":{"translation":{"x":1.0242068983635988,"y":-0.1549999521264185},"rotation":{"radians":-0.014924264990084975}},"curvature":0.0},{"time":0.025609804424775617,"velocity":2.0684268869643523,"acceleration":-21.155814970757113,"pose":{"translation":{"x":1.050678214033299,"y":-0.155881913417109},"rotation":{"radians":-0.06693930018684048}},"curvature":-3.4114914552546445},{"time":0.032803644393329875,"velocity":1.9162353396603813,"acceleration":6.611464338649243,"pose":{"translation":{"x":1.064948717041106,"y":-0.15721368705295774},"rotation":{"radians":-0.12030810077177533}},"curvature":-3.895082466360081},{"time":0.040842065461474814,"velocity":1.9693810738914683,"acceleration":20.933702197658278,"pose":{"translation":{"x":1.0803890767003188,"y":-0.1595566406348458},"rotation":{"radians":-0.1803961258779653}},"curvature":-3.7177180422598464},{"time":0.04925296545483286,"velocity":2.1454523495667117,"acceleration":29.60747444619942,"pose":{"translation":{"x":1.0973094211838648,"y":-0.1631836906287051},"rotation":{"radians":-0.24040394266674808}},"curvature":-3.1928905407395165},{"time":0.057779827766930275,"velocity":2.397911207578397,"acceleration":34.08103398278143,"pose":{"translation":{"x":1.1159816671791125,"y":-0.1683369846189167},"rotation":{"radians":-0.2961605935752694}},"curvature":-2.5748522974238695},{"time":0.06634123060191074,"velocity":2.6896926685376474,"acceleration":34.7124334432402,"pose":{"translation":{"x":1.1366409048026715,"y":-0.17522897523924807},"rotation":{"radians":-0.3457580062863986}},"curvature":-2.0050835227837482},{"time":0.07496542833509111,"velocity":2.9890595583520136,"acceleration":29.946915136341534,"pose":{"translation":{"x":1.1594867825151933,"y":-0.18404349410379134},"rotation":{"radians":-0.38878619951971055}},"curvature":-1.5361154851955572},{"time":0.092799865601637,"velocity":3.52314593767767,"acceleration":20.316759060686696,"pose":{"translation":{"x":1.2123681532587383,"y":-0.20803878150913113},"rotation":{"radians":-0.4570521842006177}},"curvature":-0.897377112453681},{"time":0.11200241195010796,"velocity":3.9132794451912236,"acceleration":12.121023757030521,"pose":{"translation":{"x":1.275566760738191,"y":-0.24126188872979926},"rotation":{"radians":-0.5067439345172463}},"curvature":-0.5409928938872032},{"time":0.13317424852601328,"velocity":4.16990377930774,"acceleration":6.90480129836837,"pose":{"translation":{"x":1.349545154333866,"y":-0.28426265292587083},"rotation":{"radians":-0.5435193504995377}},"curvature":-0.34292793555252027},{"time":0.1566916611587298,"velocity":4.332286840588385,"acceleration":3.9319735410791212,"pose":{"translation":{"x":1.4343317687515507,"y":-0.3372360723126428},"rotation":{"radians":-0.5715034441142186}},"curvature":-0.2297206976838789},{"time":0.1827183894169434,"velocity":4.434623247460538,"acceleration":2.5936952749045616,"pose":{"translation":{"x":1.5295652412961114,"y":-0.4000566719506442},"rotation":{"radians":-0.5934879292510035}},"curvature":-0.1626345369425383},{"time":0.19666826742095458,"velocity":4.4708049801250365,"acceleration":1.9886980096395166,"pose":{"translation":{"x":1.5808909445009771,"y":-0.43504128127314967},"rotation":{"radians":-0.6028413229938115}},"curvature":-0.13965064284099912},{"time":0.2112323836377278,"velocity":4.499768609057492,"acceleration":1.5336432363557886,"pose":{"translation":{"x":1.634538729145096,"y":-0.472312869535646},"rotation":{"radians":-0.6113438731482959}},"curvature":-0.12151830617487935},{"time":0.2263886445797095,"velocity":4.523012906139606,"acceleration":1.188198673442852,"pose":{"translation":{"x":1.6903735294084679,"y":-0.5117809228117848},"rotation":{"radians":-0.6191387196362657}},"curvature":-0.10713445715936788},{"time":0.24210853089120857,"velocity":4.541691254201601,"acceleration":0.9230363077806585,"pose":{"translation":{"x":1.748244226622337,"y":-0.5533413411886713},"rotation":{"radians":-0.6263458426140492}},"curvature":-0.09568276311179288},{"time":0.2583578665211356,"velocity":4.556689980965338,"acceleration":0.7168404321502287,"pose":{"translation":{"x":1.8079850341839898,"y":-0.5968775126978025},"rotation":{"radians":-0.6330667663073747}},"curvature":-0.0865550073435694},{"time":0.2750975094493898,"velocity":4.568689633836068,"acceleration":0.5540582852879005,"pose":{"translation":{"x":1.8694168824715565,"y":-0.6422613872460049},"rotation":{"radians":-0.6393883221634832}},"curvature":-0.07929554842622359},{"time":0.29228398071991496,"velocity":4.578211940638365,"acceleration":0.42325474807225716,"pose":{"translation":{"x":1.9323488037588106,"y":-0.6893545505463726},"rotation":{"radians":-0.6453856748471296}},"curvature":-0.0735618964657416},{"time":0.30987004541523744,"velocity":4.585655326020566,"acceleration":0.3159246834429844,"pose":{"translation":{"x":1.9965793171299688,"y":-0.7380092980492045},"rotation":{"radians":-0.65112477533599}},"curvature":-0.06909660399485994},{"time":0.32780525650741293,"velocity":4.591321501907345,"acceleration":0.22563867391089165,"pose":{"translation":{"x":2.0618978133944914,"y":-0.7880697088729425},"rotation":{"radians":-0.6566643720711324}},"curvature":-0.0657071663771941},{"time":0.34603647031814,"velocity":4.595435168815383,"acceleration":0.14742576911862446,"pose":{"translation":{"x":2.128085940001884,"y":-0.839372719735109},"rotation":{"radians":-0.6620576842842592}},"curvature":-0.06325165765214856},{"time":0.3645083405905348,"velocity":4.59815839849735,"acceleration":0.07732154341794786,"pose":{"translation":{"x":2.1949189859564937,"y":-0.891749198883246},"rotation":{"radians":-0.6673538206949008}},"curvature":-0.061628538480436416},{"time":0.3831637968549877,"velocity":4.599600867168884,"acceleration":0.01202897597466842,"pose":{"translation":{"x":2.2621672667323134,"y":-0.9450250200258506},"rotation":{"radians":-0.6725990108733612}},"curvature":-0.06076956645238116},{"time":0.4019445117952919,"velocity":4.599826779937688,"acceleration":-0.05134643121218473,"pose":{"translation":{"x":2.3295975091877787,"y":-0.9990221362633144},"rotation":{"radians":-0.6778377048334125}},"curvature":-0.06063508702204383},{"time":0.4207913616307893,"velocity":4.598859061459043,"acceleration":-0.11551640937741646,"pose":{"translation":{"x":2.396974236480571,"y":-1.0535596540188625},"rotation":{"radians":-0.6831135881205861}},"curvature":-0.061211235160974556},{"time":0.43964488308120203,"velocity":4.596681170356971,"acceleration":-0.1832077196231995,"pose":{"translation":{"x":2.4640611529824143,"y":-1.108454906969488},"rotation":{"radians":-0.6884705542364015}},"curvature":-0.06250876808175994},{"time":0.4584457302398705,"velocity":4.5932367100220475,"acceleration":-0.25735804364112175,"pose":{"translation":{"x":2.530622529193878,"y":-1.1635245299768913},"rotation":{"radians":-0.6939536732962518}},"curvature":-0.06456340310101423},{"time":0.4771351346320946,"velocity":4.588426841470847,"acceleration":-0.3413293051820923,"pose":{"translation":{"x":2.596424586659176,"y":-1.2185855330184205},"rotation":{"radians":-0.6996101951300101}},"curvature":-0.06743767120729748},{"time":0.49565537187010267,"velocity":4.58210534176259,"acceleration":-0.4391592408085358,"pose":{"translation":{"x":2.661236882880967,"y":-1.2734563751180061},"rotation":{"radians":-0.7054906265203724}},"curvature":-0.07122443266535772},{"time":0.5139502386413288,"velocity":4.574070981960645,"acceleration":-0.55587571035062,"pose":{"translation":{"x":2.7248336962351547,"y":-1.3279580382770977},"rotation":{"radians":-0.711649925996724}},"curvature":-0.07605235210334034},{"time":0.5319655442991419,"velocity":4.564056711130925,"acceleration":-0.6979041874500918,"pose":{"translation":{"x":2.7869954108856856,"y":-1.3819151014056064},"rotation":{"radians":-0.7181488657617937}},"curvature":-0.08209381492673395},{"time":0.5496496220924428,"velocity":4.551714919187787,"acceleration":-0.8736070962717432,"pose":{"translation":{"x":2.8475099016993557,"y":-1.4351568142528388},"rotation":{"radians":-0.7250556192580382}},"curvature":-0.089576006814548},{"time":0.566953866110386,"velocity":4.536597808818094,"acceleration":-1.0940036642771789,"pose":{"translation":{"x":2.906173919160599,"y":-1.4875181713384364},"rotation":{"radians":-0.7324476450365182}},"curvature":-0.09879620292355824},{"time":0.5838333013741773,"velocity":4.518131644788577,"acceleration":-1.3737288809187866,"pose":{"translation":{"x":2.962794474286303,"y":-1.5388409858833139},"rotation":{"radians":-0.7404139535163994}},"curvature":-0.11014276350833384},{"time":0.6002471962202129,"velocity":4.495583403390214,"acceleration":-1.7322949595692405,"pose":{"translation":{"x":3.017190223540596,"y":-1.5889749637405925},"rotation":{"radians":-0.7490578634583538}},"curvature":-0.12412396332287678},{"time":0.616159728206077,"velocity":4.468018204437117,"acceleration":-2.1957066260189535,"pose":{"translation":{"x":3.0691928537496507,"y":-1.6377787773265464},"rotation":{"radians":-0.7585003798474376}},"curvature":-0.1414076683227251},{"time":0.631540717187749,"velocity":4.434246065015335,"acceleration":-2.7984274125160087,"pose":{"translation":{"x":3.118648467016489,"y":-1.6851211395515324},"rotation":{"radians":-0.7688843540542437}},"curvature":-0.16287611175991407},{"time":0.6463664417709616,"velocity":4.3927573509312605,"acceleration":-3.5855478834013743,"pose":{"translation":{"x":3.1654189656357747,"y":-1.7308818777509312},"rotation":{"radians":-0.780379618688889}},"curvature":-0.18970172617171252},{"time":0.660620557531351,"velocity":4.341648536336838,"acceleration":-5.2656848478974805,"pose":{"translation":{"x":3.2093834370086203,"y":-1.7749530076160867},"rotation":{"radians":-0.7931893181036281}},"curvature":-0.22345225928509624},{"time":0.6874191929068241,"velocity":4.20053536809588,"acceleration":-8.755975906034498,"pose":{"translation":{"x":3.288504882640466,"y":-1.8576618904744684},"rotation":{"radians":-0.8237793533054495}},"curvature":-0.32090295413693193},{"time":0.7119809342601576,"velocity":3.9854733525958403,"acceleration":-14.180452459633708,"pose":{"translation":{"x":3.3554418320122448,"y":-1.9326684901522855},"rotation":{"radians":-0.8632819252242124}},"curvature":-0.4826945143136867},{"time":0.7345635800267775,"velocity":3.665241217889539,"acceleration":-21.13365091006073,"pose":{"translation":{"x":3.4099869094745,"y":-1.9996572539505455},"rotation":{"radians":-0.9155135569606806}},"curvature":-0.7587898983103346},{"time":0.7556505892742572,"velocity":3.219595725716079,"acceleration":-25.887668679860443,"pose":{"translation":{"x":3.4523406529017313,"y":-2.05861074023567},"rotation":{"radians":-0.9858015283733543}},"curvature":-1.2344123210490974},{"time":0.7658230995484007,"velocity":2.956253150096577,"acceleration":-27.37800202037828,"pose":{"translation":{"x":3.469130887496254,"y":-2.0851587757508963},"rotation":{"radians":-1.0297380383227297}},"curvature":-1.5828738378965297},{"time":0.775896767870847,"velocity":2.68045623841202,"acceleration":-26.763717732857412,"pose":{"translation":{"x":3.483155830965993,"y":-2.1098439842295025},"rotation":{"radians":-1.080581446105553}},"curvature":-2.0212185415768835},{"time":0.7859548722953983,"velocity":2.4112639706657264,"acceleration":-23.67849844154621,"pose":{"translation":{"x":3.4945750112597773,"y":-2.132763332720299},"rotation":{"radians":-1.1387839124803456}},"curvature":-2.545767235283315},{"time":0.7960352682601854,"velocity":2.172575330523345,"acceleration":-18.09139329185749,"pose":{"translation":{"x":3.50358176041047,"y":-2.1540388637993244},"rotation":{"radians":-1.2040990274245273}},"curvature":-3.1196046435807454},{"time":0.8060866880285056,"velocity":1.990731142353115,"acceleration":-9.793077589690121,"pose":{"translation":{"x":3.510404599449802,"y":-2.173818769500745},"rotation":{"radians":-1.2750358682090688}},"curvature":-3.6491323370511024},{"time":0.8159189341865687,"velocity":1.8944431928462704,"acceleration":3.010299278337512,"pose":{"translation":{"x":3.5153086233231274,"y":-2.1922784652478495},"rotation":{"radians":-1.3482697163467114}},"curvature":-3.9706867305066895},{"time":0.8251688243850291,"velocity":1.9222881306353972,"acceleration":27.93818099146828,"pose":{"translation":{"x":3.5185968858042624,"y":-2.209621663783926},"rotation":{"radians":-1.4183035447344245}},"curvature":-3.874387484326945},{"time":0.8333133087406257,"velocity":2.149830208644237,"acceleration":-73.58171418463397,"pose":{"translation":{"x":3.520611784410261,"y":-2.2260814491032495},"rotation":{"radians":-1.4777643315520235}},"curvature":-3.1809364802236244},{"time":0.86253021721397,"velocity":0.0,"acceleration":-73.58171418463397,"pose":{"translation":{"x":3.5223961082701587,"y":-2.2574364159091713},"rotation":{"radians":-1.533313890103249}},"curvature":-5.903430769592215E-14}] \ No newline at end of file diff --git a/src/Robot.cpp b/src/Robot.cpp index 171132f..db56c4e 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -15,7 +15,7 @@ void Robot::robotInit() { wpi::SmallString<64> deployDirectory1; frc::filesystem::GetDeployDirectory(deployDirectory1); wpi::sys::path::append(deployDirectory1, "paths"); - wpi::sys::path::append(deployDirectory1, "right.wpilib.json"); + wpi::sys::path::append(deployDirectory1, "foreward.wpilib.json"); frc::Trajectory trajectory1 = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory1); frc::Trajectory trajectory2 = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); frc::Trajectory trajectory = trajectory2; diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index a31db4f..47f0474 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -45,18 +45,14 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { config.AddConstraint(autoVoltageConstraint); // An example trajectory to follow. All units in meters. - auto exampleTrajectory = frc::TrajectoryGenerator::GenerateTrajectory( - // Start at the origin facing the +X direction - frc::Pose2d(0_m, 0_m, frc::Rotation2d(0_deg)), - // Pass through these two interior waypoints, making an 's' curve path - {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)}, - // End 3 meters straight ahead of where we started, facing forward - frc::Pose2d(3_m, 0_m, frc::Rotation2d(0_deg)), - // Pass the config - config); + wpi::SmallString<64> deployDirectory; + frc::filesystem::GetDeployDirectory(deployDirectory); + wpi::sys::path::append(deployDirectory, "paths"); + wpi::sys::path::append(deployDirectory, "right.wpilib.json"); + frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); frc2::RamseteCommand ramseteCommand( - exampleTrajectory, [this]() { return m_drive.getPose(); }, + trajectory, [this]() { return m_drive.getPose(); }, frc::RamseteController(AutoConstants::kRamseteB, AutoConstants::kRamseteZeta), frc::SimpleMotorFeedforward( diff --git a/src/RobotContainer.h b/src/RobotContainer.h index b362c29..acb2ffb 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -8,6 +8,10 @@ #include #include #include +#include +#include +#include +#include #include "Constants.h" #include "DriveSubsystem.h" diff --git a/src/main/deploy/paths/right.wpilib.json b/src/main/deploy/paths/right.wpilib.json index dd3d114..9a2b641 100644 --- a/src/main/deploy/paths/right.wpilib.json +++ b/src/main/deploy/paths/right.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":71.89737745448778,"pose":{"translation":{"x":3.1884797287281947,"y":-1.11964727080321},"rotation":{"radians":-0.014924264990084975}},"curvature":0.0},{"time":0.05268142631895732,"velocity":3.7876563928948612,"acceleration":-59.21877194518338,"pose":{"translation":{"x":3.288224082733628,"y":-1.1218902732848743},"rotation":{"radians":-0.0403604301267946}},"curvature":-0.6477347161258742},{"time":0.065514378921308,"velocity":3.027704699352909,"acceleration":-60.80332122104294,"pose":{"translation":{"x":3.331877617444612,"y":-1.1244853725247268},"rotation":{"radians":-0.08438803131334119}},"curvature":-1.4823351481606475},{"time":0.08017189482943719,"velocity":2.1364790512883824,"acceleration":-49.06001447129655,"pose":{"translation":{"x":3.3694477203028774,"y":-1.129055577359315},"rotation":{"radians":-0.16848946991993805}},"curvature":-3.217545897949398},{"time":0.088805972713633,"velocity":1.7128910653434348,"acceleration":-36.874935338028024,"pose":{"translation":{"x":3.3857381692078086,"y":-1.1323381424087688},"rotation":{"radians":-0.23321582313921457}},"curvature":-4.67532579835257},{"time":0.09870430596676388,"velocity":1.347890666679981,"acceleration":-27.52374540467266,"pose":{"translation":{"x":3.4003246705429637,"y":-1.1364253836844578},"rotation":{"radians":-0.31820697087304906}},"curvature":-6.666391703427893},{"time":0.1042636529843187,"velocity":1.194876614752576,"acceleration":-21.87942884039311,"pose":{"translation":{"x":3.406980716935266,"y":-1.138803315325991},"rotation":{"radians":-0.36945663667725215}},"curvature":-7.862940171392727},{"time":0.11025203226317788,"velocity":1.0638542964514919,"acceleration":-16.847469869568364,"pose":{"translation":{"x":3.413216547742749,"y":-1.1414212366924745},"rotation":{"radians":-0.4269562853680734}},"curvature":-9.161065946190682},{"time":0.11668007251373871,"velocity":0.9555580820097955,"acceleration":-12.47056095030327,"pose":{"translation":{"x":3.419037704283193,"y":-1.144291749610191},"rotation":{"radians":-0.4907496613456893}},"curvature":-10.50275149137545},{"time":0.12353356839552536,"velocity":0.8700911438933228,"acceleration":-8.702140600437376,"pose":{"translation":{"x":3.4244512891515826,"y":-1.1474272131997965},"rotation":{"radians":-0.5605494558412518}},"curvature":-11.797403394481876},{"time":0.13076635109573062,"velocity":0.8071504519037256,"acceleration":-5.428847799907451,"pose":{"translation":{"x":3.429465866705271,"y":-1.150839698265352},"rotation":{"radians":-0.6356493581978337}},"curvature":-12.92613056067708},{"time":0.1382965103849562,"velocity":0.7662703632134606,"acceleration":-2.4925525256649843,"pose":{"translation":{"x":3.434091363549143,"y":-1.1545409416833587},"rotation":{"radians":-0.7148801185651648}},"curvature":-13.758568783146613},{"time":0.14600870089121665,"velocity":0.7470473232886716,"acceleration":0.2923563349047811,"pose":{"translation":{"x":3.4383389690207786,"y":-1.1585423007917905},"rotation":{"radians":-0.796643224733504}},"curvature":-14.181498919180148},{"time":0.15376398039420233,"velocity":0.7493146283803267,"acceleration":3.1274105162128683,"pose":{"translation":{"x":3.442221035675619,"y":-1.1628547077791276},"rotation":{"radians":-0.879039128670613}},"curvature":-14.13048668495357},{"time":0.1614159123291146,"velocity":0.7732453607829164,"acceleration":6.2224884154221245,"pose":{"translation":{"x":3.445750979772129,"y":-1.16748862407339},"rotation":{"radians":-0.9600732954344354}},"curvature":-13.610309663954157},{"time":0.16882882891931472,"velocity":0.8193721483899272,"acceleration":9.788836768369139,"pose":{"translation":{"x":3.4489431817569614,"y":-1.1724539947311718},"rotation":{"radians":-1.037888857922356}},"curvature":-12.693389767895697},{"time":0.17589307963882372,"velocity":0.8885229455740351,"acceleration":14.028806760935778,"pose":{"translation":{"x":3.4518128867501217,"y":-1.177760202826674},"rotation":{"radians":-1.1109617733901278}},"curvature":-11.497133978077434},{"time":0.18253357510806822,"velocity":0.9816811733089359,"acceleration":19.11904573956067,"pose":{"translation":{"x":3.454376105030131,"y":-1.1834160238407379},"rotation":{"radians":-1.1782123842054637}},"curvature":-10.152020839072915},{"time":0.18871089003190056,"velocity":1.099785539885357,"acceleration":25.185591459861286,"pose":{"translation":{"x":3.456649512519192,"y":-1.189429580049879},"rotation":{"radians":-1.2390233231447232}},"curvature":-8.774290588471855},{"time":0.19441671438734293,"velocity":1.2434901010432546,"acceleration":32.27206435015343,"pose":{"translation":{"x":3.458650351268351,"y":-1.1958082949153208},"rotation":{"radians":-1.2931851159063472}},"curvature":-7.450872939335512},{"time":0.1996664435011948,"velocity":1.4129096968263561,"acceleration":40.30568661605891,"pose":{"translation":{"x":3.460396329942662,"y":-1.2025588474720275},"rotation":{"radians":-1.340803982831074}},"curvature":-6.236411835290776},{"time":0.20449133814801623,"velocity":1.6073803884166407,"acceleration":53.740275685826795,"pose":{"translation":{"x":3.4619055243063532,"y":-1.209687126717738},"rotation":{"radians":-1.3822025931282806}},"curvature":-5.157967348327374},{"time":0.2129854894967538,"velocity":2.0638584236149353,"acceleration":71.3543118302435,"pose":{"translation":{"x":3.464287101565633,"y":-1.2250961974152026},"rotation":{"radians":-1.4482094847209641}},"curvature":-3.4249694963224426},{"time":0.22031724397529434,"velocity":2.5870107189395015,"acceleration":82.22663254477679,"pose":{"translation":{"x":3.4659432495796945,"y":-1.2420650850283956},"rotation":{"radians":-1.4953067179772608}},"curvature":-2.1909366724396966},{"time":0.2438218365064351,"velocity":4.5197142121123175,"acceleration":-7.5518339561036285,"pose":{"translation":{"x":3.468192668188263,"y":-1.325555125071546},"rotation":{"radians":-1.5652390742470428}},"curvature":-0.10916672029551365},{"time":0.2677899366670382,"velocity":4.338711099456182,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4692222678466824,"y":-1.431709944692168},"rotation":{"radians":-1.5514589466239832}},"curvature":0.22541620669281257},{"time":0.3234971221764526,"velocity":0.0,"acceleration":-77.88422731790946,"pose":{"translation":{"x":3.4729270150046876,"y":-1.5525018368761265},"rotation":{"radians":-1.5333138901032233}},"curvature":4.454736102207827E-14}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":80.76699269765997,"pose":{"translation":{"x":1.0242068983635988,"y":-0.1549999521264185},"rotation":{"radians":-0.014924264990084975}},"curvature":0.0},{"time":0.025609804424775617,"velocity":2.0684268869643523,"acceleration":-21.155814970757113,"pose":{"translation":{"x":1.050678214033299,"y":-0.155881913417109},"rotation":{"radians":-0.06693930018684048}},"curvature":-3.4114914552546445},{"time":0.032803644393329875,"velocity":1.9162353396603813,"acceleration":6.611464338649243,"pose":{"translation":{"x":1.064948717041106,"y":-0.15721368705295774},"rotation":{"radians":-0.12030810077177533}},"curvature":-3.895082466360081},{"time":0.040842065461474814,"velocity":1.9693810738914683,"acceleration":20.933702197658278,"pose":{"translation":{"x":1.0803890767003188,"y":-0.1595566406348458},"rotation":{"radians":-0.1803961258779653}},"curvature":-3.7177180422598464},{"time":0.04925296545483286,"velocity":2.1454523495667117,"acceleration":29.60747444619942,"pose":{"translation":{"x":1.0973094211838648,"y":-0.1631836906287051},"rotation":{"radians":-0.24040394266674808}},"curvature":-3.1928905407395165},{"time":0.057779827766930275,"velocity":2.397911207578397,"acceleration":34.08103398278143,"pose":{"translation":{"x":1.1159816671791125,"y":-0.1683369846189167},"rotation":{"radians":-0.2961605935752694}},"curvature":-2.5748522974238695},{"time":0.06634123060191074,"velocity":2.6896926685376474,"acceleration":34.7124334432402,"pose":{"translation":{"x":1.1366409048026715,"y":-0.17522897523924807},"rotation":{"radians":-0.3457580062863986}},"curvature":-2.0050835227837482},{"time":0.07496542833509111,"velocity":2.9890595583520136,"acceleration":29.946915136341534,"pose":{"translation":{"x":1.1594867825151933,"y":-0.18404349410379134},"rotation":{"radians":-0.38878619951971055}},"curvature":-1.5361154851955572},{"time":0.092799865601637,"velocity":3.52314593767767,"acceleration":20.316759060686696,"pose":{"translation":{"x":1.2123681532587383,"y":-0.20803878150913113},"rotation":{"radians":-0.4570521842006177}},"curvature":-0.897377112453681},{"time":0.11200241195010796,"velocity":3.9132794451912236,"acceleration":12.121023757030521,"pose":{"translation":{"x":1.275566760738191,"y":-0.24126188872979926},"rotation":{"radians":-0.5067439345172463}},"curvature":-0.5409928938872032},{"time":0.13317424852601328,"velocity":4.16990377930774,"acceleration":6.90480129836837,"pose":{"translation":{"x":1.349545154333866,"y":-0.28426265292587083},"rotation":{"radians":-0.5435193504995377}},"curvature":-0.34292793555252027},{"time":0.1566916611587298,"velocity":4.332286840588385,"acceleration":3.9319735410791212,"pose":{"translation":{"x":1.4343317687515507,"y":-0.3372360723126428},"rotation":{"radians":-0.5715034441142186}},"curvature":-0.2297206976838789},{"time":0.1827183894169434,"velocity":4.434623247460538,"acceleration":2.5936952749045616,"pose":{"translation":{"x":1.5295652412961114,"y":-0.4000566719506442},"rotation":{"radians":-0.5934879292510035}},"curvature":-0.1626345369425383},{"time":0.19666826742095458,"velocity":4.4708049801250365,"acceleration":1.9886980096395166,"pose":{"translation":{"x":1.5808909445009771,"y":-0.43504128127314967},"rotation":{"radians":-0.6028413229938115}},"curvature":-0.13965064284099912},{"time":0.2112323836377278,"velocity":4.499768609057492,"acceleration":1.5336432363557886,"pose":{"translation":{"x":1.634538729145096,"y":-0.472312869535646},"rotation":{"radians":-0.6113438731482959}},"curvature":-0.12151830617487935},{"time":0.2263886445797095,"velocity":4.523012906139606,"acceleration":1.188198673442852,"pose":{"translation":{"x":1.6903735294084679,"y":-0.5117809228117848},"rotation":{"radians":-0.6191387196362657}},"curvature":-0.10713445715936788},{"time":0.24210853089120857,"velocity":4.541691254201601,"acceleration":0.9230363077806585,"pose":{"translation":{"x":1.748244226622337,"y":-0.5533413411886713},"rotation":{"radians":-0.6263458426140492}},"curvature":-0.09568276311179288},{"time":0.2583578665211356,"velocity":4.556689980965338,"acceleration":0.7168404321502287,"pose":{"translation":{"x":1.8079850341839898,"y":-0.5968775126978025},"rotation":{"radians":-0.6330667663073747}},"curvature":-0.0865550073435694},{"time":0.2750975094493898,"velocity":4.568689633836068,"acceleration":0.5540582852879005,"pose":{"translation":{"x":1.8694168824715565,"y":-0.6422613872460049},"rotation":{"radians":-0.6393883221634832}},"curvature":-0.07929554842622359},{"time":0.29228398071991496,"velocity":4.578211940638365,"acceleration":0.42325474807225716,"pose":{"translation":{"x":1.9323488037588106,"y":-0.6893545505463726},"rotation":{"radians":-0.6453856748471296}},"curvature":-0.0735618964657416},{"time":0.30987004541523744,"velocity":4.585655326020566,"acceleration":0.3159246834429844,"pose":{"translation":{"x":1.9965793171299688,"y":-0.7380092980492045},"rotation":{"radians":-0.65112477533599}},"curvature":-0.06909660399485994},{"time":0.32780525650741293,"velocity":4.591321501907345,"acceleration":0.22563867391089165,"pose":{"translation":{"x":2.0618978133944914,"y":-0.7880697088729425},"rotation":{"radians":-0.6566643720711324}},"curvature":-0.0657071663771941},{"time":0.34603647031814,"velocity":4.595435168815383,"acceleration":0.14742576911862446,"pose":{"translation":{"x":2.128085940001884,"y":-0.839372719735109},"rotation":{"radians":-0.6620576842842592}},"curvature":-0.06325165765214856},{"time":0.3645083405905348,"velocity":4.59815839849735,"acceleration":0.07732154341794786,"pose":{"translation":{"x":2.1949189859564937,"y":-0.891749198883246},"rotation":{"radians":-0.6673538206949008}},"curvature":-0.061628538480436416},{"time":0.3831637968549877,"velocity":4.599600867168884,"acceleration":0.01202897597466842,"pose":{"translation":{"x":2.2621672667323134,"y":-0.9450250200258506},"rotation":{"radians":-0.6725990108733612}},"curvature":-0.06076956645238116},{"time":0.4019445117952919,"velocity":4.599826779937688,"acceleration":-0.05134643121218473,"pose":{"translation":{"x":2.3295975091877787,"y":-0.9990221362633144},"rotation":{"radians":-0.6778377048334125}},"curvature":-0.06063508702204383},{"time":0.4207913616307893,"velocity":4.598859061459043,"acceleration":-0.11551640937741646,"pose":{"translation":{"x":2.396974236480571,"y":-1.0535596540188625},"rotation":{"radians":-0.6831135881205861}},"curvature":-0.061211235160974556},{"time":0.43964488308120203,"velocity":4.596681170356971,"acceleration":-0.1832077196231995,"pose":{"translation":{"x":2.4640611529824143,"y":-1.108454906969488},"rotation":{"radians":-0.6884705542364015}},"curvature":-0.06250876808175994},{"time":0.4584457302398705,"velocity":4.5932367100220475,"acceleration":-0.25735804364112175,"pose":{"translation":{"x":2.530622529193878,"y":-1.1635245299768913},"rotation":{"radians":-0.6939536732962518}},"curvature":-0.06456340310101423},{"time":0.4771351346320946,"velocity":4.588426841470847,"acceleration":-0.3413293051820923,"pose":{"translation":{"x":2.596424586659176,"y":-1.2185855330184205},"rotation":{"radians":-0.6996101951300101}},"curvature":-0.06743767120729748},{"time":0.49565537187010267,"velocity":4.58210534176259,"acceleration":-0.4391592408085358,"pose":{"translation":{"x":2.661236882880967,"y":-1.2734563751180061},"rotation":{"radians":-0.7054906265203724}},"curvature":-0.07122443266535772},{"time":0.5139502386413288,"velocity":4.574070981960645,"acceleration":-0.55587571035062,"pose":{"translation":{"x":2.7248336962351547,"y":-1.3279580382770977},"rotation":{"radians":-0.711649925996724}},"curvature":-0.07605235210334034},{"time":0.5319655442991419,"velocity":4.564056711130925,"acceleration":-0.6979041874500918,"pose":{"translation":{"x":2.7869954108856856,"y":-1.3819151014056064},"rotation":{"radians":-0.7181488657617937}},"curvature":-0.08209381492673395},{"time":0.5496496220924428,"velocity":4.551714919187787,"acceleration":-0.8736070962717432,"pose":{"translation":{"x":2.8475099016993557,"y":-1.4351568142528388},"rotation":{"radians":-0.7250556192580382}},"curvature":-0.089576006814548},{"time":0.566953866110386,"velocity":4.536597808818094,"acceleration":-1.0940036642771789,"pose":{"translation":{"x":2.906173919160599,"y":-1.4875181713384364},"rotation":{"radians":-0.7324476450365182}},"curvature":-0.09879620292355824},{"time":0.5838333013741773,"velocity":4.518131644788577,"acceleration":-1.3737288809187866,"pose":{"translation":{"x":2.962794474286303,"y":-1.5388409858833139},"rotation":{"radians":-0.7404139535163994}},"curvature":-0.11014276350833384},{"time":0.6002471962202129,"velocity":4.495583403390214,"acceleration":-1.7322949595692405,"pose":{"translation":{"x":3.017190223540596,"y":-1.5889749637405925},"rotation":{"radians":-0.7490578634583538}},"curvature":-0.12412396332287678},{"time":0.616159728206077,"velocity":4.468018204437117,"acceleration":-2.1957066260189535,"pose":{"translation":{"x":3.0691928537496507,"y":-1.6377787773265464},"rotation":{"radians":-0.7585003798474376}},"curvature":-0.1414076683227251},{"time":0.631540717187749,"velocity":4.434246065015335,"acceleration":-2.7984274125160087,"pose":{"translation":{"x":3.118648467016489,"y":-1.6851211395515324},"rotation":{"radians":-0.7688843540542437}},"curvature":-0.16287611175991407},{"time":0.6463664417709616,"velocity":4.3927573509312605,"acceleration":-3.5855478834013743,"pose":{"translation":{"x":3.1654189656357747,"y":-1.7308818777509312},"rotation":{"radians":-0.780379618688889}},"curvature":-0.18970172617171252},{"time":0.660620557531351,"velocity":4.341648536336838,"acceleration":-5.2656848478974805,"pose":{"translation":{"x":3.2093834370086203,"y":-1.7749530076160867},"rotation":{"radians":-0.7931893181036281}},"curvature":-0.22345225928509624},{"time":0.6874191929068241,"velocity":4.20053536809588,"acceleration":-8.755975906034498,"pose":{"translation":{"x":3.288504882640466,"y":-1.8576618904744684},"rotation":{"radians":-0.8237793533054495}},"curvature":-0.32090295413693193},{"time":0.7119809342601576,"velocity":3.9854733525958403,"acceleration":-14.180452459633708,"pose":{"translation":{"x":3.3554418320122448,"y":-1.9326684901522855},"rotation":{"radians":-0.8632819252242124}},"curvature":-0.4826945143136867},{"time":0.7345635800267775,"velocity":3.665241217889539,"acceleration":-21.13365091006073,"pose":{"translation":{"x":3.4099869094745,"y":-1.9996572539505455},"rotation":{"radians":-0.9155135569606806}},"curvature":-0.7587898983103346},{"time":0.7556505892742572,"velocity":3.219595725716079,"acceleration":-25.887668679860443,"pose":{"translation":{"x":3.4523406529017313,"y":-2.05861074023567},"rotation":{"radians":-0.9858015283733543}},"curvature":-1.2344123210490974},{"time":0.7658230995484007,"velocity":2.956253150096577,"acceleration":-27.37800202037828,"pose":{"translation":{"x":3.469130887496254,"y":-2.0851587757508963},"rotation":{"radians":-1.0297380383227297}},"curvature":-1.5828738378965297},{"time":0.775896767870847,"velocity":2.68045623841202,"acceleration":-26.763717732857412,"pose":{"translation":{"x":3.483155830965993,"y":-2.1098439842295025},"rotation":{"radians":-1.080581446105553}},"curvature":-2.0212185415768835},{"time":0.7859548722953983,"velocity":2.4112639706657264,"acceleration":-23.67849844154621,"pose":{"translation":{"x":3.4945750112597773,"y":-2.132763332720299},"rotation":{"radians":-1.1387839124803456}},"curvature":-2.545767235283315},{"time":0.7960352682601854,"velocity":2.172575330523345,"acceleration":-18.09139329185749,"pose":{"translation":{"x":3.50358176041047,"y":-2.1540388637993244},"rotation":{"radians":-1.2040990274245273}},"curvature":-3.1196046435807454},{"time":0.8060866880285056,"velocity":1.990731142353115,"acceleration":-9.793077589690121,"pose":{"translation":{"x":3.510404599449802,"y":-2.173818769500745},"rotation":{"radians":-1.2750358682090688}},"curvature":-3.6491323370511024},{"time":0.8159189341865687,"velocity":1.8944431928462704,"acceleration":3.010299278337512,"pose":{"translation":{"x":3.5153086233231274,"y":-2.1922784652478495},"rotation":{"radians":-1.3482697163467114}},"curvature":-3.9706867305066895},{"time":0.8251688243850291,"velocity":1.9222881306353972,"acceleration":27.93818099146828,"pose":{"translation":{"x":3.5185968858042624,"y":-2.209621663783926},"rotation":{"radians":-1.4183035447344245}},"curvature":-3.874387484326945},{"time":0.8333133087406257,"velocity":2.149830208644237,"acceleration":-73.58171418463397,"pose":{"translation":{"x":3.520611784410261,"y":-2.2260814491032495},"rotation":{"radians":-1.4777643315520235}},"curvature":-3.1809364802236244},{"time":0.86253021721397,"velocity":0.0,"acceleration":-73.58171418463397,"pose":{"translation":{"x":3.5223961082701587,"y":-2.2574364159091713},"rotation":{"radians":-1.533313890103249}},"curvature":-5.903430769592215E-14}] \ No newline at end of file From 6016fb32dd4f14edf3e14703662f35113c4e3a60 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Thu, 5 Mar 2020 18:49:36 -0600 Subject: [PATCH 23/31] Figured out how to run multiple paths by passing a desired path in --- src/Autonomous/Actions/PathFinder.cpp | 6 +++--- src/Autonomous/Actions/PathFinder.h | 2 +- src/RobotContainer.cpp | 8 ++------ src/RobotContainer.h | 3 +-- src/autonomous/Auton.cpp | 2 +- 5 files changed, 8 insertions(+), 13 deletions(-) diff --git a/src/Autonomous/Actions/PathFinder.cpp b/src/Autonomous/Actions/PathFinder.cpp index 83940c6..366d175 100644 --- a/src/Autonomous/Actions/PathFinder.cpp +++ b/src/Autonomous/Actions/PathFinder.cpp @@ -1,8 +1,8 @@ #include "PathFinder.h" #include "Robot.h" -PathFinderAction::PathFinderAction() { - // m_path = path; +PathFinderAction::PathFinderAction(std::string path) { + m_path = path; } void PathFinderAction::ActionInit() { @@ -11,7 +11,7 @@ void PathFinderAction::ActionInit() { CORE::COREAutonAction::actionStatus PathFinderAction::Action() { Robot::GetInstance()->m_driveSubsystem.auton(); - m_autonomousCommand = Robot::GetInstance()->m_container.GetAutonomousCommand(); + m_autonomousCommand = Robot::GetInstance()->m_container.GetAutonomousCommand(m_path); if (m_autonomousCommand != nullptr) { m_autonomousCommand->Schedule(); } diff --git a/src/Autonomous/Actions/PathFinder.h b/src/Autonomous/Actions/PathFinder.h index 9cb5593..b43c881 100644 --- a/src/Autonomous/Actions/PathFinder.h +++ b/src/Autonomous/Actions/PathFinder.h @@ -9,7 +9,7 @@ using namespace CORE; class PathFinderAction : public COREAutonAction { public: - explicit PathFinderAction(); + explicit PathFinderAction(std::string path); void ActionInit() override; actionStatus Action() override; void ActionEnd() override; diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 47f0474..748bdd2 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -25,11 +25,7 @@ RobotContainer::RobotContainer() { {&m_drive})); } -frc2::Command* RobotContainer::GetTeleopDriveCommand() { - m_drive.teleop(); -} - -frc2::Command* RobotContainer::GetAutonomousCommand() { +frc2::Command* RobotContainer::GetAutonomousCommand(std::string path) { // Create a voltage constraint to ensure we don't accelerate too fast frc::DifferentialDriveVoltageConstraint autoVoltageConstraint( frc::SimpleMotorFeedforward( @@ -48,7 +44,7 @@ frc2::Command* RobotContainer::GetAutonomousCommand() { wpi::SmallString<64> deployDirectory; frc::filesystem::GetDeployDirectory(deployDirectory); wpi::sys::path::append(deployDirectory, "paths"); - wpi::sys::path::append(deployDirectory, "right.wpilib.json"); + wpi::sys::path::append(deployDirectory, path); frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); frc2::RamseteCommand ramseteCommand( diff --git a/src/RobotContainer.h b/src/RobotContainer.h index acb2ffb..39d1a8b 100644 --- a/src/RobotContainer.h +++ b/src/RobotContainer.h @@ -23,8 +23,7 @@ class RobotContainer { public: RobotContainer(); - frc2::Command* GetAutonomousCommand(); - frc2::Command* GetTeleopDriveCommand(); + frc2::Command* GetAutonomousCommand(std::string path); private: diff --git a/src/autonomous/Auton.cpp b/src/autonomous/Auton.cpp index a7300f3..bb067bf 100644 --- a/src/autonomous/Auton.cpp +++ b/src/autonomous/Auton.cpp @@ -3,6 +3,6 @@ Autonomous::Autonomous() : COREAuton("Test Auto") {} void Autonomous::AddNodes() { - m_drivePath = new Node(5, new PathFinderAction()); + m_drivePath = new Node(5, new PathFinderAction("example.wpilib.json")); AddFirstNode(m_drivePath); } From b96632bd5cc157f51c8d633788bcb03fc55f2a3c Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Thu, 5 Mar 2020 20:37:27 -0600 Subject: [PATCH 24/31] Added extra autons and updated some paths --- PathWeaver/Paths/example.path | 2 +- PathWeaver/output/example.wpilib.json | 2 +- src/Autonomous/SecondAuton.cpp | 12 ++++++++++++ src/Autonomous/SecondAuton.h | 18 ++++++++++++++++++ src/autonomous/Auton.cpp | 4 +++- src/autonomous/Auton.h | 1 + src/main/deploy/paths/example.wpilib.json | 2 +- 7 files changed, 37 insertions(+), 4 deletions(-) create mode 100644 src/Autonomous/SecondAuton.cpp create mode 100644 src/Autonomous/SecondAuton.h diff --git a/PathWeaver/Paths/example.path b/PathWeaver/Paths/example.path index 21caaf4..927cdd1 100644 --- a/PathWeaver/Paths/example.path +++ b/PathWeaver/Paths/example.path @@ -1,3 +1,3 @@ X,Y,Tangent X,Tangent Y,Fixed Theta,Name 0.0,0.0,3.048,0.0,true, -15.23876963475554,-5.0266196237355265,3.16950164983399,-0.06852976540181599,true, +4.05128543290908,-2.2854290076628865,2.0730254034049302,3.871931745202603,true, diff --git a/PathWeaver/output/example.wpilib.json b/PathWeaver/output/example.wpilib.json index 42fb442..b57c712 100644 --- a/PathWeaver/output/example.wpilib.json +++ b/PathWeaver/output/example.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":71.6754486328193,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.052504537201690564,"velocity":3.763286259189722,"acceleration":3.393027875765885,"pose":{"translation":{"x":0.0987840856718992,"y":-0.0014550809384724233},"rotation":{"radians":-0.0406235201304543}},"curvature":-0.669267331858832},{"time":0.08369849591678691,"velocity":3.869128230665534,"acceleration":8.940395462782044,"pose":{"translation":{"x":0.21743610778889016,"y":-0.011090481290308164},"rotation":{"radians":-0.11922715157584657}},"curvature":-0.5777181959580991},{"time":0.10210103517690408,"velocity":4.033654209170354,"acceleration":7.7520539423460715,"pose":{"translation":{"x":0.2894547521368349,"y":-0.021134285931893225},"rotation":{"radians":-0.15629119482489962}},"curvature":-0.4449483653936229},{"time":0.12254133010230119,"velocity":4.192108478029495,"acceleration":5.75700633123382,"pose":{"translation":{"x":0.3722655413186195,"y":-0.035621769310835674},"rotation":{"radians":-0.18844460732445098}},"curvature":-0.3269300330427504},{"time":0.14533768211239437,"velocity":4.3233472208806365,"acceleration":3.944401761401226,"pose":{"translation":{"x":0.4673396090946371,"y":-0.055158757396353585},"rotation":{"radians":-0.21542702352704587}},"curvature":-0.2357318596690303},{"time":0.17082259532410582,"velocity":4.423869957442069,"acceleration":2.8844388002223487,"pose":{"translation":{"x":0.5759365232228123,"y":-0.08026398863855952},"rotation":{"radians":-0.23772289170313524}},"curvature":-0.16953787250521077},{"time":0.18466411165336516,"velocity":4.4637949641960954,"acceleration":2.326862827367757,"pose":{"translation":{"x":0.635643814194672,"y":-0.09504381204755785},"rotation":{"radians":-0.24733668078881516}},"curvature":-0.14407454738817005},{"time":0.1992899012288189,"velocity":4.497827170280122,"acceleration":1.8726028175616212,"pose":{"translation":{"x":0.6991124192700513,"y":-0.11137246160318348},"rotation":{"radians":-0.2560512882871814}},"curvature":-0.12272641890725453},{"time":0.21473112059424881,"velocity":4.526742441170413,"acceleration":1.5061957817442015,"pose":{"translation":{"x":0.766443903568408,"y":-0.1292917769905396},"rotation":{"radians":-0.2639545845640026}},"curvature":-0.1048403284194074},{"time":0.23101567055964584,"velocity":4.551270161635896,"acceleration":1.2125328488063274,"pose":{"translation":{"x":0.8377281344236926,"y":-0.14883878260629593},"rotation":{"radians":-0.27112822180522567}},"curvature":-0.08984639789950959},{"time":0.2481681966511829,"velocity":4.572068162961893,"acceleration":0.9780339853892758,"pose":{"translation":{"x":0.9130435355659563,"y":-0.1700457921722737},"rotation":{"radians":-0.2776468756372453}},"curvature":-0.07725850624670107},{"time":0.2662101398397362,"velocity":4.58971379656276,"acceleration":0.7910806745495272,"pose":{"translation":{"x":0.9924573413029585,"y":-0.19294051334903078},"rotation":{"radians":-0.2835780974936386}},"curvature":-0.06666802579853986},{"time":0.28515981743654306,"velocity":4.604704520298538,"acceleration":0.6420396874172175,"pose":{"translation":{"x":1.0760258507017746,"y":-0.21754615234944685},"rotation":{"radians":-0.2889825347232104}},"curvature":-0.057734725453877866},{"time":0.30503252074980275,"velocity":4.617463584521919,"acceleration":0.5230871945044425,"pose":{"translation":{"x":1.1637946817704043,"y":-0.24388151855230836},"rotation":{"radians":-0.29391435676502015}},"curvature":-0.050177014396362525},{"time":0.32584062079799275,"velocity":4.628348035199094,"acceleration":0.42795546527859657,"pose":{"translation":{"x":1.2557990256393792,"y":-0.2719611291158937},"rotation":{"radians":-0.29842178249670276}},"curvature":-0.04376264842952715},{"time":0.3475936765970335,"velocity":4.637657374314804,"acceleration":0.35166819045207165,"pose":{"translation":{"x":1.3520639007433704,"y":-0.3017953135915584},"rotation":{"radians":-0.30254764263473954}},"curvature":-0.03830040704132812},{"time":0.37029854270166584,"velocity":4.645641953492277,"acceleration":0.29029645766093237,"pose":{"translation":{"x":1.4526044070027964,"y":-0.33339031853731993},"rotation":{"radians":-0.3063299370432376}},"curvature":-0.03363290685993953},{"time":0.3939594741066458,"velocity":4.652510638064101,"acceleration":0.24074807079349372,"pose":{"translation":{"x":1.5574259800054309,"y":-0.36674841213144305},"rotation":{"radians":-0.3098023639018164}},"curvature":-0.02963053745593578},{"time":0.4185782275335135,"velocity":4.65843755545696,"acceleration":0.2005926419332328,"pose":{"translation":{"x":1.666524645188012,"y":-0.4018679887860249},"rotation":{"radians":-0.3129948087165449}},"curvature":-0.026186420205458822},{"time":0.4441541587084636,"velocity":4.6635678990612455,"acceleration":0.16791995076836871,"pose":{"translation":{"x":1.7798872720178476,"y":-0.4387436737605798},"rotation":{"radians":-0.31593378811677125}},"curvature":-0.023212258501245673},{"time":0.4706843155906152,"velocity":4.6680228416987735,"acceleration":0.1473081055449243,"pose":{"translation":{"x":1.8974918281744246,"y":-0.477366427775625},"rotation":{"radians":-0.3186428476369191}},"curvature":-0.020634943232970684},{"time":0.48430557417763576,"velocity":4.670029363496365,"acceleration":0.13525227729273576,"pose":{"translation":{"x":1.9578755731199786,"y":-0.49732915462086014},"rotation":{"radians":-0.31991779085791866}},"curvature":-0.01947571752148467},{"time":0.4981632894321226,"velocity":4.671903651042609,"acceleration":0.12432688548768328,"pose":{"translation":{"x":2.019307633731017,"y":-0.5177236516262647},"rotation":{"radians":-0.3211429151700534}},"curvature":-0.018393786838207256},{"time":0.5122564819575298,"velocity":4.673655813775871,"acceleration":0.11441569818551017,"pose":{"translation":{"x":2.081782865529898,"y":-0.538547804816047},"rotation":{"radians":-0.3223204787561041}},"curvature":-0.017383137392378067},{"time":0.5265840442775498,"velocity":4.675295111822012,"acceleration":0.10541529555668874,"pose":{"translation":{"x":2.145295615336293,"y":-0.5597992907957762},"rotation":{"radians":-0.3234526131282243}},"curvature":-0.01643827432726884},{"time":0.5411447433384899,"velocity":4.676830032217033,"acceleration":0.0972335891691984,"pose":{"translation":{"x":2.20983972921036,"y":-0.5814755800215547},"rotation":{"radians":-0.3245413308852529}},"curvature":-0.015554173193681813},{"time":0.5559372229684437,"velocity":4.678268358104166,"acceleration":0.08978851658604482,"pose":{"translation":{"x":2.275408560395923,"y":-0.6035739400691946},"rotation":{"radians":-0.3255885329724584}},"curvature":-0.014726236202830386},{"time":0.5709600062957906,"velocity":4.679617231534122,"acceleration":0.0830068906946886,"pose":{"translation":{"x":2.3419949772636413,"y":-0.6260914389033911},"rotation":{"radians":-0.32659601547299605}},"curvature":-0.013950252777561888},{"time":0.5862114981295551,"velocity":4.680883210449698,"acceleration":0.07682338543969686,"pose":{"translation":{"x":2.4095913712541885,"y":-0.6490249481468979},"rotation":{"radians":-0.3275654759594006}},"curvature":-0.013222363967972418},{"time":0.6016899873039058,"velocity":4.682072320389564,"acceleration":0.07117964169334849,"pose":{"translation":{"x":2.4781896648214286,"y":-0.6723711463497003},"rotation":{"radians":-0.3284985194323406}},"curvature":-0.012539030340552192},{"time":0.6173936489891477,"velocity":4.683190101401593,"acceleration":0.06602347886871857,"pose":{"translation":{"x":2.547781319375588,"y":-0.6961265222581916},"rotation":{"radians":-0.32939666387264166}},"curvature":-0.011897002989255367},{"time":0.6333205469712927,"velocity":4.684241650613961,"acceleration":0.061308199557898,"pose":{"translation":{"x":2.618357343226433,"y":-0.7202873780843462},"rotation":{"radians":-0.3302613454313242}},"curvature":-0.011293297352516853},{"time":0.6494686359022924,"velocity":4.685231660872621,"acceleration":0.056991975988469196,"pose":{"translation":{"x":2.6899082995264454,"y":-0.7448498327748948},"rotation":{"radians":-0.33109392328110016}},"curvature":-0.010725169552478188},{"time":0.6658357635228018,"velocity":4.68616445581697,"acceleration":0.05303730842556608,"pose":{"translation":{"x":2.762424314213996,"y":-0.7698098252804986},"rotation":{"radians":-0.33189568415147325}},"curvature":-0.010190095001780771},{"time":0.6824196728593326,"velocity":4.687044021731353,"acceleration":0.04941054684157204,"pose":{"translation":{"x":2.8358950839565202,"y":-0.7951631178249241},"rotation":{"radians":-0.332667846568304}},"curvature":-0.009685749049497792},{"time":0.699218004397476,"velocity":4.687874036478679,"acceleration":0.046081468224634096,"pose":{"translation":{"x":2.9103098840936954,"y":-0.8209052991742178},"rotation":{"radians":-0.3334115648174423}},"curvature":-0.009209989461344641},{"time":0.7162282982327365,"velocity":4.68865789579354,"acceleration":0.04302290282954284,"pose":{"translation":{"x":2.9856575765806124,"y":-0.8470317879058803},"rotation":{"radians":-0.3341279326508223}},"curvature":-0.008760840550476132},{"time":0.7334479962006001,"velocity":4.689398737185965,"acceleration":0.04021040348993698,"pose":{"translation":{"x":3.061926617930954,"y":-0.8735378356780407},"rotation":{"radians":-0.3348179867522378}},"curvature":-0.008336478794167414},{"time":0.7508744439870677,"velocity":4.6900994616828555,"acceleration":0.03762195283333545,"pose":{"translation":{"x":3.13910506716017,"y":-0.9004185304986319},"rotation":{"radians":-0.33548270997890794}},"curvature":-0.007935219788693488},{"time":0.7685048932210419,"velocity":4.690762753612367,"acceleration":0.03523770386995457,"pose":{"translation":{"x":3.2171805937286497,"y":-0.927668799994564},"rotation":{"radians":-0.33612303439387825}},"curvature":-0.007555506409969931},{"time":0.7863365035498443,"velocity":4.691391098616657,"acceleration":0.033039749987155066,"pose":{"translation":{"x":3.296140485484901,"y":-0.9552834146809005},"rotation":{"radians":-0.3367398441032938}},"curvature":-0.007195898061161926},{"time":0.8043663446988317,"velocity":4.691986800060528,"acceleration":0.03101192085748364,"pose":{"translation":{"x":3.3759716566087206,"y":-0.983256991230031},"rotation":{"radians":-0.3373339779116408}},"curvature":-0.006855060900686268},{"time":0.8225913985163283,"velocity":4.69255199398714,"acceleration":0.029139601208403573,"pose":{"translation":{"x":3.4566606555543737,"y":-1.011583995740847},"rotation":{"radians":-0.3379062318071501}},"curvature":-0.00653175895495657},{"time":0.8410085610047663,"velocity":4.693088662757443,"acceleration":0.027409569760689707,"pose":{"translation":{"x":3.5381936729937724,"y":-1.0402587470079157},"rotation":{"radians":-0.3384573612887194}},"curvature":-0.006224846030001168},{"time":0.8596146443389476,"velocity":4.6935986474965645,"acceleration":0.025809855984173163,"pose":{"translation":{"x":3.6205565497596375,"y":-1.069275419790655},"rotation":{"radians":-0.3389880835449301}},"curvature":-0.005933258344827627},{"time":0.8784063788723748,"velocity":4.694083659458565,"acceleration":0.02432961259209342,"pose":{"translation":{"x":3.70373478478869,"y":-1.0986280480825084},"rotation":{"radians":-0.3394990794949884}},"curvature":-0.0056560078172345615},{"time":0.897380415132286,"velocity":4.694545290410077,"acceleration":0.022959001958506343,"pose":{"translation":{"x":3.7877135430648137,"y":-1.1283105283801182},"rotation":{"radians":-0.3399909957007404}},"curvature":-0.005392175939770404},{"time":0.9165333258042762,"velocity":4.694985022123706,"acceleration":0.021689094852614006,"pose":{"translation":{"x":3.872477663562239,"y":-1.1583166229525013},"rotation":{"radians":-0.34046444615826527}},"curvature":-0.00514090818980659},{"time":0.9358616077071303,"velocity":4.6954042350632355,"acceleration":0.020511780085435836,"pose":{"translation":{"x":3.9580116671887158,"y":-1.1886399631102225},"rotation":{"radians":-0.34092001397695176}},"curvature":-0.004901408923299515},{"time":0.9553616837584529,"velocity":4.6958042163348495,"acceleration":0.01941968382425391,"pose":{"translation":{"x":4.044299764728684,"y":-1.2192740524745713},"rotation":{"radians":-0.34135825295340627}},"curvature":-0.004672936706836661},{"time":0.9750299049318558,"velocity":4.696186166971422,"acceleration":0.018406097485132958,"pose":{"translation":{"x":4.131325864786455,"y":-1.250212270246734},"rotation":{"radians":-0.34177968904702144}},"curvature":-0.004454800047062241},{"time":0.9948625522059731,"velocity":4.696551208610538,"acceleration":0.017464913239636663,"pose":{"translation":{"x":4.219073581729384,"y":-1.281447874476969},"rotation":{"radians":-0.3421848217635512}},"curvature":-0.004246353480603635},{"time":1.0148558385061224,"velocity":4.696900389621145,"acceleration":0.01659056628522065,"pose":{"translation":{"x":4.3075262436310435,"y":-1.312974005333782},"rotation":{"radians":-0.3425741254525841}},"curvature":-0.00404699399123586},{"time":1.0350059106388894,"velocity":4.697234690728516,"acceleration":0.015777983132407462,"pose":{"translation":{"x":4.396666900214407,"y":-1.3447836883730995},"rotation":{"radians":-0.3429480505243987}},"curvature":-0.0038561577242561726},{"time":1.0553088512201658,"velocity":4.697555030182546,"acceleration":0.015022535243084308,"pose":{"translation":{"x":4.48647833079501,"y":-1.3768698378074444},"rotation":{"radians":-0.34330702459128587}},"curvature":-0.003673316970948526},{"time":1.0757606805969266,"velocity":4.697862268510144,"acceleration":0.014319997438426777,"pose":{"translation":{"x":4.576943052224139,"y":-1.4092252597751103},"rotation":{"radians":-0.34365145353806514}},"curvature":-0.003497977398624211},{"time":1.0963573587634323,"velocity":4.698157212888728,"acceleration":0.013666510556798168,"pose":{"translation":{"x":4.668043326831998,"y":-1.4418426556093347},"rotation":{"radians":-0.3439817225261905}},"curvature":-0.00332967550406501},{"time":1.117094787271751,"velocity":4.698440621174358,"acceleration":0.013058547904707297,"pose":{"translation":{"x":4.759761170370888,"y":-1.474714625107476},"rotation":{"radians":-0.3442981969355225}},"curvature":-0.0031679762702993635},{"time":1.1379688111373605,"velocity":4.698713205614971,"acceleration":0.012492885094505708,"pose":{"translation":{"x":4.852078359958381,"y":-1.507833669800185},"rotation":{"radians":-0.3446012232475584}},"curvature":-0.00301247100853054},{"time":1.1589752207398896,"velocity":4.6989756362763835,"acceleration":0.011966572911404053,"pose":{"translation":{"x":4.944976442020495,"y":-1.5411921962205826},"rotation":{"radians":-0.34489112987363685}},"curvature":-0.0028627753687348653},{"time":1.1801097537194458,"velocity":4.699228544206232,"acceleration":0.011476912888864071,"pose":{"translation":{"x":5.03843674023487,"y":-1.5747825191734315},"rotation":{"radians":-0.3451682279313891}},"curvature":-0.002718527503976295},{"time":1.201368096868549,"velocity":4.699472524358716,"acceleration":0.011021435311205923,"pose":{"translation":{"x":5.13244036347394,"y":-1.608596865004313},"rotation":{"radians":-0.3454328119724706}},"curvature":-0.0025793863748584827},{"time":1.2227458880201547,"velocity":4.6997081383009895,"acceleration":0.010597879392235597,"pose":{"translation":{"x":5.226968213748115,"y":-1.6426273748688005},"rotation":{"radians":-0.3456851606643893}},"curvature":-0.002445030181772817},{"time":1.2442387179320789,"velocity":4.699935916720194,"acceleration":0.01020417540646546,"pose":{"translation":{"x":5.322000994148948,"y":-1.676866108001632},"rotation":{"radians":-0.34592553742904764}},"curvature":-0.0023151549137154226},{"time":1.2658421321675262,"velocity":4.700156361748431,"acceleration":0.009838428575118652,"pose":{"translation":{"x":5.41751921679232,"y":-1.7113050449858913},"rotation":{"radians":-0.34615419104042433}},"curvature":-0.002189473003451237},{"time":1.2875516329725323,"velocity":4.7003699491215025,"acceleration":0.009498904530761338,"pose":{"translation":{"x":5.513503210761603,"y":-1.7459360910221728},"rotation":{"radians":-0.3463713561836444}},"curvature":-0.002067712079705491},{"time":1.3093626811503483,"velocity":4.700577130185859,"acceleration":0.009184016203396412,"pose":{"translation":{"x":5.609933130050849,"y":-1.7807510791977645},"rotation":{"radians":-0.34657725397752587}},"curvature":-0.001949613807880811},{"time":1.3312706979323152,"velocity":4.700778333766969,"acceleration":0.008892311988809397,"pose":{"translation":{"x":5.70678896150795,"y":-1.8157417737558181},"rotation":{"radians":-0.3467720924625369}},"curvature":-0.0018349328115315432},{"time":1.353271066846537,"velocity":4.7009739679112235,"acceleration":0.008622465074958126,"pose":{"translation":{"x":5.804050532777829,"y":-1.8508998733645248},"rotation":{"radians":-0.34695606705594856}},"curvature":-0.0017234356674891186},{"time":1.3753591355835073,"velocity":4.701164421512481,"acceleration":0.00837326381556048,"pose":{"translation":{"x":5.901697520245603,"y":-1.8862170143862897},"rotation":{"radians":-0.3471293609758433}},"curvature":-0.0016148999681312745},{"time":1.3975302178590974,"velocity":4.701350065833451,"acceleration":0.008143603052542164,"pose":{"translation":{"x":5.999709456979765,"y":-1.9216847741469065},"rotation":{"radians":-0.34729214563550515}},"curvature":-0.0015091134448230758},{"time":1.419779595275509,"velocity":4.701531255931297,"acceleration":0.007932476300126834,"pose":{"translation":{"x":6.098065740675358,"y":-1.9572946742047326},"rotation":{"radians":-0.34744458100960596}},"curvature":-0.001405873147046175},{"time":1.442102519179547,"velocity":4.701708331996115,"acceleration":0.007738968711621765,"pose":{"translation":{"x":6.196745641597146,"y":-1.9930381836198596},"rotation":{"radians":-0.34758681597348584}},"curvature":-0.001304984672166229},{"time":1.4644942125187514,"velocity":4.701881620610267,"acceleration":0.007562250761078728,"pose":{"translation":{"x":6.295728310522794,"y":-2.028906722223296},"rotation":{"radians":-0.34771898861672773}},"curvature":-0.001206261441183089},{"time":1.4869498716956224,"velocity":4.702051435935968,"acceleration":0.007401572575570495,"pose":{"translation":{"x":6.394992786686045,"y":-2.064891663886134},"rotation":{"radians":-0.34784122653211924}},"curvature":-0.001109524016160343},{"time":1.5094646684197912,"velocity":4.702218080837946,"acceleration":0.007256258868360784,"pose":{"translation":{"x":6.494518005719888,"y":-2.1009843397887265},"rotation":{"radians":-0.34795364708101434}},"curvature":-0.0010145994553500933},{"time":1.5320337515578726,"velocity":4.702381847947618,"acceleration":0.007125704417549445,"pose":{"translation":{"x":6.594282807599738,"y":-2.1371760416898637},"rotation":{"radians":-0.348056357636004}},"curvature":-9.213207023082924E-4},{"time":1.5546522489821248,"velocity":4.702543020674632,"acceleration":0.007009370055230198,"pose":{"translation":{"x":6.694265944586614,"y":-2.173458025195944},"rotation":{"radians":-0.3481494558017369}},"curvature":-8.295260055553096E-4},{"time":1.5773152694167862,"velocity":4.702701874171428,"acceleration":0.006906779123471565,"pose":{"translation":{"x":6.794446089170307,"y":-2.2098215130301524},"rotation":{"radians":-0.34823302961464364}},"curvature":-7.390583655584746E-4},{"time":1.6000179042829614,"velocity":4.702858676255969,"acceleration":0.00681751436758972,"pose":{"translation":{"x":6.894801842012562,"y":-2.246257698301633},"rotation":{"radians":-0.3483071577222395}},"curvature":-6.497650060150667E-4},{"time":1.6227552295418346,"velocity":4.703013688297602,"acceleration":0.0067412152377363125,"pose":{"translation":{"x":6.995311739890247,"y":-2.282757747774662},"rotation":{"radians":-0.3483719095426188}},"curvature":-5.614968665936572E-4},{"time":1.6455223075360237,"velocity":4.7031671660706955,"acceleration":0.006677575573078309,"pose":{"translation":{"x":7.095954263638535,"y":-2.319312805137826},"rotation":{"radians":-0.3484273454046753}},"curvature":-4.7410811444260957E-4},{"time":1.6683141888298572,"velocity":4.703319360580488,"acceleration":0.006626341648883162,"pose":{"translation":{"x":7.196707846094072,"y":-2.355913994273193},"rotation":{"radians":-0.3484735166695209}},"curvature":-3.8745567191490635E-4},{"time":1.691125914047767,"velocity":4.703470518865382,"acceleration":0.006587310568012005,"pose":{"translation":{"x":7.2975508800381625,"y":-2.3925524225254877},"rotation":{"radians":-0.34851046583350903}},"curvature":-3.013987580703957E-4},{"time":1.7139525157111006,"velocity":4.703620884779751,"acceleration":0.006560328983487329,"pose":{"translation":{"x":7.398461726139931,"y":-2.429219183971269},"rotation":{"radians":-0.3485382266132044}},"curvature":-2.1579844161684353E-4},{"time":1.7367890200739886,"velocity":4.703770699761204,"acceleration":0.0065452921394948465,"pose":{"translation":{"x":7.499418720899509,"y":-2.465905362688101},"rotation":{"radians":-0.34855682401258936}},"curvature":-1.3051720303238805E-4},{"time":1.759630448957244,"velocity":4.7039202035861285,"acceleration":4.449473299374387E-4,"pose":{"translation":{"x":7.600400184591206,"y":-2.5026020360237293},"rotation":{"radians":-0.3485662743727219}},"curvature":-4.541850367600483E-5},{"time":1.7824721597108582,"velocity":4.7039303669443395,"acceleration":-0.00654966633545872,"pose":{"translation":{"x":7.701384429206682,"y":-2.5393002778652534},"rotation":{"radians":-0.3485665854040169}},"curvature":3.963364025820933E-5},{"time":1.8053098968726535,"velocity":4.703780787386073,"acceleration":-0.006569054232772703,"pose":{"translation":{"x":7.802349766398126,"y":-2.5759911619083042},"rotation":{"radians":-0.34855775620125407}},"curvature":1.2477508105031952E-4},{"time":1.828139068949373,"velocity":4.703630821316612,"acceleration":-0.006600426578437126,"pose":{"translation":{"x":7.9032745154214314,"y":-2.612665764926218},"rotation":{"radians":-0.34853977724137036}},"curvature":2.101419621190588E-4},{"time":1.850954701227469,"velocity":4.703480228410919,"acceleration":-0.00664390882496388,"pose":{"translation":{"x":8.004137011079372,"y":-2.649315170039208},"rotation":{"radians":-0.3485126303640174}},"curvature":2.958711421266519E-4},{"time":1.8737518250882366,"velocity":4.703328766398517,"acceleration":-0.006699675404599612,"pose":{"translation":{"x":8.10491561166477,"y":-2.6859304699835427},"rotation":{"radians":-0.34847628873483827}},"curvature":3.8210062261826935E-4},{"time":1.8965254798420614,"velocity":4.70317619030389,"acceleration":-0.006767950827795425,"pose":{"translation":{"x":8.205588706903683,"y":-2.7225027703807188},"rotation":{"radians":-0.34843071679132664}},"curvature":4.689699813158928E-4},{"time":1.919270714564398,"velocity":4.703022251673723,"acceleration":-0.0068490111044155035,"pose":{"translation":{"x":8.306134725898573,"y":-2.7590231930066356},"rotation":{"radians":-0.348375870171102}},"curvature":5.566208132271923E-4},{"time":1.9419825899332837,"velocity":4.702866697787119,"acceleration":-0.006943185502400931,"pose":{"translation":{"x":8.406532145071477,"y":-2.795482879060766},"rotation":{"radians":-0.3483116956223592}},"curvature":6.451971817814837E-4},{"time":1.9646561800679763,"velocity":4.702709270844808,"acceleration":-0.0070508586574038225,"pose":{"translation":{"x":8.50675949610719,"y":-2.8318729924353425},"rotation":{"radians":-0.3482381308961976}},"curvature":7.34846082278786E-4},{"time":1.9872865743693844,"velocity":4.702549707133228,"acceleration":-0.007172473054539557,"pose":{"translation":{"x":8.606795373896436,"y":-2.868184722984517},"rotation":{"radians":-0.34815510462047056}},"curvature":8.257179200227773E-4},{"time":2.009868879362072,"velocity":4.702387736159158,"acceleration":-0.007308531901937402,"pose":{"translation":{"x":8.706618444479046,"y":-2.904409289793546},"rotation":{"radians":-0.34806253615474037}},"curvature":9.179670056143282E-4},{"time":2.0323982205378757,"velocity":4.702223079750445,"acceleration":-0.007459602426343874,"pose":{"translation":{"x":8.806207452987135,"y":-2.940537944447957},"rotation":{"radians":-0.3479603354258481}},"curvature":0.0010117520700021036},{"time":2.0548697442008126,"velocity":4.702055451118006,"acceleration":-0.007626319616182957,"pose":{"translation":{"x":8.905541231588264,"y":-2.976561974302734},"rotation":{"radians":-0.3478484027435526}},"curvature":0.001107236802033505},{"time":2.0772786193144706,"velocity":4.70188455387415,"acceleration":-0.007809390451326412,"pose":{"translation":{"x":9.004598707428634,"y":-3.0124727057514793},"rotation":{"radians":-0.347726628595613}},"curvature":0.0012045904114051415},{"time":2.0996200393503432,"velocity":4.701710081001853,"acceleration":-0.008009598655879972,"pose":{"translation":{"x":9.10335891057625,"y":-3.0482615074955994},"rotation":{"radians":-0.34759489342162275}},"curvature":0.0013039882201029346},{"time":2.121889224138702,"velocity":4.701531713769304,"acceleration":-0.00822781002135825,"pose":{"translation":{"x":9.201800981964098,"y":-3.08391979381347},"rotation":{"radians":-0.34745306736482856}},"curvature":0.0014056122856276633},{"time":2.1440814217209203,"velocity":4.701349120583641,"acceleration":-0.008464978348691914,"pose":{"translation":{"x":9.299904181333321,"y":-3.119439027829614},"rotation":{"radians":-0.3473010100010797}},"curvature":0.0015096520595355926},{"time":2.1661919102041907,"velocity":4.701161955777351,"acceleration":-0.008722152069124894,"pose":{"translation":{"x":9.397647895176398,"y":-3.1548107247838875},"rotation":{"radians":-0.3471385700439829}},"curvature":0.0016163050850910667},{"time":2.188215999618132,"velocity":4.700969858320299,"acceleration":-0.009000481606593141,"pose":{"translation":{"x":9.495011644680316,"y":-3.190026455300628},"rotation":{"radians":-0.34696558502523067}},"curvature":0.001725777738118011},{"time":2.210149033773783,"velocity":4.700772450449804,"acceleration":-0.00930122755461837,"pose":{"translation":{"x":9.591975093669726,"y":-3.2250778486578557},"rotation":{"radians":-0.3467818809490062}},"curvature":0.001838286015466734},{"time":2.2319863921246013,"velocity":4.700569336210592,"acceleration":-0.009625769750443165,"pose":{"translation":{"x":9.68851805655017,"y":-3.2599565960564316},"rotation":{"radians":-0.3465872719192283}},"curvature":0.0019540563758784833},{"time":2.2537234916304514,"velocity":4.700360099895706,"acceleration":-0.009975617338042204,"pose":{"translation":{"x":9.78462050625119,"y":-3.294654453889242},"rotation":{"radians":-0.34638155973835105}},"curvature":0.002073326638432182},{"time":2.275355788623497,"velocity":4.70014430437876,"acceleration":-0.010352419921175708,"pose":{"translation":{"x":9.880262582169562,"y":-3.3291632470103636},"rotation":{"radians":-0.3461645334762574}},"curvature":0.002196346944214573},{"time":2.296878780677523,"velocity":4.699921489327057,"acceleration":-0.010757979926080005,"pose":{"translation":{"x":9.975424598112431,"y":-3.3634748720042476},"rotation":{"radians":-0.34593596900772544}},"curvature":0.0023233807873473296},{"time":2.318288008479419,"velocity":4.699691169284131,"acceleration":-0.011194266298869378,"pose":{"translation":{"x":10.07008705024051,"y":-3.3975813004548874},"rotation":{"radians":-0.3456956285167822}},"curvature":0.0024547061220649216},{"time":2.3395790577042384,"velocity":4.699452831609326,"acceleration":-0.011663429689199518,"pose":{"translation":{"x":10.164230625011236,"y":-3.4314745822149924},"rotation":{"radians":-0.34544325996614667}},"curvature":0.002590616553150375},{"time":2.360747560893146,"velocity":4.699205934260757,"acceleration":-0.0121678192788589,"pose":{"translation":{"x":10.257836207121956,"y":-3.46514684867517},"rotation":{"radians":-0.345178596529807}},"curvature":0.0027314226177157816},{"time":2.3817891993347553,"velocity":4.698949903406868,"acceleration":-0.012710001443912312,"pose":{"translation":{"x":10.350884887453121,"y":-3.498590316033094},"rotation":{"radians":-0.34490135598663285}},"curvature":0.002877453167072652},{"time":2.4026997049501913,"velocity":4.698684130850303,"acceleration":-0.013292780455117918,"pose":{"translation":{"x":10.44335797101142,"y":-3.5317972885626787},"rotation":{"radians":-0.3446112400727581}},"curvature":0.0030290568582754976},{"time":2.423474862181822,"velocity":4.6984079712463025,"acceleration":-0.013919221449873004,"pose":{"translation":{"x":10.53523698487298,"y":-3.5647601618832567},"rotation":{"radians":-0.3443079337902877}},"curvature":0.0031866037658480804},{"time":2.4441105098860723,"velocity":4.6981207390961455,"acceleration":-0.014592675939876076,"pose":{"translation":{"x":10.626503686126556,"y":-3.597471426228756},"rotation":{"radians":-0.3439911046697081}},"curvature":0.0033504871252351643},{"time":2.4646025432303795,"velocity":4.697821705494203,"acceleration":-0.015316810146859804,"pose":{"translation":{"x":10.717140069816656,"y":-3.629923669716865},"rotation":{"radians":-0.34366040198316133}},"curvature":0.0035211252206675107},{"time":2.4849469155949153,"velocity":4.697510094605138,"acceleration":-0.0160956365025476,"pose":{"translation":{"x":10.807128376886784,"y":-3.6621095816182105},"rotation":{"radians":-0.34331545590554663}},"curvature":0.0036989634313900604},{"time":2.505139640478907,"velocity":4.69718507984541,"acceleration":-0.016933548684983864,"pose":{"translation":{"x":10.896451102122565,"y":-3.694021955625546},"rotation":{"radians":-0.3429558766201623}},"curvature":0.0038844764516212213},{"time":2.5251767934121814,"velocity":4.6968457797407055,"acceleration":-0.017835360616437822,"pose":{"translation":{"x":10.985091002094928,"y":-3.7256536931229007},"rotation":{"radians":-0.34258125336537437}},"curvature":0.004078170701167172},{"time":2.545054513872177,"velocity":4.696491253428069,"acceleration":-0.018806349899489008,"pose":{"translation":{"x":11.073031103103302,"y":-3.756997806454782},"rotation":{"radians":-0.3421911534185059}},"curvature":0.004280586945357151},{"time":2.5647690072067633,"velocity":4.696120495768327,"acceleration":-0.019852306232666976,"pose":{"translation":{"x":11.16025470911876,"y":-3.7880474221953246},"rotation":{"radians":-0.3417851210128856}},"curvature":0.004492303144895317},{"time":2.5843165465631714,"velocity":4.695732432030929,"acceleration":-0.020979585412727316,"pose":{"translation":{"x":11.246745409727243,"y":-3.8187957844174782},"rotation":{"radians":-0.3413626761836514}},"curvature":0.004713937558374009},{"time":2.603693474823708,"velocity":4.695325912109451,"acceleration":-0.022195169616132677,"pose":{"translation":{"x":11.33248708807267,"y":-3.849236257962188},"rotation":{"radians":-0.34092331353761457}},"curvature":0.004946152122576614},{"time":2.62289620654834,"velocity":4.694899704221729,"acceleration":-0.02350673473946075,"pose":{"translation":{"x":11.417463928800158,"y":-3.8793623317075525},"rotation":{"radians":-0.3404665009421011}},"curvature":0.005189656138359233},{"time":2.6419212299249346,"velocity":4.694452488043804,"acceleration":-0.024922725682528783,"pose":{"translation":{"x":11.501660425999223,"y":-3.9091676218380123},"rotation":{"radians":-0.33999167812732334}},"curvature":0.005445210292855843},{"time":2.660765108727339,"velocity":4.6939828472216165,"acceleration":-0.026452440575377722,"pose":{"translation":{"x":11.585061391146851,"y":-3.9386458751135187},"rotation":{"radians":-0.33949825519644855}},"curvature":0.00571363105204153},{"time":2.679424484282301,"velocity":4.693489261198575,"acceleration":-0.028106125087259022,"pose":{"translation":{"x":11.667651961050796,"y":-3.967790972138708},"rotation":{"radians":-0.33898561103703356}},"curvature":0.005995795461361073},{"time":2.697896077445319,"velocity":4.6929700962905745,"acceleration":-0.02989507810188587,"pose":{"translation":{"x":11.749417605792681,"y":-3.9965969306320748},"rotation":{"radians":-0.3384530916271089}},"curvature":0.006292646396205132},{"time":2.716176690586381,"velocity":4.692423595932972,"acceleration":-0.031831770225640814,"pose":{"translation":{"x":11.830344136671187,"y":-4.025057908695155},"rotation":{"radians":-0.3379000082286223}},"curvature":0.006605198308581373},{"time":2.7342632095861976,"velocity":4.691847870015988,"acceleration":-0.033929976783624,"pose":{"translation":{"x":11.910417714145257,"y":-4.053168208081688},"rotation":{"radians":-0.33732563546046274}},"curvature":0.006934543521389735},{"time":2.752152605843496,"velocity":4.691240883216305,"acceleration":-0.03620492719374585,"pose":{"translation":{"x":11.989624855777217,"y":-4.0809222774667955},"rotation":{"radians":-0.33672920924269195}},"curvature":0.0072818591273748415},{"time":2.769841938294482,"velocity":4.690600442222811,"acceleration":-0.03867347285947374,"pose":{"translation":{"x":12.067952444176013,"y":-4.108314715716173},"rotation":{"radians":-0.3361099246030069}},"curvature":0.007648414556132973},{"time":2.7873283554448736,"velocity":4.689924181743736,"acceleration":-0.04135427601665364,"pose":{"translation":{"x":12.145387734940332,"y":-4.135340275155226},"rotation":{"radians":-0.3354669333358014}},"curvature":0.008035579879585916},{"time":2.80460909741585,"velocity":4.689209549170496,"acceleration":-0.04426802230643189,"pose":{"translation":{"x":12.221918364601805,"y":-4.161993864838287},"rotation":{"radians":-0.3347993415035072}},"curvature":0.008444834934168088},{"time":2.8216814980044727,"velocity":4.688453787760414,"acceleration":-0.047437660221822595,"pose":{"translation":{"x":12.297532358568203,"y":-4.1882705538177625},"rotation":{"radians":-0.3341062067691632}},"curvature":0.008877779346723532},{"time":2.838542986759918,"velocity":4.687653918185999,"acceleration":-0.05088867101258431,"pose":{"translation":{"x":12.372218139066542,"y":-4.214165574413309},"rotation":{"radians":-0.3333865355483635}},"curvature":0.009336143560852333},{"time":2.8551910910764002,"velocity":4.686806718282455,"acceleration":-0.054649373121779386,"pose":{"translation":{"x":12.445964533086354,"y":-4.239674325481033},"rotation":{"radians":-0.3326392799679521}},"curvature":0.009821800971294984},{"time":2.871623438304054,"velocity":4.685908700807544,"acceleration":-0.05875126578953377,"pose":{"translation":{"x":12.518760780322776,"y":-4.264792375682632},"rotation":{"radians":-0.33186333461791867}},"curvature":0.010336781286057863},{"time":2.8878377578790704,"velocity":4.684956089008596,"acceleration":-0.06322941709174404,"pose":{"translation":{"x":12.590596541119782,"y":-4.289515466754583},"rotation":{"radians":-0.3310575330820859}},"curvature":0.01088328524943052},{"time":2.903831883474275,"velocity":4.683944789770319,"acceleration":-0.06812290240327248,"pose":{"translation":{"x":12.661461904413306,"y":-4.313839516777328},"rotation":{"radians":-0.3302206442322277}},"curvature":0.011463700874031485},{"time":2.9196037551717033,"velocity":4.682870364093958,"acceleration":-0.07347530008608452,"pose":{"translation":{"x":12.731347395674508,"y":-4.337760623444428},"rotation":{"radians":-0.32935136826924993}},"curvature":0.012080621346673854},{"time":2.935151421658612,"velocity":4.681727994633194,"acceleration":-0.0793352521256913,"pose":{"translation":{"x":12.800243984852827,"y":-4.361275067331761},"rotation":{"radians":-0.32844833249412186}},"curvature":0.01273686479130493},{"time":2.950473042448533,"velocity":4.680512449984851,"acceleration":-0.08575709846545777,"pose":{"translation":{"x":12.86814309431925,"y":-4.3843793151666635},"rotation":{"radians":-0.3275100867901435}},"curvature":0.013435496092784157},{"time":2.965566890129039,"velocity":4.679218045403092,"acceleration":-0.09280159495653127,"pose":{"translation":{"x":12.935036606809449,"y":-4.40707002309715},"rotation":{"radians":-0.3265350987972188}},"curvature":0.01417985100789982},{"time":2.980431352638047,"velocity":4.677838599574084,"acceleration":-0.10053672612980348,"pose":{"translation":{"x":13.000916873366975,"y":-4.4293440399610375},"rotation":{"radians":-0.32552174875765966}},"curvature":0.014973562815084425},{"time":2.9950649355704617,"velocity":4.67636738705451,"acceleration":-0.10903862543674586,"pose":{"translation":{"x":13.06577672128643,"y":-4.451198410555165},"rotation":{"radians":-0.32446832401217235}},"curvature":0.015820591781829072},{"time":3.0094662645171266,"velocity":4.674797085941703,"acceleration":-0.11839261719725701,"pose":{"translation":{"x":13.129609462056594,"y":-4.472630378904537},"rotation":{"radians":-0.32337301312369243}},"curvature":0.016725257759070637},{"time":3.0236340874381407,"velocity":4.673119720306097,"acceleration":-0.12869439622974374,"pose":{"translation":{"x":13.192408899303656,"y":-4.493637391531511},"rotation":{"radians":-0.32223389960592}},"curvature":0.017692276244898913},{"time":3.037567277072596,"velocity":4.6713265968785365,"acceleration":-0.1400513630315125,"pose":{"translation":{"x":13.254169336734417,"y":-4.514217100724977},"rotation":{"radians":-0.32104895523272536}},"curvature":0.018726798295979317},{"time":3.0512648333868566,"velocity":4.669408235446523,"acceleration":-0.15944310911691464,"pose":{"translation":{"x":13.31488558607937,"y":-4.534367367809519},"rotation":{"radians":-0.3198160329040922}},"curvature":0.01983445470401043},{"time":3.077949955319033,"velocity":4.665153476638493,"acceleration":-0.1901269962237044,"pose":{"translation":{"x":13.433167355211653,"y":-4.573372085743699},"rotation":{"radians":-0.3171970255059308}},"curvature":0.022294391065331428},{"time":3.103683870896565,"velocity":4.660260764568663,"acceleration":-0.22775501837782047,"pose":{"translation":{"x":13.547223162860146,"y":-4.61063874087338},"rotation":{"radians":-0.31435702175215313}},"curvature":0.025128719746191984},{"time":3.1284634250193823,"velocity":4.654617096764026,"acceleration":-0.27407522987829763,"pose":{"translation":{"x":13.657030601927586,"y":-4.6461580825362425},"rotation":{"radians":-0.3112737242049294}},"curvature":0.02840547474637604},{"time":3.1522877493248997,"velocity":4.648087439603296,"acceleration":-0.33130354234391324,"pose":{"translation":{"x":13.762576156241451,"y":-4.679924518481943},"rotation":{"radians":-0.30792207344212147}},"curvature":0.03220657073056085},{"time":3.175158351948469,"velocity":4.640510327938568,"acceleration":-0.4022481120027285,"pose":{"translation":{"x":13.863855454735537,"y":-4.711936219485672},"rotation":{"radians":-0.3042738902734083}},"curvature":0.03663082788132656},{"time":3.197079210639608,"velocity":4.6316927039165785,"acceleration":-0.4904616550168139,"pose":{"translation":{"x":13.960873525631587,"y":-4.74219522396174},"rotation":{"radians":-0.3002974800220574}},"curvature":0.041797641580355344},{"time":3.2180568690647227,"velocity":4.621403966847019,"acceleration":-0.6004230195223179,"pose":{"translation":{"x":14.053645050620927,"y":-4.770707542577206},"rotation":{"radians":-0.29595720118383684}},"curvature":0.047851400266761906},{"time":3.238100535762091,"velocity":4.609369287966286,"acceleration":-0.7377446298927908,"pose":{"translation":{"x":14.14219461904598,"y":-4.797483262865374},"rotation":{"radians":-0.2912130051670268}},"curvature":0.05496674222623008},{"time":3.2572221846333433,"velocity":4.5952623941968245,"acceleration":-0.9093929586820941,"pose":{"translation":{"x":14.226556982082004,"y":-4.822536653839496},"rotation":{"radians":-0.28601996080331615}},"curvature":0.06335470093611098},{"time":3.2754366549525287,"velocity":4.578698283142433,"acceleration":-1.1238917562461512,"pose":{"translation":{"x":14.306777306918573,"y":-4.845886270606236},"rotation":{"radians":-0.2803277881560503}},"curvature":0.07326969592626409},{"time":3.292761747501338,"velocity":4.559226754450624,"acceleration":-1.3914476517067018,"pose":{"translation":{"x":14.382911430941283,"y":-4.867555058979352},"rotation":{"radians":-0.27408044263325626}},"curvature":0.08501714408146493},{"time":3.3092183113897087,"velocity":4.53632830727299,"acceleration":-1.7238886333663872,"pose":{"translation":{"x":14.455026115913277,"y":-4.887570460093219},"rotation":{"radians":-0.2672158150436699}},"curvature":0.098961134271922},{"time":3.324830313117469,"velocity":4.509414954950408,"acceleration":-2.134230780024759,"pose":{"translation":{"x":14.523199302156948,"y":-4.90596451501645},"rotation":{"radians":-0.2596656494177151}},"curvature":0.11553103187927309},{"time":3.3396248751158573,"velocity":4.477839945356463,"acceleration":-2.635582574494589,"pose":{"translation":{"x":14.587520362735464,"y":-4.922773969365473},"rotation":{"radians":-0.2513558325781181}},"curvature":0.1352249183989282},{"time":3.3536322649503463,"velocity":4.44092231279453,"acceleration":-3.582519105845448,"pose":{"translation":{"x":14.6480903576344,"y":-4.938040377918078},"rotation":{"radians":-0.24220728295076446}},"curvature":0.1586062266635573},{"time":3.3794347583579305,"velocity":4.348484387183408,"acceleration":-5.186635757116057,"pose":{"translation":{"x":14.758441350037616,"y":-4.964134950233838},"rotation":{"radians":-0.2210651007715408}},"curvature":0.21889213471806965},{"time":3.402523334073605,"velocity":4.228732354795608,"acceleration":-6.925099334184698,"pose":{"translation":{"x":14.855304156600658,"y":-4.984680828730376},"rotation":{"radians":-0.19561593010305592}},"curvature":0.3009105711885031},{"time":3.423220591137756,"velocity":4.085401793681209,"acceleration":-7.899727949539971,"pose":{"translation":{"x":14.939933912939077,"y":-5.000194252026091},"rotation":{"radians":-0.16547937300014395}},"curvature":0.40539956187435466},{"time":3.4418379315812926,"velocity":3.9383298690332986,"acceleration":-2.659333139312578,"pose":{"translation":{"x":15.01379714686142,"y":-5.01127844822588},"rotation":{"radians":-0.13098495469222307}},"curvature":0.5205219044461243},{"time":3.4733958669977514,"velocity":3.8544068055720233,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.136195922525479,"y":-5.023027104998107},"rotation":{"radians":-0.05862956694538753}},"curvature":0.5901506220921002},{"time":3.526652624736256,"velocity":0.0,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.238769634755512,"y":-5.02661962373552},"rotation":{"radians":-0.02161825323650912}},"curvature":-7.335559861346185E-16}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":73.93371404298517,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.05086995411362648,"velocity":3.7610046408166373,"acceleration":-18.57424203854883,"pose":{"translation":{"x":0.09565459966956365,"y":-0.0011123190880267572},"rotation":{"radians":-0.033995686872156414}},"curvature":-0.6712975775070884},{"time":0.06423826537265727,"velocity":3.512698391844742,"acceleration":-10.316146987916182,"pose":{"translation":{"x":0.14420644593008536,"y":-0.00365847304961269},"rotation":{"radians":-0.07271127000739433}},"curvature":-0.9080092233290921},{"time":0.07866454248842716,"velocity":3.363874796630048,"acceleration":-4.5974687137995,"pose":{"translation":{"x":0.1935763088920889,"y":-0.00844833890789438},"rotation":{"radians":-0.12203434947950173}},"curvature":-1.0666328276324561},{"time":0.09397890319552708,"velocity":3.293467502407316,"acceleration":-0.4802586390523535,"pose":{"translation":{"x":0.24397981266699661,"y":-0.016069845849796573},"rotation":{"radians":-0.178789722310322}},"curvature":-1.1466717358565035},{"time":0.11002242275188717,"velocity":3.2857624635395686,"acceleration":2.4960196154245624,"pose":{"translation":{"x":0.29560528877399317,"y":-0.027034433839816373},"rotation":{"radians":-0.2398407802177261}},"curvature":-1.1556390419488096},{"time":0.12666286596154275,"velocity":3.3272973362002274,"acceleration":4.560418520550342,"pose":{"translation":{"x":0.34861477578104033,"y":-0.04177988428587403},"rotation":{"radians":-0.3023314758911567}},"curvature":-1.107791259588418},{"time":0.14380602395230674,"velocity":3.405477311402028,"acceleration":5.847386046055847,"pose":{"translation":{"x":0.4031450189458916,"y":-0.060673150705163784},"rotation":{"radians":-0.36388782061669217}},"curvature":-1.0208946900841094},{"time":0.16139978344948339,"velocity":3.5083548151834814,"acceleration":6.472892216004755,"pose":{"translation":{"x":0.4593084698571069,"y":-0.08401318939000467},"rotation":{"radians":-0.4227283937354438}},"curvature":-0.9124481689723783},{"time":0.17943071819493958,"velocity":3.6250671123446345,"acceleration":6.566925304337632,"pose":{"translation":{"x":0.5171942860750671,"y":-0.11203379007369133},"rotation":{"radians":-0.47767077540076774}},"curvature":-0.7968705445643984},{"time":0.19791541378527516,"velocity":3.7464547275597875,"acceleration":6.274059430287694,"pose":{"translation":{"x":0.5768693307729895,"y":-0.14490640659634485},"rotation":{"radians":-0.5280570880490987}},"curvature":-0.6843026492654564},{"time":0.2168896263348448,"velocity":3.865500064738698,"acceleration":5.737160684411951,"pose":{"translation":{"x":0.6383791723779415,"y":-0.18274298757076357},"rotation":{"radians":-0.5736380137020395}},"curvature":-0.5807734339025615},{"time":0.2363978567632875,"velocity":3.9774219173752083,"acceleration":5.079304224561394,"pose":{"translation":{"x":0.7017490842118557,"y":-0.2255988070482738},"rotation":{"radians":-0.614450730048045}},"curvature":-0.4890913977589932},{"time":0.2564848157629174,"velocity":4.07944969308062,"acceleration":4.393089481814577,"pose":{"translation":{"x":0.7669850441325448,"y":-0.2734752951845809},"rotation":{"radians":-0.6507127237454765}},"curvature":-0.4098974703359642},{"time":0.27718924766098957,"velocity":4.170406115078987,"acceleration":3.739141148120054,"pose":{"translation":{"x":0.8340747341747161,"y":-0.3263228689056197},"rotation":{"radians":-0.6827401373770496}},"curvature":-0.3425641324237417},{"time":0.2985399502763592,"velocity":4.25023940576939,"acceleration":3.1509757796655906,"pose":{"translation":{"x":0.9029885401909865,"y":-0.3840437625734058},"rotation":{"radians":-0.7108905367060246}},"curvature":-0.2858398519486856},{"time":0.32055355266246643,"velocity":4.319603733711203,"acceleration":2.642401943027515,"pose":{"translation":{"x":0.9736805514928966,"y":-0.44649485865188593},"rotation":{"radians":-0.7355258661852377}},"curvature":-0.23825643905398558},{"time":0.34323356729339727,"velocity":4.379533448439867,"acceleration":2.2146815827867807,"pose":{"translation":{"x":1.0460895604919258,"y":-0.5134905183727889},"rotation":{"radians":-0.7569903480877602}},"curvature":-0.19835880323219002},{"time":0.3665702986787249,"velocity":4.431216877641394,"acceleration":1.8621545583886336,"pose":{"translation":{"x":1.1201400623405071,"y":-0.584805412401477},"rotation":{"radians":-0.7755986136832825}},"curvature":-0.16481771303838497},{"time":0.3905412896036193,"velocity":4.475854567661279,"acceleration":1.5760888534687674,"pose":{"translation":{"x":1.1957432545730415,"y":-0.6601773515027954},"rotation":{"radians":-0.7916304068283152}},"curvature":-0.136472518244863},{"time":0.41511208060110466,"velocity":4.514580317473326,"acceleration":1.3470385500755164,"pose":{"translation":{"x":1.272798036746913,"y":-0.7393101172069247},"rotation":{"radians":-0.8053292516533164}},"curvature":-0.11233552372944057},{"time":0.44023713373183376,"velocity":4.548424732613114,"acceleration":1.1661359456825557,"pose":{"translation":{"x":1.3511920100835033,"y":-0.8218762924752305},"rotation":{"radians":-0.8169033307113529}},"curvature":-0.09157753249531594},{"time":0.4658608265472986,"velocity":4.578305441866355,"acceleration":1.0257044303838847,"pose":{"translation":{"x":1.4308024771092056,"y":-0.9075200923661149},"rotation":{"radians":-0.826527445285146}},"curvature":-0.07350571496131073},{"time":0.4919184594606803,"velocity":4.605032871390928,"acceleration":0.9194807910085864,"pose":{"translation":{"x":1.511497441296441,"y":-0.9958601947008667},"rotation":{"radians":-0.8343453578075383}},"curvature":-0.0575397047719729},{"time":0.5183372440020911,"velocity":4.62932443629855,"acceleration":0.8426402753159437,"pose":{"translation":{"x":1.5931366067046713,"y":-1.086492570729512},"rotation":{"radians":-0.8404720957244525}},"curvature":-0.04318871524079346},{"time":0.5450372545084912,"velocity":4.651822940502601,"acceleration":0.791745641265346,"pose":{"translation":{"x":1.6755723776214158,"y":-1.1789933157966677},"rotation":{"radians":-0.8449959706278242}},"curvature":-0.03003072506763607},{"time":0.5719323347113374,"velocity":4.673117003024687,"acceleration":0.764694355739304,"pose":{"translation":{"x":1.7586508582032636,"y":-1.272921480007388},"rotation":{"radians":-0.847980170089422}},"curvature":-0.01769384334869522},{"time":0.5989309555759273,"velocity":4.693762696012584,"acceleration":0.7568977715020626,"pose":{"translation":{"x":1.8422128521168903,"y":-1.3678218988930184},"rotation":{"radians":-0.8494638363538869}},"curvature":-0.005839475817147653},{"time":0.6124392671308087,"velocity":4.703987106925229,"acceleration":-0.7576202624729402,"pose":{"translation":{"x":1.884124214371652,"y":-1.415491274754145},"rotation":{"radians":-0.8496487636296656}},"curvature":7.338372827318603E-6},{"time":0.6259667126088134,"velocity":4.693738440131595,"acceleration":-0.7573261930329094,"pose":{"translation":{"x":1.9260948621800718,"y":-1.4632280240770439},"rotation":{"radians":-0.8494625719018405}},"curvature":0.0058533418985739095},{"time":0.6395304014241225,"velocity":4.683466303317614,"acceleration":-0.7628673911206666,"pose":{"translation":{"x":1.9681038503903356,"y":-1.5109725139851649},"rotation":{"radians":-0.8489035135054931}},"curvature":0.011738406267223144},{"time":0.6531180622983974,"velocity":4.673100719915023,"acceleration":-0.7830355253123729,"pose":{"translation":{"x":2.0101300900026993,"y":-1.5586647539409455},"rotation":{"radians":-0.8479683169889314}},"curvature":0.017703234141495484},{"time":0.6803169691263304,"velocity":4.6518030096190905,"acceleration":-0.8307527071415495,"pose":{"translation":{"x":2.094149435627793,"y":-1.6536512642900423},"rotation":{"radians":-0.8449485345965028}},"curvature":0.030042325088393048},{"time":0.7074672445481859,"velocity":4.629247844812745,"acceleration":-0.906071998205533,"pose":{"translation":{"x":2.1779824971725197,"y":-1.74770383901935},"rotation":{"radians":-0.8403446169538852}},"curvature":0.04323372732782724},{"time":0.7344755175101836,"velocity":4.604776404961988,"acceleration":-1.01361258743599,"pose":{"translation":{"x":2.2614585704692027,"y":-1.8403387007794274},"rotation":{"radians":-0.8340693961508749}},"curvature":0.05769202793525322},{"time":0.7612522238680076,"velocity":4.57763519834762,"acceleration":-1.160129175098113,"pose":{"translation":{"x":2.3444076487063414,"y":-1.9310748416422285},"rotation":{"radians":-0.8260035993520203}},"curvature":0.07390849077791047},{"time":0.7877128317622496,"velocity":4.546937475138678,"acceleration":-1.3549882474774477,"pose":{"translation":{"x":2.426661422069622,"y":-2.019436853766954},"rotation":{"radians":-0.8159910361504031}},"curvature":0.09248322937699277},{"time":0.813779227317755,"velocity":4.51161781550687,"acceleration":-1.6107636336331643,"pose":{"translation":{"x":2.5080542773829357,"y":-2.1049577600659006},"rotation":{"radians":-0.8038322413203592}},"curvature":0.11416735583944754},{"time":0.839381300487912,"velocity":4.470378927098766,"acceleration":-1.9438858378565922,"pose":{"translation":{"x":2.588424297749391,"y":-2.187181844870313},"rotation":{"radians":-0.7892762221224462}},"curvature":0.13991912182652635},{"time":0.8644587801703956,"velocity":4.42163116949485,"acceleration":-2.375170055426009,"pose":{"translation":{"x":2.6676142621923296,"y":-2.2656674845962357},"rotation":{"radians":-0.7720098817436143}},"curvature":0.17097933982888272},{"time":0.8889633767270971,"velocity":4.363428585533077,"acceleration":-2.929829651838316,"pose":{"translation":{"x":2.7454726452963403,"y":-2.339989978410361},"rotation":{"radians":-0.7516446268743371}},"curvature":0.20897277722399427},{"time":0.9128612955339693,"velocity":4.293411754395478,"acceleration":-3.636189034284287,"pose":{"translation":{"x":2.821854616848273,"y":-2.409744378895878},"rotation":{"radians":-0.7276996587451912}},"curvature":0.25604326999230087},{"time":0.9361361800412911,"velocity":4.208779874575722,"acceleration":-4.5216881828428575,"pose":{"translation":{"x":2.896623041478257,"y":-2.474548322718337},"rotation":{"radians":-0.6995815816713621}},"curvature":0.31502967674654303},{"time":0.9587925123471198,"velocity":4.106335004521895,"acceleration":-5.60399278914594,"pose":{"translation":{"x":2.96964947830071,"y":-2.534044861291477},"rotation":{"radians":-0.6665604228891332}},"curvature":0.3896842355974877},{"time":0.9808594148938787,"velocity":3.9826722417710725,"acceleration":-6.874575522892502,"pose":{"translation":{"x":3.04081518055536,"y":-2.5879052914431},"rotation":{"radians":-0.6277432981168334}},"curvature":0.4849170693388809},{"time":1.0023946064250508,"velocity":3.834626941190075,"acceleration":-8.273406521918307,"pose":{"translation":{"x":3.11001209524825,"y":-2.6358319860809054},"rotation":{"radians":-0.5820494394596601}},"curvature":0.6070052569314024},{"time":1.023487881785884,"velocity":3.6601136992511396,"acceleration":-9.658924301782564,"pose":{"translation":{"x":3.177143862792765,"y":-2.6775612248583514},"rotation":{"radians":-0.5281952543243555}},"curvature":0.7636036847155038},{"time":1.044262785170934,"velocity":3.459450480078093,"acceleration":-10.789223965170862,"pose":{"translation":{"x":3.2421268166506345,"y":-2.7128660248404923},"rotation":{"radians":-0.46470714806956975}},"curvature":0.9631955271206418},{"time":1.064874016530968,"velocity":3.2370712887367334,"acceleration":-11.302561869966173,"pose":{"translation":{"x":3.304890982972959,"y":-2.7415589711698534},"rotation":{"radians":-0.38999454733449745}},"curvature":1.2132942484999119},{"time":1.0751733665117909,"velocity":3.120662248358049,"acceleration":-11.380543528234176,"pose":{"translation":{"x":3.335423144080664,"y":-2.753378948077126},"rotation":{"radians":-0.3479421309491289}},"curvature":1.358426651163162},{"time":1.0855002323875398,"velocity":3.003136901748853,"acceleration":-11.216467878014123,"pose":{"translation":{"x":3.365381080241215,"y":-2.763495047732251},"rotation":{"radians":-0.3025345461911083}},"curvature":1.5163645477959347},{"time":1.0958762629042613,"velocity":2.8867544887567504,"acceleration":-10.787091569870057,"pose":{"translation":{"x":3.3947603409450227,"y":-2.771896232330702},"rotation":{"radians":-0.25365089774536415}},"curvature":1.6854394262653827},{"time":1.1063204241314064,"velocity":2.774092365229049,"acceleration":-10.083979354300292,"pose":{"translation":{"x":3.423557518908273,"y":-2.778574467822663},"rotation":{"radians":-0.2012312246583879}},"curvature":1.8626231696577111},{"time":1.116847291817288,"velocity":2.667939648819167,"acceleration":-9.114909548892705,"pose":{"translation":{"x":3.45177028131171,"y":-2.783524812371301},"rotation":{"radians":-0.14529883493435322}},"curvature":2.0432619119023365},{"time":1.1274652330479096,"velocity":2.5711580749065925,"acceleration":-7.902719904762865,"pose":{"translation":{"x":3.479397401039414,"y":-2.7867455048110834},"rotation":{"radians":-0.0859833260459511}},"curvature":2.2209525751205432},{"time":1.1381747023193047,"velocity":2.4865241389260913,"acceleration":-6.481835710274992,"pose":{"translation":{"x":3.5064387879175904,"y":-2.788238053106106},"rotation":{"radians":-0.023541166424358224}},"curvature":2.3876772149703944},{"time":1.1489669632051263,"velocity":2.4165704769217693,"acceleration":-4.893457504823976,"pose":{"translation":{"x":3.5328955199533447,"y":-2.7880073228083617},"rotation":{"radians":0.04163035986200551}},"curvature":2.5342978229784756},{"time":1.1598235861318837,"velocity":2.363444053983784,"acceleration":-3.1807991066892427,"pose":{"translation":{"x":3.5587698745734646,"y":-2.7860616255160906},"rotation":{"radians":0.10899046026919362}},"curvature":2.6514478762539073},{"time":1.1707170215801754,"velocity":2.3287942242410806,"acceleration":-1.3856587256487902,"pose":{"translation":{"x":3.5840653598632053,"y":-2.782412807332051},"rotation":{"radians":0.1778672128711063}},"curvature":2.7307347638871597},{"time":1.1816123811036878,"velocity":2.313696974248245,"acceleration":0.4529836040260616,"pose":{"translation":{"x":3.6087867458050726,"y":-2.7770763373218585},"rotation":{"radians":0.24748653454997566}},"curvature":2.7660235695030395},{"time":1.1924702965896494,"velocity":2.3186154319372863,"acceleration":2.2984661787443414,"pose":{"translation":{"x":3.632940095517595,"y":-2.7700713959722734},"rotation":{"radians":0.31701575037894764}},"curvature":2.754476535466626},{"time":1.2032504480047301,"velocity":2.343393245366592,"acceleration":4.114879379943721,"pose":{"translation":{"x":3.6565327964941177,"y":-2.7614209636495133},"rotation":{"radians":0.38561608743857945}},"curvature":2.6970429684751966},{"time":1.2139151589148818,"velocity":2.387277244383836,"acceleration":5.8656152888126085,"pose":{"translation":{"x":3.679573591841575,"y":-2.7511519090575547},"rotation":{"radians":0.45249593249925324}},"curvature":2.5982479898838817},{"time":1.2244324399740094,"velocity":2.4489675689609944,"acceleration":7.513095171032861,"pose":{"translation":{"x":3.7020726115192786,"y":-2.739295077696468},"rotation":{"radians":0.5169564675958617}},"curvature":2.465353225992898},{"time":1.2347780217261053,"velocity":2.526694909264192,"acceleration":9.020223160123546,"pose":{"translation":{"x":3.724041403577694,"y":-2.7258853803206904},"rotation":{"radians":0.5784234297196774}},"curvature":2.307150240547736},{"time":1.2449361883882646,"velocity":2.6183238394545953,"acceleration":10.353415712615588,"pose":{"translation":{"x":3.7454929653972253,"y":-2.7109618813973526},"rotation":{"radians":0.6364623147658734}},"curvature":2.1327154300991826},{"time":1.2548994965281624,"velocity":2.7214781104998442,"acceleration":11.486441454404693,"pose":{"translation":{"x":3.766441774926996,"y":-2.6945678875645847},"rotation":{"radians":0.690777976015161}},"curvature":1.9503948408229943},{"time":1.2646676509055195,"velocity":2.8336794438729447,"acceleration":12.40400342145132,"pose":{"translation":{"x":3.78690382192363,"y":-2.676751036089815},"rotation":{"radians":0.7412021292820162}},"curvature":1.7671553148299803},{"time":1.2742458825560947,"velocity":2.9524878620381325,"acceleration":13.35685206525256,"pose":{"translation":{"x":3.806896639190036,"y":-2.657563383328103},"rotation":{"radians":0.7876733331307859}},"curvature":1.5883069062901587},{"time":1.2928595976722068,"velocity":3.2011085012287985,"acceleration":13.998945423131802,"pose":{"translation":{"x":3.8455526184079023,"y":-2.615306525551933},"rotation":{"radians":0.868906180060489}},"curvature":1.2570039051762898},{"time":1.310844421110843,"velocity":3.452877062990928,"acceleration":14.150170837417582,"pose":{"translation":{"x":3.882582023003213,"y":-2.5683055082444355},"rotation":{"radians":0.9352587452193236}},"curvature":0.970126267999398},{"time":1.3282733030525866,"velocity":3.6994987199717837,"acceleration":14.183752411184486,"pose":{"translation":{"x":3.918183851421153,"y":-2.5171448921474564},"rotation":{"radians":0.987894429762669}},"curvature":0.7269708668153606},{"time":1.3451820170575517,"velocity":3.9393277330097365,"acceleration":14.530228908111532,"pose":{"translation":{"x":3.952584789770473,"y":-2.4624884354022427},"rotation":{"radians":1.0279514762298647}},"curvature":0.5197118506738984},{"time":1.361554429814943,"velocity":4.177222638152715,"acceleration":-37.75826254579163,"pose":{"translation":{"x":3.9860402114645037,"y":-2.4050819242152457},"rotation":{"radians":1.056303137076602}},"curvature":0.3376360990041316},{"time":1.379187419339346,"velocity":3.511431590223104,"acceleration":-90.0,"pose":{"translation":{"x":4.018835176862188,"y":-2.3457560035239737},"rotation":{"radians":1.07341462703974}},"curvature":0.16881081832860914},{"time":1.4182033258973805,"velocity":0.0,"acceleration":-90.0,"pose":{"translation":{"x":4.051285432909083,"y":-2.2854290076628843},"rotation":{"radians":1.0792327605274032}},"curvature":-2.689929800695296E-15}] \ No newline at end of file diff --git a/src/Autonomous/SecondAuton.cpp b/src/Autonomous/SecondAuton.cpp new file mode 100644 index 0000000..ae70ecd --- /dev/null +++ b/src/Autonomous/SecondAuton.cpp @@ -0,0 +1,12 @@ +#include + +SecondAuton::SecondAuton() : COREAuton("Two Path Test Auto") {} + +void SecondAuton::AddNodes() { + m_drivePath = new Node(5, new PathFinderAction("foreward.wpilib.json")); + m_wait = new Node(3); + m_secondDrivePath = new Node(5, new PathFinderAction("second.wpilib.json")); + AddFirstNode(m_drivePath); + m_drivePath->AddNext(m_wait); + m_wait->AddNext(m_secondDrivePath); +} diff --git a/src/Autonomous/SecondAuton.h b/src/Autonomous/SecondAuton.h new file mode 100644 index 0000000..f3ee7e6 --- /dev/null +++ b/src/Autonomous/SecondAuton.h @@ -0,0 +1,18 @@ +#pragma once + +#include +#include +#include + +using namespace CORE; +using namespace std; + +class SecondAuton: public COREAuton { +public: + SecondAuton(); + void AddNodes() override; +private: + Node * m_drivePath = nullptr; + Node * m_wait = nullptr; + Node * m_secondDrivePath = nullptr; +}; diff --git a/src/autonomous/Auton.cpp b/src/autonomous/Auton.cpp index bb067bf..590bf7c 100644 --- a/src/autonomous/Auton.cpp +++ b/src/autonomous/Auton.cpp @@ -3,6 +3,8 @@ Autonomous::Autonomous() : COREAuton("Test Auto") {} void Autonomous::AddNodes() { - m_drivePath = new Node(5, new PathFinderAction("example.wpilib.json")); + m_drivePath = new Node(15, new PathFinderAction("example.wpilib.json")); + m_secondDrivePath = new Node(15, new PathFinderAction("foreward.wpilib.json")); AddFirstNode(m_drivePath); + m_drivePath->AddNext(m_secondDrivePath); } diff --git a/src/autonomous/Auton.h b/src/autonomous/Auton.h index 4eaf872..7e8a672 100644 --- a/src/autonomous/Auton.h +++ b/src/autonomous/Auton.h @@ -13,4 +13,5 @@ class Autonomous: public COREAuton { void AddNodes() override; private: Node * m_drivePath; + Node * m_secondDrivePath; }; diff --git a/src/main/deploy/paths/example.wpilib.json b/src/main/deploy/paths/example.wpilib.json index 42fb442..b57c712 100644 --- a/src/main/deploy/paths/example.wpilib.json +++ b/src/main/deploy/paths/example.wpilib.json @@ -1 +1 @@ -[{"time":0.0,"velocity":0.0,"acceleration":71.6754486328193,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.052504537201690564,"velocity":3.763286259189722,"acceleration":3.393027875765885,"pose":{"translation":{"x":0.0987840856718992,"y":-0.0014550809384724233},"rotation":{"radians":-0.0406235201304543}},"curvature":-0.669267331858832},{"time":0.08369849591678691,"velocity":3.869128230665534,"acceleration":8.940395462782044,"pose":{"translation":{"x":0.21743610778889016,"y":-0.011090481290308164},"rotation":{"radians":-0.11922715157584657}},"curvature":-0.5777181959580991},{"time":0.10210103517690408,"velocity":4.033654209170354,"acceleration":7.7520539423460715,"pose":{"translation":{"x":0.2894547521368349,"y":-0.021134285931893225},"rotation":{"radians":-0.15629119482489962}},"curvature":-0.4449483653936229},{"time":0.12254133010230119,"velocity":4.192108478029495,"acceleration":5.75700633123382,"pose":{"translation":{"x":0.3722655413186195,"y":-0.035621769310835674},"rotation":{"radians":-0.18844460732445098}},"curvature":-0.3269300330427504},{"time":0.14533768211239437,"velocity":4.3233472208806365,"acceleration":3.944401761401226,"pose":{"translation":{"x":0.4673396090946371,"y":-0.055158757396353585},"rotation":{"radians":-0.21542702352704587}},"curvature":-0.2357318596690303},{"time":0.17082259532410582,"velocity":4.423869957442069,"acceleration":2.8844388002223487,"pose":{"translation":{"x":0.5759365232228123,"y":-0.08026398863855952},"rotation":{"radians":-0.23772289170313524}},"curvature":-0.16953787250521077},{"time":0.18466411165336516,"velocity":4.4637949641960954,"acceleration":2.326862827367757,"pose":{"translation":{"x":0.635643814194672,"y":-0.09504381204755785},"rotation":{"radians":-0.24733668078881516}},"curvature":-0.14407454738817005},{"time":0.1992899012288189,"velocity":4.497827170280122,"acceleration":1.8726028175616212,"pose":{"translation":{"x":0.6991124192700513,"y":-0.11137246160318348},"rotation":{"radians":-0.2560512882871814}},"curvature":-0.12272641890725453},{"time":0.21473112059424881,"velocity":4.526742441170413,"acceleration":1.5061957817442015,"pose":{"translation":{"x":0.766443903568408,"y":-0.1292917769905396},"rotation":{"radians":-0.2639545845640026}},"curvature":-0.1048403284194074},{"time":0.23101567055964584,"velocity":4.551270161635896,"acceleration":1.2125328488063274,"pose":{"translation":{"x":0.8377281344236926,"y":-0.14883878260629593},"rotation":{"radians":-0.27112822180522567}},"curvature":-0.08984639789950959},{"time":0.2481681966511829,"velocity":4.572068162961893,"acceleration":0.9780339853892758,"pose":{"translation":{"x":0.9130435355659563,"y":-0.1700457921722737},"rotation":{"radians":-0.2776468756372453}},"curvature":-0.07725850624670107},{"time":0.2662101398397362,"velocity":4.58971379656276,"acceleration":0.7910806745495272,"pose":{"translation":{"x":0.9924573413029585,"y":-0.19294051334903078},"rotation":{"radians":-0.2835780974936386}},"curvature":-0.06666802579853986},{"time":0.28515981743654306,"velocity":4.604704520298538,"acceleration":0.6420396874172175,"pose":{"translation":{"x":1.0760258507017746,"y":-0.21754615234944685},"rotation":{"radians":-0.2889825347232104}},"curvature":-0.057734725453877866},{"time":0.30503252074980275,"velocity":4.617463584521919,"acceleration":0.5230871945044425,"pose":{"translation":{"x":1.1637946817704043,"y":-0.24388151855230836},"rotation":{"radians":-0.29391435676502015}},"curvature":-0.050177014396362525},{"time":0.32584062079799275,"velocity":4.628348035199094,"acceleration":0.42795546527859657,"pose":{"translation":{"x":1.2557990256393792,"y":-0.2719611291158937},"rotation":{"radians":-0.29842178249670276}},"curvature":-0.04376264842952715},{"time":0.3475936765970335,"velocity":4.637657374314804,"acceleration":0.35166819045207165,"pose":{"translation":{"x":1.3520639007433704,"y":-0.3017953135915584},"rotation":{"radians":-0.30254764263473954}},"curvature":-0.03830040704132812},{"time":0.37029854270166584,"velocity":4.645641953492277,"acceleration":0.29029645766093237,"pose":{"translation":{"x":1.4526044070027964,"y":-0.33339031853731993},"rotation":{"radians":-0.3063299370432376}},"curvature":-0.03363290685993953},{"time":0.3939594741066458,"velocity":4.652510638064101,"acceleration":0.24074807079349372,"pose":{"translation":{"x":1.5574259800054309,"y":-0.36674841213144305},"rotation":{"radians":-0.3098023639018164}},"curvature":-0.02963053745593578},{"time":0.4185782275335135,"velocity":4.65843755545696,"acceleration":0.2005926419332328,"pose":{"translation":{"x":1.666524645188012,"y":-0.4018679887860249},"rotation":{"radians":-0.3129948087165449}},"curvature":-0.026186420205458822},{"time":0.4441541587084636,"velocity":4.6635678990612455,"acceleration":0.16791995076836871,"pose":{"translation":{"x":1.7798872720178476,"y":-0.4387436737605798},"rotation":{"radians":-0.31593378811677125}},"curvature":-0.023212258501245673},{"time":0.4706843155906152,"velocity":4.6680228416987735,"acceleration":0.1473081055449243,"pose":{"translation":{"x":1.8974918281744246,"y":-0.477366427775625},"rotation":{"radians":-0.3186428476369191}},"curvature":-0.020634943232970684},{"time":0.48430557417763576,"velocity":4.670029363496365,"acceleration":0.13525227729273576,"pose":{"translation":{"x":1.9578755731199786,"y":-0.49732915462086014},"rotation":{"radians":-0.31991779085791866}},"curvature":-0.01947571752148467},{"time":0.4981632894321226,"velocity":4.671903651042609,"acceleration":0.12432688548768328,"pose":{"translation":{"x":2.019307633731017,"y":-0.5177236516262647},"rotation":{"radians":-0.3211429151700534}},"curvature":-0.018393786838207256},{"time":0.5122564819575298,"velocity":4.673655813775871,"acceleration":0.11441569818551017,"pose":{"translation":{"x":2.081782865529898,"y":-0.538547804816047},"rotation":{"radians":-0.3223204787561041}},"curvature":-0.017383137392378067},{"time":0.5265840442775498,"velocity":4.675295111822012,"acceleration":0.10541529555668874,"pose":{"translation":{"x":2.145295615336293,"y":-0.5597992907957762},"rotation":{"radians":-0.3234526131282243}},"curvature":-0.01643827432726884},{"time":0.5411447433384899,"velocity":4.676830032217033,"acceleration":0.0972335891691984,"pose":{"translation":{"x":2.20983972921036,"y":-0.5814755800215547},"rotation":{"radians":-0.3245413308852529}},"curvature":-0.015554173193681813},{"time":0.5559372229684437,"velocity":4.678268358104166,"acceleration":0.08978851658604482,"pose":{"translation":{"x":2.275408560395923,"y":-0.6035739400691946},"rotation":{"radians":-0.3255885329724584}},"curvature":-0.014726236202830386},{"time":0.5709600062957906,"velocity":4.679617231534122,"acceleration":0.0830068906946886,"pose":{"translation":{"x":2.3419949772636413,"y":-0.6260914389033911},"rotation":{"radians":-0.32659601547299605}},"curvature":-0.013950252777561888},{"time":0.5862114981295551,"velocity":4.680883210449698,"acceleration":0.07682338543969686,"pose":{"translation":{"x":2.4095913712541885,"y":-0.6490249481468979},"rotation":{"radians":-0.3275654759594006}},"curvature":-0.013222363967972418},{"time":0.6016899873039058,"velocity":4.682072320389564,"acceleration":0.07117964169334849,"pose":{"translation":{"x":2.4781896648214286,"y":-0.6723711463497003},"rotation":{"radians":-0.3284985194323406}},"curvature":-0.012539030340552192},{"time":0.6173936489891477,"velocity":4.683190101401593,"acceleration":0.06602347886871857,"pose":{"translation":{"x":2.547781319375588,"y":-0.6961265222581916},"rotation":{"radians":-0.32939666387264166}},"curvature":-0.011897002989255367},{"time":0.6333205469712927,"velocity":4.684241650613961,"acceleration":0.061308199557898,"pose":{"translation":{"x":2.618357343226433,"y":-0.7202873780843462},"rotation":{"radians":-0.3302613454313242}},"curvature":-0.011293297352516853},{"time":0.6494686359022924,"velocity":4.685231660872621,"acceleration":0.056991975988469196,"pose":{"translation":{"x":2.6899082995264454,"y":-0.7448498327748948},"rotation":{"radians":-0.33109392328110016}},"curvature":-0.010725169552478188},{"time":0.6658357635228018,"velocity":4.68616445581697,"acceleration":0.05303730842556608,"pose":{"translation":{"x":2.762424314213996,"y":-0.7698098252804986},"rotation":{"radians":-0.33189568415147325}},"curvature":-0.010190095001780771},{"time":0.6824196728593326,"velocity":4.687044021731353,"acceleration":0.04941054684157204,"pose":{"translation":{"x":2.8358950839565202,"y":-0.7951631178249241},"rotation":{"radians":-0.332667846568304}},"curvature":-0.009685749049497792},{"time":0.699218004397476,"velocity":4.687874036478679,"acceleration":0.046081468224634096,"pose":{"translation":{"x":2.9103098840936954,"y":-0.8209052991742178},"rotation":{"radians":-0.3334115648174423}},"curvature":-0.009209989461344641},{"time":0.7162282982327365,"velocity":4.68865789579354,"acceleration":0.04302290282954284,"pose":{"translation":{"x":2.9856575765806124,"y":-0.8470317879058803},"rotation":{"radians":-0.3341279326508223}},"curvature":-0.008760840550476132},{"time":0.7334479962006001,"velocity":4.689398737185965,"acceleration":0.04021040348993698,"pose":{"translation":{"x":3.061926617930954,"y":-0.8735378356780407},"rotation":{"radians":-0.3348179867522378}},"curvature":-0.008336478794167414},{"time":0.7508744439870677,"velocity":4.6900994616828555,"acceleration":0.03762195283333545,"pose":{"translation":{"x":3.13910506716017,"y":-0.9004185304986319},"rotation":{"radians":-0.33548270997890794}},"curvature":-0.007935219788693488},{"time":0.7685048932210419,"velocity":4.690762753612367,"acceleration":0.03523770386995457,"pose":{"translation":{"x":3.2171805937286497,"y":-0.927668799994564},"rotation":{"radians":-0.33612303439387825}},"curvature":-0.007555506409969931},{"time":0.7863365035498443,"velocity":4.691391098616657,"acceleration":0.033039749987155066,"pose":{"translation":{"x":3.296140485484901,"y":-0.9552834146809005},"rotation":{"radians":-0.3367398441032938}},"curvature":-0.007195898061161926},{"time":0.8043663446988317,"velocity":4.691986800060528,"acceleration":0.03101192085748364,"pose":{"translation":{"x":3.3759716566087206,"y":-0.983256991230031},"rotation":{"radians":-0.3373339779116408}},"curvature":-0.006855060900686268},{"time":0.8225913985163283,"velocity":4.69255199398714,"acceleration":0.029139601208403573,"pose":{"translation":{"x":3.4566606555543737,"y":-1.011583995740847},"rotation":{"radians":-0.3379062318071501}},"curvature":-0.00653175895495657},{"time":0.8410085610047663,"velocity":4.693088662757443,"acceleration":0.027409569760689707,"pose":{"translation":{"x":3.5381936729937724,"y":-1.0402587470079157},"rotation":{"radians":-0.3384573612887194}},"curvature":-0.006224846030001168},{"time":0.8596146443389476,"velocity":4.6935986474965645,"acceleration":0.025809855984173163,"pose":{"translation":{"x":3.6205565497596375,"y":-1.069275419790655},"rotation":{"radians":-0.3389880835449301}},"curvature":-0.005933258344827627},{"time":0.8784063788723748,"velocity":4.694083659458565,"acceleration":0.02432961259209342,"pose":{"translation":{"x":3.70373478478869,"y":-1.0986280480825084},"rotation":{"radians":-0.3394990794949884}},"curvature":-0.0056560078172345615},{"time":0.897380415132286,"velocity":4.694545290410077,"acceleration":0.022959001958506343,"pose":{"translation":{"x":3.7877135430648137,"y":-1.1283105283801182},"rotation":{"radians":-0.3399909957007404}},"curvature":-0.005392175939770404},{"time":0.9165333258042762,"velocity":4.694985022123706,"acceleration":0.021689094852614006,"pose":{"translation":{"x":3.872477663562239,"y":-1.1583166229525013},"rotation":{"radians":-0.34046444615826527}},"curvature":-0.00514090818980659},{"time":0.9358616077071303,"velocity":4.6954042350632355,"acceleration":0.020511780085435836,"pose":{"translation":{"x":3.9580116671887158,"y":-1.1886399631102225},"rotation":{"radians":-0.34092001397695176}},"curvature":-0.004901408923299515},{"time":0.9553616837584529,"velocity":4.6958042163348495,"acceleration":0.01941968382425391,"pose":{"translation":{"x":4.044299764728684,"y":-1.2192740524745713},"rotation":{"radians":-0.34135825295340627}},"curvature":-0.004672936706836661},{"time":0.9750299049318558,"velocity":4.696186166971422,"acceleration":0.018406097485132958,"pose":{"translation":{"x":4.131325864786455,"y":-1.250212270246734},"rotation":{"radians":-0.34177968904702144}},"curvature":-0.004454800047062241},{"time":0.9948625522059731,"velocity":4.696551208610538,"acceleration":0.017464913239636663,"pose":{"translation":{"x":4.219073581729384,"y":-1.281447874476969},"rotation":{"radians":-0.3421848217635512}},"curvature":-0.004246353480603635},{"time":1.0148558385061224,"velocity":4.696900389621145,"acceleration":0.01659056628522065,"pose":{"translation":{"x":4.3075262436310435,"y":-1.312974005333782},"rotation":{"radians":-0.3425741254525841}},"curvature":-0.00404699399123586},{"time":1.0350059106388894,"velocity":4.697234690728516,"acceleration":0.015777983132407462,"pose":{"translation":{"x":4.396666900214407,"y":-1.3447836883730995},"rotation":{"radians":-0.3429480505243987}},"curvature":-0.0038561577242561726},{"time":1.0553088512201658,"velocity":4.697555030182546,"acceleration":0.015022535243084308,"pose":{"translation":{"x":4.48647833079501,"y":-1.3768698378074444},"rotation":{"radians":-0.34330702459128587}},"curvature":-0.003673316970948526},{"time":1.0757606805969266,"velocity":4.697862268510144,"acceleration":0.014319997438426777,"pose":{"translation":{"x":4.576943052224139,"y":-1.4092252597751103},"rotation":{"radians":-0.34365145353806514}},"curvature":-0.003497977398624211},{"time":1.0963573587634323,"velocity":4.698157212888728,"acceleration":0.013666510556798168,"pose":{"translation":{"x":4.668043326831998,"y":-1.4418426556093347},"rotation":{"radians":-0.3439817225261905}},"curvature":-0.00332967550406501},{"time":1.117094787271751,"velocity":4.698440621174358,"acceleration":0.013058547904707297,"pose":{"translation":{"x":4.759761170370888,"y":-1.474714625107476},"rotation":{"radians":-0.3442981969355225}},"curvature":-0.0031679762702993635},{"time":1.1379688111373605,"velocity":4.698713205614971,"acceleration":0.012492885094505708,"pose":{"translation":{"x":4.852078359958381,"y":-1.507833669800185},"rotation":{"radians":-0.3446012232475584}},"curvature":-0.00301247100853054},{"time":1.1589752207398896,"velocity":4.6989756362763835,"acceleration":0.011966572911404053,"pose":{"translation":{"x":4.944976442020495,"y":-1.5411921962205826},"rotation":{"radians":-0.34489112987363685}},"curvature":-0.0028627753687348653},{"time":1.1801097537194458,"velocity":4.699228544206232,"acceleration":0.011476912888864071,"pose":{"translation":{"x":5.03843674023487,"y":-1.5747825191734315},"rotation":{"radians":-0.3451682279313891}},"curvature":-0.002718527503976295},{"time":1.201368096868549,"velocity":4.699472524358716,"acceleration":0.011021435311205923,"pose":{"translation":{"x":5.13244036347394,"y":-1.608596865004313},"rotation":{"radians":-0.3454328119724706}},"curvature":-0.0025793863748584827},{"time":1.2227458880201547,"velocity":4.6997081383009895,"acceleration":0.010597879392235597,"pose":{"translation":{"x":5.226968213748115,"y":-1.6426273748688005},"rotation":{"radians":-0.3456851606643893}},"curvature":-0.002445030181772817},{"time":1.2442387179320789,"velocity":4.699935916720194,"acceleration":0.01020417540646546,"pose":{"translation":{"x":5.322000994148948,"y":-1.676866108001632},"rotation":{"radians":-0.34592553742904764}},"curvature":-0.0023151549137154226},{"time":1.2658421321675262,"velocity":4.700156361748431,"acceleration":0.009838428575118652,"pose":{"translation":{"x":5.41751921679232,"y":-1.7113050449858913},"rotation":{"radians":-0.34615419104042433}},"curvature":-0.002189473003451237},{"time":1.2875516329725323,"velocity":4.7003699491215025,"acceleration":0.009498904530761338,"pose":{"translation":{"x":5.513503210761603,"y":-1.7459360910221728},"rotation":{"radians":-0.3463713561836444}},"curvature":-0.002067712079705491},{"time":1.3093626811503483,"velocity":4.700577130185859,"acceleration":0.009184016203396412,"pose":{"translation":{"x":5.609933130050849,"y":-1.7807510791977645},"rotation":{"radians":-0.34657725397752587}},"curvature":-0.001949613807880811},{"time":1.3312706979323152,"velocity":4.700778333766969,"acceleration":0.008892311988809397,"pose":{"translation":{"x":5.70678896150795,"y":-1.8157417737558181},"rotation":{"radians":-0.3467720924625369}},"curvature":-0.0018349328115315432},{"time":1.353271066846537,"velocity":4.7009739679112235,"acceleration":0.008622465074958126,"pose":{"translation":{"x":5.804050532777829,"y":-1.8508998733645248},"rotation":{"radians":-0.34695606705594856}},"curvature":-0.0017234356674891186},{"time":1.3753591355835073,"velocity":4.701164421512481,"acceleration":0.00837326381556048,"pose":{"translation":{"x":5.901697520245603,"y":-1.8862170143862897},"rotation":{"radians":-0.3471293609758433}},"curvature":-0.0016148999681312745},{"time":1.3975302178590974,"velocity":4.701350065833451,"acceleration":0.008143603052542164,"pose":{"translation":{"x":5.999709456979765,"y":-1.9216847741469065},"rotation":{"radians":-0.34729214563550515}},"curvature":-0.0015091134448230758},{"time":1.419779595275509,"velocity":4.701531255931297,"acceleration":0.007932476300126834,"pose":{"translation":{"x":6.098065740675358,"y":-1.9572946742047326},"rotation":{"radians":-0.34744458100960596}},"curvature":-0.001405873147046175},{"time":1.442102519179547,"velocity":4.701708331996115,"acceleration":0.007738968711621765,"pose":{"translation":{"x":6.196745641597146,"y":-1.9930381836198596},"rotation":{"radians":-0.34758681597348584}},"curvature":-0.001304984672166229},{"time":1.4644942125187514,"velocity":4.701881620610267,"acceleration":0.007562250761078728,"pose":{"translation":{"x":6.295728310522794,"y":-2.028906722223296},"rotation":{"radians":-0.34771898861672773}},"curvature":-0.001206261441183089},{"time":1.4869498716956224,"velocity":4.702051435935968,"acceleration":0.007401572575570495,"pose":{"translation":{"x":6.394992786686045,"y":-2.064891663886134},"rotation":{"radians":-0.34784122653211924}},"curvature":-0.001109524016160343},{"time":1.5094646684197912,"velocity":4.702218080837946,"acceleration":0.007256258868360784,"pose":{"translation":{"x":6.494518005719888,"y":-2.1009843397887265},"rotation":{"radians":-0.34795364708101434}},"curvature":-0.0010145994553500933},{"time":1.5320337515578726,"velocity":4.702381847947618,"acceleration":0.007125704417549445,"pose":{"translation":{"x":6.594282807599738,"y":-2.1371760416898637},"rotation":{"radians":-0.348056357636004}},"curvature":-9.213207023082924E-4},{"time":1.5546522489821248,"velocity":4.702543020674632,"acceleration":0.007009370055230198,"pose":{"translation":{"x":6.694265944586614,"y":-2.173458025195944},"rotation":{"radians":-0.3481494558017369}},"curvature":-8.295260055553096E-4},{"time":1.5773152694167862,"velocity":4.702701874171428,"acceleration":0.006906779123471565,"pose":{"translation":{"x":6.794446089170307,"y":-2.2098215130301524},"rotation":{"radians":-0.34823302961464364}},"curvature":-7.390583655584746E-4},{"time":1.6000179042829614,"velocity":4.702858676255969,"acceleration":0.00681751436758972,"pose":{"translation":{"x":6.894801842012562,"y":-2.246257698301633},"rotation":{"radians":-0.3483071577222395}},"curvature":-6.497650060150667E-4},{"time":1.6227552295418346,"velocity":4.703013688297602,"acceleration":0.0067412152377363125,"pose":{"translation":{"x":6.995311739890247,"y":-2.282757747774662},"rotation":{"radians":-0.3483719095426188}},"curvature":-5.614968665936572E-4},{"time":1.6455223075360237,"velocity":4.7031671660706955,"acceleration":0.006677575573078309,"pose":{"translation":{"x":7.095954263638535,"y":-2.319312805137826},"rotation":{"radians":-0.3484273454046753}},"curvature":-4.7410811444260957E-4},{"time":1.6683141888298572,"velocity":4.703319360580488,"acceleration":0.006626341648883162,"pose":{"translation":{"x":7.196707846094072,"y":-2.355913994273193},"rotation":{"radians":-0.3484735166695209}},"curvature":-3.8745567191490635E-4},{"time":1.691125914047767,"velocity":4.703470518865382,"acceleration":0.006587310568012005,"pose":{"translation":{"x":7.2975508800381625,"y":-2.3925524225254877},"rotation":{"radians":-0.34851046583350903}},"curvature":-3.013987580703957E-4},{"time":1.7139525157111006,"velocity":4.703620884779751,"acceleration":0.006560328983487329,"pose":{"translation":{"x":7.398461726139931,"y":-2.429219183971269},"rotation":{"radians":-0.3485382266132044}},"curvature":-2.1579844161684353E-4},{"time":1.7367890200739886,"velocity":4.703770699761204,"acceleration":0.0065452921394948465,"pose":{"translation":{"x":7.499418720899509,"y":-2.465905362688101},"rotation":{"radians":-0.34855682401258936}},"curvature":-1.3051720303238805E-4},{"time":1.759630448957244,"velocity":4.7039202035861285,"acceleration":4.449473299374387E-4,"pose":{"translation":{"x":7.600400184591206,"y":-2.5026020360237293},"rotation":{"radians":-0.3485662743727219}},"curvature":-4.541850367600483E-5},{"time":1.7824721597108582,"velocity":4.7039303669443395,"acceleration":-0.00654966633545872,"pose":{"translation":{"x":7.701384429206682,"y":-2.5393002778652534},"rotation":{"radians":-0.3485665854040169}},"curvature":3.963364025820933E-5},{"time":1.8053098968726535,"velocity":4.703780787386073,"acceleration":-0.006569054232772703,"pose":{"translation":{"x":7.802349766398126,"y":-2.5759911619083042},"rotation":{"radians":-0.34855775620125407}},"curvature":1.2477508105031952E-4},{"time":1.828139068949373,"velocity":4.703630821316612,"acceleration":-0.006600426578437126,"pose":{"translation":{"x":7.9032745154214314,"y":-2.612665764926218},"rotation":{"radians":-0.34853977724137036}},"curvature":2.101419621190588E-4},{"time":1.850954701227469,"velocity":4.703480228410919,"acceleration":-0.00664390882496388,"pose":{"translation":{"x":8.004137011079372,"y":-2.649315170039208},"rotation":{"radians":-0.3485126303640174}},"curvature":2.958711421266519E-4},{"time":1.8737518250882366,"velocity":4.703328766398517,"acceleration":-0.006699675404599612,"pose":{"translation":{"x":8.10491561166477,"y":-2.6859304699835427},"rotation":{"radians":-0.34847628873483827}},"curvature":3.8210062261826935E-4},{"time":1.8965254798420614,"velocity":4.70317619030389,"acceleration":-0.006767950827795425,"pose":{"translation":{"x":8.205588706903683,"y":-2.7225027703807188},"rotation":{"radians":-0.34843071679132664}},"curvature":4.689699813158928E-4},{"time":1.919270714564398,"velocity":4.703022251673723,"acceleration":-0.0068490111044155035,"pose":{"translation":{"x":8.306134725898573,"y":-2.7590231930066356},"rotation":{"radians":-0.348375870171102}},"curvature":5.566208132271923E-4},{"time":1.9419825899332837,"velocity":4.702866697787119,"acceleration":-0.006943185502400931,"pose":{"translation":{"x":8.406532145071477,"y":-2.795482879060766},"rotation":{"radians":-0.3483116956223592}},"curvature":6.451971817814837E-4},{"time":1.9646561800679763,"velocity":4.702709270844808,"acceleration":-0.0070508586574038225,"pose":{"translation":{"x":8.50675949610719,"y":-2.8318729924353425},"rotation":{"radians":-0.3482381308961976}},"curvature":7.34846082278786E-4},{"time":1.9872865743693844,"velocity":4.702549707133228,"acceleration":-0.007172473054539557,"pose":{"translation":{"x":8.606795373896436,"y":-2.868184722984517},"rotation":{"radians":-0.34815510462047056}},"curvature":8.257179200227773E-4},{"time":2.009868879362072,"velocity":4.702387736159158,"acceleration":-0.007308531901937402,"pose":{"translation":{"x":8.706618444479046,"y":-2.904409289793546},"rotation":{"radians":-0.34806253615474037}},"curvature":9.179670056143282E-4},{"time":2.0323982205378757,"velocity":4.702223079750445,"acceleration":-0.007459602426343874,"pose":{"translation":{"x":8.806207452987135,"y":-2.940537944447957},"rotation":{"radians":-0.3479603354258481}},"curvature":0.0010117520700021036},{"time":2.0548697442008126,"velocity":4.702055451118006,"acceleration":-0.007626319616182957,"pose":{"translation":{"x":8.905541231588264,"y":-2.976561974302734},"rotation":{"radians":-0.3478484027435526}},"curvature":0.001107236802033505},{"time":2.0772786193144706,"velocity":4.70188455387415,"acceleration":-0.007809390451326412,"pose":{"translation":{"x":9.004598707428634,"y":-3.0124727057514793},"rotation":{"radians":-0.347726628595613}},"curvature":0.0012045904114051415},{"time":2.0996200393503432,"velocity":4.701710081001853,"acceleration":-0.008009598655879972,"pose":{"translation":{"x":9.10335891057625,"y":-3.0482615074955994},"rotation":{"radians":-0.34759489342162275}},"curvature":0.0013039882201029346},{"time":2.121889224138702,"velocity":4.701531713769304,"acceleration":-0.00822781002135825,"pose":{"translation":{"x":9.201800981964098,"y":-3.08391979381347},"rotation":{"radians":-0.34745306736482856}},"curvature":0.0014056122856276633},{"time":2.1440814217209203,"velocity":4.701349120583641,"acceleration":-0.008464978348691914,"pose":{"translation":{"x":9.299904181333321,"y":-3.119439027829614},"rotation":{"radians":-0.3473010100010797}},"curvature":0.0015096520595355926},{"time":2.1661919102041907,"velocity":4.701161955777351,"acceleration":-0.008722152069124894,"pose":{"translation":{"x":9.397647895176398,"y":-3.1548107247838875},"rotation":{"radians":-0.3471385700439829}},"curvature":0.0016163050850910667},{"time":2.188215999618132,"velocity":4.700969858320299,"acceleration":-0.009000481606593141,"pose":{"translation":{"x":9.495011644680316,"y":-3.190026455300628},"rotation":{"radians":-0.34696558502523067}},"curvature":0.001725777738118011},{"time":2.210149033773783,"velocity":4.700772450449804,"acceleration":-0.00930122755461837,"pose":{"translation":{"x":9.591975093669726,"y":-3.2250778486578557},"rotation":{"radians":-0.3467818809490062}},"curvature":0.001838286015466734},{"time":2.2319863921246013,"velocity":4.700569336210592,"acceleration":-0.009625769750443165,"pose":{"translation":{"x":9.68851805655017,"y":-3.2599565960564316},"rotation":{"radians":-0.3465872719192283}},"curvature":0.0019540563758784833},{"time":2.2537234916304514,"velocity":4.700360099895706,"acceleration":-0.009975617338042204,"pose":{"translation":{"x":9.78462050625119,"y":-3.294654453889242},"rotation":{"radians":-0.34638155973835105}},"curvature":0.002073326638432182},{"time":2.275355788623497,"velocity":4.70014430437876,"acceleration":-0.010352419921175708,"pose":{"translation":{"x":9.880262582169562,"y":-3.3291632470103636},"rotation":{"radians":-0.3461645334762574}},"curvature":0.002196346944214573},{"time":2.296878780677523,"velocity":4.699921489327057,"acceleration":-0.010757979926080005,"pose":{"translation":{"x":9.975424598112431,"y":-3.3634748720042476},"rotation":{"radians":-0.34593596900772544}},"curvature":0.0023233807873473296},{"time":2.318288008479419,"velocity":4.699691169284131,"acceleration":-0.011194266298869378,"pose":{"translation":{"x":10.07008705024051,"y":-3.3975813004548874},"rotation":{"radians":-0.3456956285167822}},"curvature":0.0024547061220649216},{"time":2.3395790577042384,"velocity":4.699452831609326,"acceleration":-0.011663429689199518,"pose":{"translation":{"x":10.164230625011236,"y":-3.4314745822149924},"rotation":{"radians":-0.34544325996614667}},"curvature":0.002590616553150375},{"time":2.360747560893146,"velocity":4.699205934260757,"acceleration":-0.0121678192788589,"pose":{"translation":{"x":10.257836207121956,"y":-3.46514684867517},"rotation":{"radians":-0.345178596529807}},"curvature":0.0027314226177157816},{"time":2.3817891993347553,"velocity":4.698949903406868,"acceleration":-0.012710001443912312,"pose":{"translation":{"x":10.350884887453121,"y":-3.498590316033094},"rotation":{"radians":-0.34490135598663285}},"curvature":0.002877453167072652},{"time":2.4026997049501913,"velocity":4.698684130850303,"acceleration":-0.013292780455117918,"pose":{"translation":{"x":10.44335797101142,"y":-3.5317972885626787},"rotation":{"radians":-0.3446112400727581}},"curvature":0.0030290568582754976},{"time":2.423474862181822,"velocity":4.6984079712463025,"acceleration":-0.013919221449873004,"pose":{"translation":{"x":10.53523698487298,"y":-3.5647601618832567},"rotation":{"radians":-0.3443079337902877}},"curvature":0.0031866037658480804},{"time":2.4441105098860723,"velocity":4.6981207390961455,"acceleration":-0.014592675939876076,"pose":{"translation":{"x":10.626503686126556,"y":-3.597471426228756},"rotation":{"radians":-0.3439911046697081}},"curvature":0.0033504871252351643},{"time":2.4646025432303795,"velocity":4.697821705494203,"acceleration":-0.015316810146859804,"pose":{"translation":{"x":10.717140069816656,"y":-3.629923669716865},"rotation":{"radians":-0.34366040198316133}},"curvature":0.0035211252206675107},{"time":2.4849469155949153,"velocity":4.697510094605138,"acceleration":-0.0160956365025476,"pose":{"translation":{"x":10.807128376886784,"y":-3.6621095816182105},"rotation":{"radians":-0.34331545590554663}},"curvature":0.0036989634313900604},{"time":2.505139640478907,"velocity":4.69718507984541,"acceleration":-0.016933548684983864,"pose":{"translation":{"x":10.896451102122565,"y":-3.694021955625546},"rotation":{"radians":-0.3429558766201623}},"curvature":0.0038844764516212213},{"time":2.5251767934121814,"velocity":4.6968457797407055,"acceleration":-0.017835360616437822,"pose":{"translation":{"x":10.985091002094928,"y":-3.7256536931229007},"rotation":{"radians":-0.34258125336537437}},"curvature":0.004078170701167172},{"time":2.545054513872177,"velocity":4.696491253428069,"acceleration":-0.018806349899489008,"pose":{"translation":{"x":11.073031103103302,"y":-3.756997806454782},"rotation":{"radians":-0.3421911534185059}},"curvature":0.004280586945357151},{"time":2.5647690072067633,"velocity":4.696120495768327,"acceleration":-0.019852306232666976,"pose":{"translation":{"x":11.16025470911876,"y":-3.7880474221953246},"rotation":{"radians":-0.3417851210128856}},"curvature":0.004492303144895317},{"time":2.5843165465631714,"velocity":4.695732432030929,"acceleration":-0.020979585412727316,"pose":{"translation":{"x":11.246745409727243,"y":-3.8187957844174782},"rotation":{"radians":-0.3413626761836514}},"curvature":0.004713937558374009},{"time":2.603693474823708,"velocity":4.695325912109451,"acceleration":-0.022195169616132677,"pose":{"translation":{"x":11.33248708807267,"y":-3.849236257962188},"rotation":{"radians":-0.34092331353761457}},"curvature":0.004946152122576614},{"time":2.62289620654834,"velocity":4.694899704221729,"acceleration":-0.02350673473946075,"pose":{"translation":{"x":11.417463928800158,"y":-3.8793623317075525},"rotation":{"radians":-0.3404665009421011}},"curvature":0.005189656138359233},{"time":2.6419212299249346,"velocity":4.694452488043804,"acceleration":-0.024922725682528783,"pose":{"translation":{"x":11.501660425999223,"y":-3.9091676218380123},"rotation":{"radians":-0.33999167812732334}},"curvature":0.005445210292855843},{"time":2.660765108727339,"velocity":4.6939828472216165,"acceleration":-0.026452440575377722,"pose":{"translation":{"x":11.585061391146851,"y":-3.9386458751135187},"rotation":{"radians":-0.33949825519644855}},"curvature":0.00571363105204153},{"time":2.679424484282301,"velocity":4.693489261198575,"acceleration":-0.028106125087259022,"pose":{"translation":{"x":11.667651961050796,"y":-3.967790972138708},"rotation":{"radians":-0.33898561103703356}},"curvature":0.005995795461361073},{"time":2.697896077445319,"velocity":4.6929700962905745,"acceleration":-0.02989507810188587,"pose":{"translation":{"x":11.749417605792681,"y":-3.9965969306320748},"rotation":{"radians":-0.3384530916271089}},"curvature":0.006292646396205132},{"time":2.716176690586381,"velocity":4.692423595932972,"acceleration":-0.031831770225640814,"pose":{"translation":{"x":11.830344136671187,"y":-4.025057908695155},"rotation":{"radians":-0.3379000082286223}},"curvature":0.006605198308581373},{"time":2.7342632095861976,"velocity":4.691847870015988,"acceleration":-0.033929976783624,"pose":{"translation":{"x":11.910417714145257,"y":-4.053168208081688},"rotation":{"radians":-0.33732563546046274}},"curvature":0.006934543521389735},{"time":2.752152605843496,"velocity":4.691240883216305,"acceleration":-0.03620492719374585,"pose":{"translation":{"x":11.989624855777217,"y":-4.0809222774667955},"rotation":{"radians":-0.33672920924269195}},"curvature":0.0072818591273748415},{"time":2.769841938294482,"velocity":4.690600442222811,"acceleration":-0.03867347285947374,"pose":{"translation":{"x":12.067952444176013,"y":-4.108314715716173},"rotation":{"radians":-0.3361099246030069}},"curvature":0.007648414556132973},{"time":2.7873283554448736,"velocity":4.689924181743736,"acceleration":-0.04135427601665364,"pose":{"translation":{"x":12.145387734940332,"y":-4.135340275155226},"rotation":{"radians":-0.3354669333358014}},"curvature":0.008035579879585916},{"time":2.80460909741585,"velocity":4.689209549170496,"acceleration":-0.04426802230643189,"pose":{"translation":{"x":12.221918364601805,"y":-4.161993864838287},"rotation":{"radians":-0.3347993415035072}},"curvature":0.008444834934168088},{"time":2.8216814980044727,"velocity":4.688453787760414,"acceleration":-0.047437660221822595,"pose":{"translation":{"x":12.297532358568203,"y":-4.1882705538177625},"rotation":{"radians":-0.3341062067691632}},"curvature":0.008877779346723532},{"time":2.838542986759918,"velocity":4.687653918185999,"acceleration":-0.05088867101258431,"pose":{"translation":{"x":12.372218139066542,"y":-4.214165574413309},"rotation":{"radians":-0.3333865355483635}},"curvature":0.009336143560852333},{"time":2.8551910910764002,"velocity":4.686806718282455,"acceleration":-0.054649373121779386,"pose":{"translation":{"x":12.445964533086354,"y":-4.239674325481033},"rotation":{"radians":-0.3326392799679521}},"curvature":0.009821800971294984},{"time":2.871623438304054,"velocity":4.685908700807544,"acceleration":-0.05875126578953377,"pose":{"translation":{"x":12.518760780322776,"y":-4.264792375682632},"rotation":{"radians":-0.33186333461791867}},"curvature":0.010336781286057863},{"time":2.8878377578790704,"velocity":4.684956089008596,"acceleration":-0.06322941709174404,"pose":{"translation":{"x":12.590596541119782,"y":-4.289515466754583},"rotation":{"radians":-0.3310575330820859}},"curvature":0.01088328524943052},{"time":2.903831883474275,"velocity":4.683944789770319,"acceleration":-0.06812290240327248,"pose":{"translation":{"x":12.661461904413306,"y":-4.313839516777328},"rotation":{"radians":-0.3302206442322277}},"curvature":0.011463700874031485},{"time":2.9196037551717033,"velocity":4.682870364093958,"acceleration":-0.07347530008608452,"pose":{"translation":{"x":12.731347395674508,"y":-4.337760623444428},"rotation":{"radians":-0.32935136826924993}},"curvature":0.012080621346673854},{"time":2.935151421658612,"velocity":4.681727994633194,"acceleration":-0.0793352521256913,"pose":{"translation":{"x":12.800243984852827,"y":-4.361275067331761},"rotation":{"radians":-0.32844833249412186}},"curvature":0.01273686479130493},{"time":2.950473042448533,"velocity":4.680512449984851,"acceleration":-0.08575709846545777,"pose":{"translation":{"x":12.86814309431925,"y":-4.3843793151666635},"rotation":{"radians":-0.3275100867901435}},"curvature":0.013435496092784157},{"time":2.965566890129039,"velocity":4.679218045403092,"acceleration":-0.09280159495653127,"pose":{"translation":{"x":12.935036606809449,"y":-4.40707002309715},"rotation":{"radians":-0.3265350987972188}},"curvature":0.01417985100789982},{"time":2.980431352638047,"velocity":4.677838599574084,"acceleration":-0.10053672612980348,"pose":{"translation":{"x":13.000916873366975,"y":-4.4293440399610375},"rotation":{"radians":-0.32552174875765966}},"curvature":0.014973562815084425},{"time":2.9950649355704617,"velocity":4.67636738705451,"acceleration":-0.10903862543674586,"pose":{"translation":{"x":13.06577672128643,"y":-4.451198410555165},"rotation":{"radians":-0.32446832401217235}},"curvature":0.015820591781829072},{"time":3.0094662645171266,"velocity":4.674797085941703,"acceleration":-0.11839261719725701,"pose":{"translation":{"x":13.129609462056594,"y":-4.472630378904537},"rotation":{"radians":-0.32337301312369243}},"curvature":0.016725257759070637},{"time":3.0236340874381407,"velocity":4.673119720306097,"acceleration":-0.12869439622974374,"pose":{"translation":{"x":13.192408899303656,"y":-4.493637391531511},"rotation":{"radians":-0.32223389960592}},"curvature":0.017692276244898913},{"time":3.037567277072596,"velocity":4.6713265968785365,"acceleration":-0.1400513630315125,"pose":{"translation":{"x":13.254169336734417,"y":-4.514217100724977},"rotation":{"radians":-0.32104895523272536}},"curvature":0.018726798295979317},{"time":3.0512648333868566,"velocity":4.669408235446523,"acceleration":-0.15944310911691464,"pose":{"translation":{"x":13.31488558607937,"y":-4.534367367809519},"rotation":{"radians":-0.3198160329040922}},"curvature":0.01983445470401043},{"time":3.077949955319033,"velocity":4.665153476638493,"acceleration":-0.1901269962237044,"pose":{"translation":{"x":13.433167355211653,"y":-4.573372085743699},"rotation":{"radians":-0.3171970255059308}},"curvature":0.022294391065331428},{"time":3.103683870896565,"velocity":4.660260764568663,"acceleration":-0.22775501837782047,"pose":{"translation":{"x":13.547223162860146,"y":-4.61063874087338},"rotation":{"radians":-0.31435702175215313}},"curvature":0.025128719746191984},{"time":3.1284634250193823,"velocity":4.654617096764026,"acceleration":-0.27407522987829763,"pose":{"translation":{"x":13.657030601927586,"y":-4.6461580825362425},"rotation":{"radians":-0.3112737242049294}},"curvature":0.02840547474637604},{"time":3.1522877493248997,"velocity":4.648087439603296,"acceleration":-0.33130354234391324,"pose":{"translation":{"x":13.762576156241451,"y":-4.679924518481943},"rotation":{"radians":-0.30792207344212147}},"curvature":0.03220657073056085},{"time":3.175158351948469,"velocity":4.640510327938568,"acceleration":-0.4022481120027285,"pose":{"translation":{"x":13.863855454735537,"y":-4.711936219485672},"rotation":{"radians":-0.3042738902734083}},"curvature":0.03663082788132656},{"time":3.197079210639608,"velocity":4.6316927039165785,"acceleration":-0.4904616550168139,"pose":{"translation":{"x":13.960873525631587,"y":-4.74219522396174},"rotation":{"radians":-0.3002974800220574}},"curvature":0.041797641580355344},{"time":3.2180568690647227,"velocity":4.621403966847019,"acceleration":-0.6004230195223179,"pose":{"translation":{"x":14.053645050620927,"y":-4.770707542577206},"rotation":{"radians":-0.29595720118383684}},"curvature":0.047851400266761906},{"time":3.238100535762091,"velocity":4.609369287966286,"acceleration":-0.7377446298927908,"pose":{"translation":{"x":14.14219461904598,"y":-4.797483262865374},"rotation":{"radians":-0.2912130051670268}},"curvature":0.05496674222623008},{"time":3.2572221846333433,"velocity":4.5952623941968245,"acceleration":-0.9093929586820941,"pose":{"translation":{"x":14.226556982082004,"y":-4.822536653839496},"rotation":{"radians":-0.28601996080331615}},"curvature":0.06335470093611098},{"time":3.2754366549525287,"velocity":4.578698283142433,"acceleration":-1.1238917562461512,"pose":{"translation":{"x":14.306777306918573,"y":-4.845886270606236},"rotation":{"radians":-0.2803277881560503}},"curvature":0.07326969592626409},{"time":3.292761747501338,"velocity":4.559226754450624,"acceleration":-1.3914476517067018,"pose":{"translation":{"x":14.382911430941283,"y":-4.867555058979352},"rotation":{"radians":-0.27408044263325626}},"curvature":0.08501714408146493},{"time":3.3092183113897087,"velocity":4.53632830727299,"acceleration":-1.7238886333663872,"pose":{"translation":{"x":14.455026115913277,"y":-4.887570460093219},"rotation":{"radians":-0.2672158150436699}},"curvature":0.098961134271922},{"time":3.324830313117469,"velocity":4.509414954950408,"acceleration":-2.134230780024759,"pose":{"translation":{"x":14.523199302156948,"y":-4.90596451501645},"rotation":{"radians":-0.2596656494177151}},"curvature":0.11553103187927309},{"time":3.3396248751158573,"velocity":4.477839945356463,"acceleration":-2.635582574494589,"pose":{"translation":{"x":14.587520362735464,"y":-4.922773969365473},"rotation":{"radians":-0.2513558325781181}},"curvature":0.1352249183989282},{"time":3.3536322649503463,"velocity":4.44092231279453,"acceleration":-3.582519105845448,"pose":{"translation":{"x":14.6480903576344,"y":-4.938040377918078},"rotation":{"radians":-0.24220728295076446}},"curvature":0.1586062266635573},{"time":3.3794347583579305,"velocity":4.348484387183408,"acceleration":-5.186635757116057,"pose":{"translation":{"x":14.758441350037616,"y":-4.964134950233838},"rotation":{"radians":-0.2210651007715408}},"curvature":0.21889213471806965},{"time":3.402523334073605,"velocity":4.228732354795608,"acceleration":-6.925099334184698,"pose":{"translation":{"x":14.855304156600658,"y":-4.984680828730376},"rotation":{"radians":-0.19561593010305592}},"curvature":0.3009105711885031},{"time":3.423220591137756,"velocity":4.085401793681209,"acceleration":-7.899727949539971,"pose":{"translation":{"x":14.939933912939077,"y":-5.000194252026091},"rotation":{"radians":-0.16547937300014395}},"curvature":0.40539956187435466},{"time":3.4418379315812926,"velocity":3.9383298690332986,"acceleration":-2.659333139312578,"pose":{"translation":{"x":15.01379714686142,"y":-5.01127844822588},"rotation":{"radians":-0.13098495469222307}},"curvature":0.5205219044461243},{"time":3.4733958669977514,"velocity":3.8544068055720233,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.136195922525479,"y":-5.023027104998107},"rotation":{"radians":-0.05862956694538753}},"curvature":0.5901506220921002},{"time":3.526652624736256,"velocity":0.0,"acceleration":-72.3740417037306,"pose":{"translation":{"x":15.238769634755512,"y":-5.02661962373552},"rotation":{"radians":-0.02161825323650912}},"curvature":-7.335559861346185E-16}] \ No newline at end of file +[{"time":0.0,"velocity":0.0,"acceleration":73.93371404298517,"pose":{"translation":{"x":0.0,"y":0.0},"rotation":{"radians":0.0}},"curvature":0.0},{"time":0.05086995411362648,"velocity":3.7610046408166373,"acceleration":-18.57424203854883,"pose":{"translation":{"x":0.09565459966956365,"y":-0.0011123190880267572},"rotation":{"radians":-0.033995686872156414}},"curvature":-0.6712975775070884},{"time":0.06423826537265727,"velocity":3.512698391844742,"acceleration":-10.316146987916182,"pose":{"translation":{"x":0.14420644593008536,"y":-0.00365847304961269},"rotation":{"radians":-0.07271127000739433}},"curvature":-0.9080092233290921},{"time":0.07866454248842716,"velocity":3.363874796630048,"acceleration":-4.5974687137995,"pose":{"translation":{"x":0.1935763088920889,"y":-0.00844833890789438},"rotation":{"radians":-0.12203434947950173}},"curvature":-1.0666328276324561},{"time":0.09397890319552708,"velocity":3.293467502407316,"acceleration":-0.4802586390523535,"pose":{"translation":{"x":0.24397981266699661,"y":-0.016069845849796573},"rotation":{"radians":-0.178789722310322}},"curvature":-1.1466717358565035},{"time":0.11002242275188717,"velocity":3.2857624635395686,"acceleration":2.4960196154245624,"pose":{"translation":{"x":0.29560528877399317,"y":-0.027034433839816373},"rotation":{"radians":-0.2398407802177261}},"curvature":-1.1556390419488096},{"time":0.12666286596154275,"velocity":3.3272973362002274,"acceleration":4.560418520550342,"pose":{"translation":{"x":0.34861477578104033,"y":-0.04177988428587403},"rotation":{"radians":-0.3023314758911567}},"curvature":-1.107791259588418},{"time":0.14380602395230674,"velocity":3.405477311402028,"acceleration":5.847386046055847,"pose":{"translation":{"x":0.4031450189458916,"y":-0.060673150705163784},"rotation":{"radians":-0.36388782061669217}},"curvature":-1.0208946900841094},{"time":0.16139978344948339,"velocity":3.5083548151834814,"acceleration":6.472892216004755,"pose":{"translation":{"x":0.4593084698571069,"y":-0.08401318939000467},"rotation":{"radians":-0.4227283937354438}},"curvature":-0.9124481689723783},{"time":0.17943071819493958,"velocity":3.6250671123446345,"acceleration":6.566925304337632,"pose":{"translation":{"x":0.5171942860750671,"y":-0.11203379007369133},"rotation":{"radians":-0.47767077540076774}},"curvature":-0.7968705445643984},{"time":0.19791541378527516,"velocity":3.7464547275597875,"acceleration":6.274059430287694,"pose":{"translation":{"x":0.5768693307729895,"y":-0.14490640659634485},"rotation":{"radians":-0.5280570880490987}},"curvature":-0.6843026492654564},{"time":0.2168896263348448,"velocity":3.865500064738698,"acceleration":5.737160684411951,"pose":{"translation":{"x":0.6383791723779415,"y":-0.18274298757076357},"rotation":{"radians":-0.5736380137020395}},"curvature":-0.5807734339025615},{"time":0.2363978567632875,"velocity":3.9774219173752083,"acceleration":5.079304224561394,"pose":{"translation":{"x":0.7017490842118557,"y":-0.2255988070482738},"rotation":{"radians":-0.614450730048045}},"curvature":-0.4890913977589932},{"time":0.2564848157629174,"velocity":4.07944969308062,"acceleration":4.393089481814577,"pose":{"translation":{"x":0.7669850441325448,"y":-0.2734752951845809},"rotation":{"radians":-0.6507127237454765}},"curvature":-0.4098974703359642},{"time":0.27718924766098957,"velocity":4.170406115078987,"acceleration":3.739141148120054,"pose":{"translation":{"x":0.8340747341747161,"y":-0.3263228689056197},"rotation":{"radians":-0.6827401373770496}},"curvature":-0.3425641324237417},{"time":0.2985399502763592,"velocity":4.25023940576939,"acceleration":3.1509757796655906,"pose":{"translation":{"x":0.9029885401909865,"y":-0.3840437625734058},"rotation":{"radians":-0.7108905367060246}},"curvature":-0.2858398519486856},{"time":0.32055355266246643,"velocity":4.319603733711203,"acceleration":2.642401943027515,"pose":{"translation":{"x":0.9736805514928966,"y":-0.44649485865188593},"rotation":{"radians":-0.7355258661852377}},"curvature":-0.23825643905398558},{"time":0.34323356729339727,"velocity":4.379533448439867,"acceleration":2.2146815827867807,"pose":{"translation":{"x":1.0460895604919258,"y":-0.5134905183727889},"rotation":{"radians":-0.7569903480877602}},"curvature":-0.19835880323219002},{"time":0.3665702986787249,"velocity":4.431216877641394,"acceleration":1.8621545583886336,"pose":{"translation":{"x":1.1201400623405071,"y":-0.584805412401477},"rotation":{"radians":-0.7755986136832825}},"curvature":-0.16481771303838497},{"time":0.3905412896036193,"velocity":4.475854567661279,"acceleration":1.5760888534687674,"pose":{"translation":{"x":1.1957432545730415,"y":-0.6601773515027954},"rotation":{"radians":-0.7916304068283152}},"curvature":-0.136472518244863},{"time":0.41511208060110466,"velocity":4.514580317473326,"acceleration":1.3470385500755164,"pose":{"translation":{"x":1.272798036746913,"y":-0.7393101172069247},"rotation":{"radians":-0.8053292516533164}},"curvature":-0.11233552372944057},{"time":0.44023713373183376,"velocity":4.548424732613114,"acceleration":1.1661359456825557,"pose":{"translation":{"x":1.3511920100835033,"y":-0.8218762924752305},"rotation":{"radians":-0.8169033307113529}},"curvature":-0.09157753249531594},{"time":0.4658608265472986,"velocity":4.578305441866355,"acceleration":1.0257044303838847,"pose":{"translation":{"x":1.4308024771092056,"y":-0.9075200923661149},"rotation":{"radians":-0.826527445285146}},"curvature":-0.07350571496131073},{"time":0.4919184594606803,"velocity":4.605032871390928,"acceleration":0.9194807910085864,"pose":{"translation":{"x":1.511497441296441,"y":-0.9958601947008667},"rotation":{"radians":-0.8343453578075383}},"curvature":-0.0575397047719729},{"time":0.5183372440020911,"velocity":4.62932443629855,"acceleration":0.8426402753159437,"pose":{"translation":{"x":1.5931366067046713,"y":-1.086492570729512},"rotation":{"radians":-0.8404720957244525}},"curvature":-0.04318871524079346},{"time":0.5450372545084912,"velocity":4.651822940502601,"acceleration":0.791745641265346,"pose":{"translation":{"x":1.6755723776214158,"y":-1.1789933157966677},"rotation":{"radians":-0.8449959706278242}},"curvature":-0.03003072506763607},{"time":0.5719323347113374,"velocity":4.673117003024687,"acceleration":0.764694355739304,"pose":{"translation":{"x":1.7586508582032636,"y":-1.272921480007388},"rotation":{"radians":-0.847980170089422}},"curvature":-0.01769384334869522},{"time":0.5989309555759273,"velocity":4.693762696012584,"acceleration":0.7568977715020626,"pose":{"translation":{"x":1.8422128521168903,"y":-1.3678218988930184},"rotation":{"radians":-0.8494638363538869}},"curvature":-0.005839475817147653},{"time":0.6124392671308087,"velocity":4.703987106925229,"acceleration":-0.7576202624729402,"pose":{"translation":{"x":1.884124214371652,"y":-1.415491274754145},"rotation":{"radians":-0.8496487636296656}},"curvature":7.338372827318603E-6},{"time":0.6259667126088134,"velocity":4.693738440131595,"acceleration":-0.7573261930329094,"pose":{"translation":{"x":1.9260948621800718,"y":-1.4632280240770439},"rotation":{"radians":-0.8494625719018405}},"curvature":0.0058533418985739095},{"time":0.6395304014241225,"velocity":4.683466303317614,"acceleration":-0.7628673911206666,"pose":{"translation":{"x":1.9681038503903356,"y":-1.5109725139851649},"rotation":{"radians":-0.8489035135054931}},"curvature":0.011738406267223144},{"time":0.6531180622983974,"velocity":4.673100719915023,"acceleration":-0.7830355253123729,"pose":{"translation":{"x":2.0101300900026993,"y":-1.5586647539409455},"rotation":{"radians":-0.8479683169889314}},"curvature":0.017703234141495484},{"time":0.6803169691263304,"velocity":4.6518030096190905,"acceleration":-0.8307527071415495,"pose":{"translation":{"x":2.094149435627793,"y":-1.6536512642900423},"rotation":{"radians":-0.8449485345965028}},"curvature":0.030042325088393048},{"time":0.7074672445481859,"velocity":4.629247844812745,"acceleration":-0.906071998205533,"pose":{"translation":{"x":2.1779824971725197,"y":-1.74770383901935},"rotation":{"radians":-0.8403446169538852}},"curvature":0.04323372732782724},{"time":0.7344755175101836,"velocity":4.604776404961988,"acceleration":-1.01361258743599,"pose":{"translation":{"x":2.2614585704692027,"y":-1.8403387007794274},"rotation":{"radians":-0.8340693961508749}},"curvature":0.05769202793525322},{"time":0.7612522238680076,"velocity":4.57763519834762,"acceleration":-1.160129175098113,"pose":{"translation":{"x":2.3444076487063414,"y":-1.9310748416422285},"rotation":{"radians":-0.8260035993520203}},"curvature":0.07390849077791047},{"time":0.7877128317622496,"velocity":4.546937475138678,"acceleration":-1.3549882474774477,"pose":{"translation":{"x":2.426661422069622,"y":-2.019436853766954},"rotation":{"radians":-0.8159910361504031}},"curvature":0.09248322937699277},{"time":0.813779227317755,"velocity":4.51161781550687,"acceleration":-1.6107636336331643,"pose":{"translation":{"x":2.5080542773829357,"y":-2.1049577600659006},"rotation":{"radians":-0.8038322413203592}},"curvature":0.11416735583944754},{"time":0.839381300487912,"velocity":4.470378927098766,"acceleration":-1.9438858378565922,"pose":{"translation":{"x":2.588424297749391,"y":-2.187181844870313},"rotation":{"radians":-0.7892762221224462}},"curvature":0.13991912182652635},{"time":0.8644587801703956,"velocity":4.42163116949485,"acceleration":-2.375170055426009,"pose":{"translation":{"x":2.6676142621923296,"y":-2.2656674845962357},"rotation":{"radians":-0.7720098817436143}},"curvature":0.17097933982888272},{"time":0.8889633767270971,"velocity":4.363428585533077,"acceleration":-2.929829651838316,"pose":{"translation":{"x":2.7454726452963403,"y":-2.339989978410361},"rotation":{"radians":-0.7516446268743371}},"curvature":0.20897277722399427},{"time":0.9128612955339693,"velocity":4.293411754395478,"acceleration":-3.636189034284287,"pose":{"translation":{"x":2.821854616848273,"y":-2.409744378895878},"rotation":{"radians":-0.7276996587451912}},"curvature":0.25604326999230087},{"time":0.9361361800412911,"velocity":4.208779874575722,"acceleration":-4.5216881828428575,"pose":{"translation":{"x":2.896623041478257,"y":-2.474548322718337},"rotation":{"radians":-0.6995815816713621}},"curvature":0.31502967674654303},{"time":0.9587925123471198,"velocity":4.106335004521895,"acceleration":-5.60399278914594,"pose":{"translation":{"x":2.96964947830071,"y":-2.534044861291477},"rotation":{"radians":-0.6665604228891332}},"curvature":0.3896842355974877},{"time":0.9808594148938787,"velocity":3.9826722417710725,"acceleration":-6.874575522892502,"pose":{"translation":{"x":3.04081518055536,"y":-2.5879052914431},"rotation":{"radians":-0.6277432981168334}},"curvature":0.4849170693388809},{"time":1.0023946064250508,"velocity":3.834626941190075,"acceleration":-8.273406521918307,"pose":{"translation":{"x":3.11001209524825,"y":-2.6358319860809054},"rotation":{"radians":-0.5820494394596601}},"curvature":0.6070052569314024},{"time":1.023487881785884,"velocity":3.6601136992511396,"acceleration":-9.658924301782564,"pose":{"translation":{"x":3.177143862792765,"y":-2.6775612248583514},"rotation":{"radians":-0.5281952543243555}},"curvature":0.7636036847155038},{"time":1.044262785170934,"velocity":3.459450480078093,"acceleration":-10.789223965170862,"pose":{"translation":{"x":3.2421268166506345,"y":-2.7128660248404923},"rotation":{"radians":-0.46470714806956975}},"curvature":0.9631955271206418},{"time":1.064874016530968,"velocity":3.2370712887367334,"acceleration":-11.302561869966173,"pose":{"translation":{"x":3.304890982972959,"y":-2.7415589711698534},"rotation":{"radians":-0.38999454733449745}},"curvature":1.2132942484999119},{"time":1.0751733665117909,"velocity":3.120662248358049,"acceleration":-11.380543528234176,"pose":{"translation":{"x":3.335423144080664,"y":-2.753378948077126},"rotation":{"radians":-0.3479421309491289}},"curvature":1.358426651163162},{"time":1.0855002323875398,"velocity":3.003136901748853,"acceleration":-11.216467878014123,"pose":{"translation":{"x":3.365381080241215,"y":-2.763495047732251},"rotation":{"radians":-0.3025345461911083}},"curvature":1.5163645477959347},{"time":1.0958762629042613,"velocity":2.8867544887567504,"acceleration":-10.787091569870057,"pose":{"translation":{"x":3.3947603409450227,"y":-2.771896232330702},"rotation":{"radians":-0.25365089774536415}},"curvature":1.6854394262653827},{"time":1.1063204241314064,"velocity":2.774092365229049,"acceleration":-10.083979354300292,"pose":{"translation":{"x":3.423557518908273,"y":-2.778574467822663},"rotation":{"radians":-0.2012312246583879}},"curvature":1.8626231696577111},{"time":1.116847291817288,"velocity":2.667939648819167,"acceleration":-9.114909548892705,"pose":{"translation":{"x":3.45177028131171,"y":-2.783524812371301},"rotation":{"radians":-0.14529883493435322}},"curvature":2.0432619119023365},{"time":1.1274652330479096,"velocity":2.5711580749065925,"acceleration":-7.902719904762865,"pose":{"translation":{"x":3.479397401039414,"y":-2.7867455048110834},"rotation":{"radians":-0.0859833260459511}},"curvature":2.2209525751205432},{"time":1.1381747023193047,"velocity":2.4865241389260913,"acceleration":-6.481835710274992,"pose":{"translation":{"x":3.5064387879175904,"y":-2.788238053106106},"rotation":{"radians":-0.023541166424358224}},"curvature":2.3876772149703944},{"time":1.1489669632051263,"velocity":2.4165704769217693,"acceleration":-4.893457504823976,"pose":{"translation":{"x":3.5328955199533447,"y":-2.7880073228083617},"rotation":{"radians":0.04163035986200551}},"curvature":2.5342978229784756},{"time":1.1598235861318837,"velocity":2.363444053983784,"acceleration":-3.1807991066892427,"pose":{"translation":{"x":3.5587698745734646,"y":-2.7860616255160906},"rotation":{"radians":0.10899046026919362}},"curvature":2.6514478762539073},{"time":1.1707170215801754,"velocity":2.3287942242410806,"acceleration":-1.3856587256487902,"pose":{"translation":{"x":3.5840653598632053,"y":-2.782412807332051},"rotation":{"radians":0.1778672128711063}},"curvature":2.7307347638871597},{"time":1.1816123811036878,"velocity":2.313696974248245,"acceleration":0.4529836040260616,"pose":{"translation":{"x":3.6087867458050726,"y":-2.7770763373218585},"rotation":{"radians":0.24748653454997566}},"curvature":2.7660235695030395},{"time":1.1924702965896494,"velocity":2.3186154319372863,"acceleration":2.2984661787443414,"pose":{"translation":{"x":3.632940095517595,"y":-2.7700713959722734},"rotation":{"radians":0.31701575037894764}},"curvature":2.754476535466626},{"time":1.2032504480047301,"velocity":2.343393245366592,"acceleration":4.114879379943721,"pose":{"translation":{"x":3.6565327964941177,"y":-2.7614209636495133},"rotation":{"radians":0.38561608743857945}},"curvature":2.6970429684751966},{"time":1.2139151589148818,"velocity":2.387277244383836,"acceleration":5.8656152888126085,"pose":{"translation":{"x":3.679573591841575,"y":-2.7511519090575547},"rotation":{"radians":0.45249593249925324}},"curvature":2.5982479898838817},{"time":1.2244324399740094,"velocity":2.4489675689609944,"acceleration":7.513095171032861,"pose":{"translation":{"x":3.7020726115192786,"y":-2.739295077696468},"rotation":{"radians":0.5169564675958617}},"curvature":2.465353225992898},{"time":1.2347780217261053,"velocity":2.526694909264192,"acceleration":9.020223160123546,"pose":{"translation":{"x":3.724041403577694,"y":-2.7258853803206904},"rotation":{"radians":0.5784234297196774}},"curvature":2.307150240547736},{"time":1.2449361883882646,"velocity":2.6183238394545953,"acceleration":10.353415712615588,"pose":{"translation":{"x":3.7454929653972253,"y":-2.7109618813973526},"rotation":{"radians":0.6364623147658734}},"curvature":2.1327154300991826},{"time":1.2548994965281624,"velocity":2.7214781104998442,"acceleration":11.486441454404693,"pose":{"translation":{"x":3.766441774926996,"y":-2.6945678875645847},"rotation":{"radians":0.690777976015161}},"curvature":1.9503948408229943},{"time":1.2646676509055195,"velocity":2.8336794438729447,"acceleration":12.40400342145132,"pose":{"translation":{"x":3.78690382192363,"y":-2.676751036089815},"rotation":{"radians":0.7412021292820162}},"curvature":1.7671553148299803},{"time":1.2742458825560947,"velocity":2.9524878620381325,"acceleration":13.35685206525256,"pose":{"translation":{"x":3.806896639190036,"y":-2.657563383328103},"rotation":{"radians":0.7876733331307859}},"curvature":1.5883069062901587},{"time":1.2928595976722068,"velocity":3.2011085012287985,"acceleration":13.998945423131802,"pose":{"translation":{"x":3.8455526184079023,"y":-2.615306525551933},"rotation":{"radians":0.868906180060489}},"curvature":1.2570039051762898},{"time":1.310844421110843,"velocity":3.452877062990928,"acceleration":14.150170837417582,"pose":{"translation":{"x":3.882582023003213,"y":-2.5683055082444355},"rotation":{"radians":0.9352587452193236}},"curvature":0.970126267999398},{"time":1.3282733030525866,"velocity":3.6994987199717837,"acceleration":14.183752411184486,"pose":{"translation":{"x":3.918183851421153,"y":-2.5171448921474564},"rotation":{"radians":0.987894429762669}},"curvature":0.7269708668153606},{"time":1.3451820170575517,"velocity":3.9393277330097365,"acceleration":14.530228908111532,"pose":{"translation":{"x":3.952584789770473,"y":-2.4624884354022427},"rotation":{"radians":1.0279514762298647}},"curvature":0.5197118506738984},{"time":1.361554429814943,"velocity":4.177222638152715,"acceleration":-37.75826254579163,"pose":{"translation":{"x":3.9860402114645037,"y":-2.4050819242152457},"rotation":{"radians":1.056303137076602}},"curvature":0.3376360990041316},{"time":1.379187419339346,"velocity":3.511431590223104,"acceleration":-90.0,"pose":{"translation":{"x":4.018835176862188,"y":-2.3457560035239737},"rotation":{"radians":1.07341462703974}},"curvature":0.16881081832860914},{"time":1.4182033258973805,"velocity":0.0,"acceleration":-90.0,"pose":{"translation":{"x":4.051285432909083,"y":-2.2854290076628843},"rotation":{"radians":1.0792327605274032}},"curvature":-2.689929800695296E-15}] \ No newline at end of file From 256313f3125d175b529e1ac365a7eba5581bdde6 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 7 Mar 2020 11:28:41 -0600 Subject: [PATCH 25/31] Testing the gyro values --- .../characterization-data-practice.json | 34068 ++++++++++++++++ src/DriveSubsystem.cpp | 3 +- 2 files changed, 34070 insertions(+), 1 deletion(-) create mode 100644 PathWeaver/characterization-data-practice.json diff --git a/PathWeaver/characterization-data-practice.json b/PathWeaver/characterization-data-practice.json new file mode 100644 index 0000000..d1d12bf --- /dev/null +++ b/PathWeaver/characterization-data-practice.json @@ -0,0 +1,34068 @@ +{ + "slow-forward": [ + [ + 1011.244098, + 12.542223876953125, + 0.0, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.264069, + 12.491964111328125, + 0.0, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.284118, + 12.485681640625, + 0.0, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.304099, + 12.53594140625, + 0.0, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.32409, + 12.491964111328125, + 0.0010416666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.344091, + 12.54850634765625, + 0.0010416666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.364094, + 12.542223876953125, + 0.0020833333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.3841, + 12.491964111328125, + 0.0020833333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.404164, + 12.53594140625, + 0.0020833333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.424078, + 12.49824658203125, + 0.003125, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.444084, + 12.49824658203125, + 0.003125, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.464206, + 12.54850634765625, + 0.004166666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.484201, + 12.485681640625, + 0.004166666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.504082, + 12.491964111328125, + 0.004166666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.52404, + 12.53594140625, + 0.005208333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.544085, + 12.47311669921875, + 0.005208333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.564067, + 12.529658935546875, + 0.0062499999999999995, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.584058, + 12.53594140625, + 0.0062499999999999995, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.604129, + 12.485681640625, + 0.0062499999999999995, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.62413, + 12.53594140625, + 0.007291666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.644034, + 12.49824658203125, + 0.007291666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.664173, + 12.49824658203125, + 0.008333333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.684261, + 12.529658935546875, + 0.008333333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.704071, + 12.491964111328125, + 0.008333333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.724078, + 12.491964111328125, + 0.009375, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.744049, + 12.54850634765625, + 0.009375, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.764073, + 12.49824658203125, + 0.009375, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.78407, + 12.53594140625, + 0.010416666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.804151, + 12.542223876953125, + 0.010416666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.824947, + 12.491964111328125, + 0.011458333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.84413, + 12.542223876953125, + 0.011458333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.864062, + 12.49824658203125, + 0.011458333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.884084, + 12.49824658203125, + 0.012499999999999999, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.904034, + 12.53594140625, + 0.012499999999999999, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.924422, + 12.491964111328125, + 0.013541666666666665, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.944081, + 12.485681640625, + 0.013541666666666665, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.96409, + 12.542223876953125, + 0.013541666666666665, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1011.984083, + 12.479399169921875, + 0.014583333333333332, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.004532, + 12.542223876953125, + 0.014583333333333332, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.024079, + 12.529658935546875, + 0.015624999999999998, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.044072, + 12.479399169921875, + 0.015624999999999998, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.06408, + 12.52337646484375, + 0.015624999999999998, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.084028, + 12.491964111328125, + 0.016666666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.104261, + 12.491964111328125, + 0.016666666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.124066, + 12.542223876953125, + 0.017708333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.144083, + 12.491964111328125, + 0.017708333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.16406, + 12.479399169921875, + 0.017708333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.184107, + 12.542223876953125, + 0.01875, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.204218, + 12.5108115234375, + 0.01875, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.22405, + 12.542223876953125, + 0.01875, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.244067, + 12.54850634765625, + 0.019791666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.264161, + 12.504529052734375, + 0.019791666666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.284082, + 12.53594140625, + 0.020833333333333332, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.304056, + 12.491964111328125, + 0.020833333333333332, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.324163, + 12.491964111328125, + 0.020833333333333332, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.344034, + 12.53594140625, + 0.021875, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.364099, + 12.491964111328125, + 0.021875, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.384078, + 12.485681640625, + 0.022916666666666665, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.404165, + 12.53594140625, + 0.022916666666666665, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.424104, + 12.491964111328125, + 0.022916666666666665, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.444552, + 12.542223876953125, + 0.02395833333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.464417, + 12.491964111328125, + 0.02395833333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.484068, + 12.479399169921875, + 0.024999999999999998, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.504107, + 12.529658935546875, + 0.024999999999999998, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.524105, + 12.491964111328125, + 0.024999999999999998, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.544091, + 12.49824658203125, + 0.026041666666666664, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.564086, + 12.542223876953125, + 0.026041666666666664, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.584095, + 12.49824658203125, + 0.02708333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.604104, + 12.491964111328125, + 0.02708333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.624249, + 12.53594140625, + 0.02708333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.644042, + 12.49824658203125, + 0.028124999999999997, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.664058, + 12.54850634765625, + 0.028124999999999997, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.684115, + 12.485681640625, + 0.028124999999999997, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.7041, + 12.491964111328125, + 0.029166666666666664, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.72406, + 12.53594140625, + 0.029166666666666664, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.744125, + 12.485681640625, + 0.03020833333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.764176, + 12.479399169921875, + 0.03020833333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.784081, + 12.542223876953125, + 0.03020833333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.804064, + 12.491964111328125, + 0.031249999999999997, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.824132, + 12.485681640625, + 0.031249999999999997, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.844103, + 12.529658935546875, + 0.03229166666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.864066, + 12.485681640625, + 0.03229166666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.884078, + 12.53594140625, + 0.03229166666666666, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.90415, + 12.485681640625, + 0.03333333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.924084, + 12.479399169921875, + 0.03333333333333333, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.944069, + 12.53594140625, + 0.034375, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.964096, + 12.479399169921875, + 0.034375, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1012.984478, + 12.485681640625, + 0.034375, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.004237, + 12.542223876953125, + 0.03541666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.024162, + 12.491964111328125, + 0.03541666666666667, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.044118, + 12.491964111328125, + 0.03645833333333334, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.064257, + 12.53594140625, + 0.03645833333333334, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.084109, + 12.485681640625, + 0.03645833333333334, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.104092, + 12.53594140625, + 0.03750000000000001, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.124307, + 12.479399169921875, + 0.03750000000000001, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.144196, + 12.47311669921875, + 0.03854166666666668, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.164028, + 12.529658935546875, + 0.03854166666666668, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.184021, + 12.485681640625, + 0.03854166666666668, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.204124, + 12.479399169921875, + 0.03958333333333335, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.224148, + 12.542223876953125, + 0.03958333333333335, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.244081, + 12.485681640625, + 0.03958333333333335, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.264108, + 12.529658935546875, + 0.04062500000000002, + 0.0, + 0.0, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.284064, + 12.53594140625, + 0.04062500000000002, + 0.5049853372434018, + -0.5069892473118279, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.30405, + 12.485681640625, + 0.04166666666666669, + 0.5049853372434018, + -0.5069892473118279, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.324074, + 12.529658935546875, + 0.04166666666666669, + 0.5173020527859237, + -0.5193548387096774, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.344203, + 12.485681640625, + 0.04166666666666669, + 0.5173020527859237, + -0.5193548387096774, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.364111, + 12.485681640625, + 0.04270833333333336, + 0.5173020527859237, + -0.5193548387096774, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.384125, + 12.529658935546875, + 0.04270833333333336, + 0.5296187683284457, + -0.5317204301075269, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.404069, + 12.479399169921875, + 0.04375000000000003, + 0.5296187683284457, + -0.5317204301075269, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.424187, + 12.491964111328125, + 0.04375000000000003, + 0.5419354838709678, + -0.5440860215053764, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.444253, + 12.529658935546875, + 0.04375000000000003, + 0.5397849462365593, + -0.5440860215053764, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.464089, + 12.491964111328125, + 0.0447916666666667, + 0.5397849462365593, + -0.5440860215053764, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.48408, + 12.53594140625, + 0.0447916666666667, + 0.5520527859237537, + -0.5564516129032259, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.504114, + 12.542223876953125, + 0.04583333333333337, + 0.5520527859237537, + -0.5564516129032259, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.524072, + 12.491964111328125, + 0.04583333333333337, + 0.5643206256109482, + -0.5688172043010753, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.544063, + 12.529658935546875, + 0.04583333333333337, + 0.5643206256109482, + -0.5688172043010753, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.564099, + 12.479399169921875, + 0.04687500000000004, + 0.5643206256109482, + -0.5665689149560117, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.584076, + 12.479399169921875, + 0.04687500000000004, + 0.5765884652981428, + -0.5788856304985337, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.604128, + 12.529658935546875, + 0.04687500000000004, + 0.5765884652981428, + -0.5788856304985337, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.624095, + 12.479399169921875, + 0.04791666666666671, + 0.5765884652981428, + -0.5788856304985337, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.644075, + 12.466834228515625, + 0.04791666666666671, + 0.6011241446725318, + -0.6035190615835777, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.664059, + 12.53594140625, + 0.04895833333333338, + 0.6011241446725318, + -0.6035190615835777, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.684087, + 12.485681640625, + 0.04895833333333338, + 0.6133919843597263, + -0.6158357771260997, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.704071, + 12.517093994140625, + 0.04895833333333338, + 0.6133919843597263, + -0.6158357771260997, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.724185, + 12.52337646484375, + 0.05000000000000005, + 0.6133919843597263, + -0.6158357771260997, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.744089, + 12.479399169921875, + 0.05000000000000005, + 0.6256598240469208, + -0.6281524926686216, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.764116, + 12.517093994140625, + 0.05104166666666672, + 0.6256598240469208, + -0.6281524926686216, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.784133, + 12.485681640625, + 0.05104166666666672, + 0.6379276637341154, + -0.6404692082111436, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.804061, + 12.47311669921875, + 0.05104166666666672, + 0.6379276637341154, + -0.6404692082111436, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.824063, + 12.542223876953125, + 0.05208333333333339, + 0.6379276637341154, + -0.6404692082111436, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.844137, + 12.485681640625, + 0.05208333333333339, + 0.6501955034213099, + -0.6527859237536657, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.864371, + 12.466834228515625, + 0.05312500000000006, + 0.6501955034213099, + -0.6527859237536657, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.88406, + 12.52337646484375, + 0.05312500000000006, + 0.6624633431085044, + -0.6651026392961877, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.90407, + 12.479399169921875, + 0.05312500000000006, + 0.6624633431085044, + -0.6651026392961877, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.924079, + 12.529658935546875, + 0.05416666666666673, + 0.6624633431085044, + -0.6651026392961877, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.944112, + 12.52337646484375, + 0.05416666666666673, + 0.674731182795699, + -0.6774193548387096, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.964115, + 12.466834228515625, + 0.05416666666666673, + 0.674731182795699, + -0.6774193548387096, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1013.984235, + 12.52337646484375, + 0.0552083333333334, + 0.674731182795699, + -0.6774193548387096, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.004104, + 12.485681640625, + 0.0552083333333334, + 0.6869990224828935, + -0.6897360703812316, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.024093, + 12.479399169921875, + 0.05625000000000007, + 0.6869990224828935, + -0.6897360703812316, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.044102, + 12.52337646484375, + 0.05625000000000007, + 0.699266862170088, + -0.7020527859237536, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.064079, + 12.485681640625, + 0.05625000000000007, + 0.699266862170088, + -0.7020527859237536, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.084159, + 12.4605517578125, + 0.05729166666666674, + 0.699266862170088, + -0.7020527859237536, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.104077, + 12.517093994140625, + 0.05729166666666674, + 0.7115347018572825, + -0.7143695014662756, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.124166, + 12.466834228515625, + 0.05833333333333341, + 0.7115347018572825, + -0.7143695014662756, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.144088, + 12.52337646484375, + 0.05833333333333341, + 0.723802541544477, + -0.7266862170087977, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.164152, + 12.52337646484375, + 0.05833333333333341, + 0.723802541544477, + -0.7266862170087977, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.184079, + 12.485681640625, + 0.05937500000000008, + 0.723802541544477, + -0.7266862170087977, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.204048, + 12.529658935546875, + 0.05937500000000008, + 0.7360703812316717, + -0.7390029325513197, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.224024, + 12.466834228515625, + 0.06041666666666675, + 0.7360703812316717, + -0.7390029325513197, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.244158, + 12.479399169921875, + 0.06041666666666675, + 0.7483382209188661, + -0.7513196480938417, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.264037, + 12.53594140625, + 0.06041666666666675, + 0.7483382209188661, + -0.7513196480938417, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.284038, + 12.47311669921875, + 0.06145833333333342, + 0.7483382209188661, + -0.7513196480938417, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.304144, + 12.485681640625, + 0.06145833333333342, + 0.7606060606060606, + -0.7636363636363637, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.324068, + 12.529658935546875, + 0.06250000000000008, + 0.7606060606060606, + -0.7636363636363637, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.344141, + 12.466834228515625, + 0.06250000000000008, + 0.7728739002932552, + -0.7759530791788857, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.3641, + 12.517093994140625, + 0.06250000000000008, + 0.7728739002932552, + -0.7759530791788857, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.384098, + 12.479399169921875, + 0.06354166666666675, + 0.7728739002932552, + -0.7759530791788857, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.404117, + 12.4605517578125, + 0.06354166666666675, + 0.7974095796676443, + -0.8005865102639296, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.424092, + 12.517093994140625, + 0.06354166666666675, + 0.7974095796676443, + -0.8005865102639296, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.444108, + 12.466834228515625, + 0.06458333333333341, + 0.7974095796676443, + -0.8005865102639296, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.464196, + 12.47311669921875, + 0.06458333333333341, + 0.8096774193548387, + -0.8129032258064516, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.484111, + 12.5108115234375, + 0.06562500000000007, + 0.8096774193548387, + -0.8129032258064516, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.504066, + 12.47311669921875, + 0.06562500000000007, + 0.8219452590420332, + -0.8252199413489736, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.52421, + 12.454269287109375, + 0.06562500000000007, + 0.8219452590420332, + -0.8252199413489736, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.544093, + 12.517093994140625, + 0.06666666666666674, + 0.8219452590420332, + -0.8252199413489736, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.564137, + 12.4605517578125, + 0.06666666666666674, + 0.8342130987292278, + -0.8375366568914955, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.584066, + 12.52337646484375, + 0.0677083333333334, + 0.8342130987292278, + -0.8375366568914955, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.604078, + 12.47311669921875, + 0.0677083333333334, + 0.8464809384164222, + -0.8498533724340175, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.624032, + 12.485681640625, + 0.0677083333333334, + 0.8464809384164222, + -0.8498533724340175, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.644144, + 12.52337646484375, + 0.06875000000000006, + 0.8464809384164222, + -0.8498533724340175, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.664191, + 12.47311669921875, + 0.06875000000000006, + 0.8587487781036168, + -0.8621700879765395, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.684089, + 12.479399169921875, + 0.06979166666666672, + 0.8587487781036168, + -0.8621700879765395, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.704128, + 12.52337646484375, + 0.06979166666666672, + 0.8710166177908113, + -0.8744868035190615, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.724105, + 12.47311669921875, + 0.06979166666666672, + 0.8710166177908113, + -0.8744868035190615, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.744049, + 12.4605517578125, + 0.07083333333333339, + 0.8710166177908113, + -0.8744868035190615, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.764029, + 12.517093994140625, + 0.07083333333333339, + 0.8832844574780059, + -0.8868035190615835, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.784157, + 12.4605517578125, + 0.07187500000000005, + 0.8832844574780059, + -0.8868035190615835, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.804088, + 12.52337646484375, + 0.07187500000000005, + 0.8955522971652006, + -0.8991202346041056, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.824071, + 12.466834228515625, + 0.07187500000000005, + 0.8955522971652006, + -0.8991202346041056, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.844092, + 12.454269287109375, + 0.07291666666666671, + 0.8955522971652006, + -0.8991202346041056, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.864107, + 12.517093994140625, + 0.07291666666666671, + 0.907820136852395, + -0.9114369501466276, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.884194, + 12.47311669921875, + 0.07395833333333338, + 0.907820136852395, + -0.9114369501466276, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.904192, + 12.454269287109375, + 0.07395833333333338, + 0.9200879765395895, + -0.9237536656891496, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.924045, + 12.504529052734375, + 0.07395833333333338, + 0.9200879765395895, + -0.9237536656891496, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.944117, + 12.4605517578125, + 0.07500000000000004, + 0.9200879765395895, + -0.9237536656891496, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.964107, + 12.454269287109375, + 0.07500000000000004, + 0.9323558162267841, + -0.9360703812316715, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1014.984056, + 12.5108115234375, + 0.07500000000000004, + 0.9323558162267841, + -0.9360703812316715, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.004118, + 12.454269287109375, + 0.0760416666666667, + 0.9323558162267841, + -0.9360703812316715, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.02418, + 12.5108115234375, + 0.0760416666666667, + 0.9446236559139786, + -0.9483870967741935, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.044134, + 12.454269287109375, + 0.07708333333333336, + 0.9446236559139786, + -0.9483870967741935, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.064125, + 12.47311669921875, + 0.07708333333333336, + 0.9568914956011731, + -0.9607038123167155, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.084081, + 12.517093994140625, + 0.07708333333333336, + 0.9568914956011731, + -0.9607038123167155, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.104073, + 12.454269287109375, + 0.07812500000000003, + 0.9568914956011731, + -0.9607038123167155, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.124343, + 12.44798681640625, + 0.07812500000000003, + 0.9691593352883676, + -0.9730205278592375, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.144476, + 12.504529052734375, + 0.07916666666666669, + 0.9691593352883676, + -0.9730205278592375, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.164065, + 12.44798681640625, + 0.07916666666666669, + 0.9814271749755621, + -0.9853372434017595, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.18407, + 12.49824658203125, + 0.07916666666666669, + 0.9814271749755621, + -0.9853372434017595, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.204095, + 12.504529052734375, + 0.08020833333333335, + 0.9814271749755621, + -0.9853372434017595, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.224072, + 12.4605517578125, + 0.08020833333333335, + 1.0059628543499513, + -1.0099706744868036, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.244088, + 12.49824658203125, + 0.08125000000000002, + 1.0059628543499513, + -1.0099706744868036, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.264675, + 12.454269287109375, + 0.08125000000000002, + 1.0182306940371457, + -1.0222873900293254, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.284085, + 12.454269287109375, + 0.08125000000000002, + 1.0182306940371457, + -1.0222873900293254, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.304107, + 12.504529052734375, + 0.08229166666666668, + 1.0182306940371457, + -1.0222873900293254, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.324064, + 12.454269287109375, + 0.08229166666666668, + 1.0304985337243402, + -1.0346041055718473, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.344322, + 12.454269287109375, + 0.08333333333333334, + 1.0304985337243402, + -1.0346041055718473, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.364072, + 12.5108115234375, + 0.08333333333333334, + 1.0304985337243402, + -1.0469208211143695, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.38411, + 12.454269287109375, + 0.08333333333333334, + 1.0427663734115347, + -1.0469208211143695, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.404066, + 12.49824658203125, + 0.084375, + 1.0427663734115347, + -1.0469208211143695, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.424109, + 12.504529052734375, + 0.084375, + 1.0550342130987291, + -1.0592375366568914, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.444036, + 12.454269287109375, + 0.084375, + 1.0550342130987291, + -1.0592375366568914, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.464033, + 12.491964111328125, + 0.08541666666666667, + 1.0550342130987291, + -1.0592375366568914, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.484063, + 12.4605517578125, + 0.08541666666666667, + 1.0673020527859238, + -1.0715542521994135, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.504075, + 12.4605517578125, + 0.08645833333333333, + 1.0673020527859238, + -1.0715542521994135, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.52412, + 12.5108115234375, + 0.08645833333333333, + 1.0795698924731185, + -1.0838709677419356, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.54409, + 12.44798681640625, + 0.08645833333333333, + 1.0795698924731185, + -1.0838709677419356, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.564046, + 12.4605517578125, + 0.0875, + 1.0795698924731185, + -1.0838709677419356, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.584319, + 12.491964111328125, + 0.0875, + 1.091837732160313, + -1.0961876832844575, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.604115, + 12.44798681640625, + 0.08854166666666666, + 1.091837732160313, + -1.0961876832844575, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.62433, + 12.49824658203125, + 0.08854166666666666, + 1.1041055718475075, + -1.1085043988269796, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.644452, + 12.49824658203125, + 0.08854166666666666, + 1.1041055718475075, + -1.1085043988269796, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.664108, + 12.4605517578125, + 0.08958333333333332, + 1.1041055718475075, + -1.1085043988269796, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.684144, + 12.491964111328125, + 0.08958333333333332, + 1.116373411534702, + -1.1208211143695015, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.704079, + 12.441704345703124, + 0.09062499999999998, + 1.116373411534702, + -1.1208211143695015, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.724091, + 12.44798681640625, + 0.09062499999999998, + 1.1286412512218964, + -1.1331378299120234, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.744101, + 12.49824658203125, + 0.09062499999999998, + 1.1286412512218964, + -1.1331378299120234, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.764131, + 12.44798681640625, + 0.09166666666666665, + 1.1286412512218964, + -1.1331378299120234, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.784107, + 12.441704345703124, + 0.09166666666666665, + 1.140909090909091, + -1.1454545454545455, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.804078, + 12.49824658203125, + 0.09270833333333331, + 1.140909090909091, + -1.1454545454545455, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.824078, + 12.435421875, + 0.09270833333333331, + 1.1531769305962856, + -1.1577712609970674, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.844103, + 12.504529052734375, + 0.09270833333333331, + 1.1531769305962856, + -1.1577712609970674, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.86407, + 12.504529052734375, + 0.09374999999999997, + 1.1531769305962856, + -1.1577712609970674, + 22.894412913528612, + 28.63695221434874, + 0.0, + 0.0, + 0.0 + ], + [ + 1015.884114, + 12.441704345703124, + 0.09374999999999997, + 1.16544477028348, + -1.1700879765395895, + 22.894412913528612, + 28.636017099660446, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1015.904123, + 12.49824658203125, + 0.09374999999999997, + 1.16544477028348, + -1.1700879765395895, + 22.894412913528612, + 28.636017099660446, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1015.924377, + 12.4605517578125, + 0.09479166666666664, + 1.16544477028348, + -1.1700879765395895, + 22.894412913528612, + 28.63508198497215, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1015.944101, + 12.441704345703124, + 0.09479166666666664, + 1.1777126099706745, + -1.1824046920821114, + 22.894412913528612, + 28.63508198497215, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1015.964134, + 12.491964111328125, + 0.0958333333333333, + 1.1777126099706745, + -1.1824046920821114, + 22.894412913528612, + 28.63508198497215, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1015.984134, + 12.435421875, + 0.0958333333333333, + 1.2022482893450637, + -1.2070381231671554, + 22.894412913528612, + 28.63508198497215, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.004061, + 12.429139404296874, + 0.0958333333333333, + 1.2022482893450637, + -1.2070381231671554, + 22.894412913528612, + 28.63508198497215, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.0241, + 12.47311669921875, + 0.09687499999999996, + 1.2022482893450637, + -1.2070381231671554, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.044255, + 12.429139404296874, + 0.09687499999999996, + 1.2145161290322581, + -1.2193548387096773, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.064168, + 12.485681640625, + 0.09791666666666662, + 1.2145161290322581, + -1.2193548387096773, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.084173, + 12.479399169921875, + 0.09791666666666662, + 1.2267839687194526, + -1.2316715542521994, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.104092, + 12.429139404296874, + 0.09791666666666662, + 1.2267839687194526, + -1.2316715542521994, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.124042, + 12.47311669921875, + 0.09895833333333329, + 1.2267839687194526, + -1.2267839687194526, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.144175, + 12.435421875, + 0.09895833333333329, + 1.239051808406647, + -1.239051808406647, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.164081, + 12.435421875, + 0.09999999999999995, + 1.2341153470185728, + -1.239051808406647, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.184164, + 12.479399169921875, + 0.09999999999999995, + 1.2463343108504399, + -1.2513196480938416, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.204114, + 12.429139404296874, + 0.09999999999999995, + 1.2463343108504399, + -1.2513196480938416, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.224112, + 12.42285693359375, + 0.10104166666666661, + 1.2463343108504399, + -1.2513196480938416, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.244097, + 12.485681640625, + 0.10104166666666661, + 1.258553274682307, + -1.2635874877810362, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.264844, + 12.441704345703124, + 0.10208333333333328, + 1.258553274682307, + -1.2635874877810362, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.284078, + 12.479399169921875, + 0.10208333333333328, + 1.270772238514174, + -1.2758553274682307, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.304029, + 12.429139404296874, + 0.10208333333333328, + 1.270772238514174, + -1.2758553274682307, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.32411, + 12.429139404296874, + 0.10312499999999994, + 1.2758553274682307, + -1.2758553274682307, + 22.894412913528612, + 28.63508198497215, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.344122, + 12.47311669921875, + 0.10312499999999994, + 1.2881231671554254, + -1.2881231671554254, + 22.894412913528612, + 28.634146870283853, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.36409, + 12.429139404296874, + 0.1041666666666666, + 1.2881231671554254, + -1.2881231671554254, + 22.894412913528612, + 28.634146870283853, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.384059, + 12.429139404296874, + 0.1041666666666666, + 1.3003910068426199, + -1.3003910068426199, + 22.894412913528612, + 28.634146870283853, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.404116, + 12.466834228515625, + 0.1041666666666666, + 1.3003910068426199, + -1.3003910068426199, + 22.894412913528612, + 28.634146870283853, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.424071, + 12.429139404296874, + 0.10520833333333326, + 1.3003910068426199, + -1.3003910068426199, + 22.894412913528612, + 28.634146870283853, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.444212, + 12.42285693359375, + 0.10520833333333326, + 1.3126588465298143, + -1.3126588465298143, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.464152, + 12.4605517578125, + 0.10520833333333326, + 1.3126588465298143, + -1.3126588465298143, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.484088, + 12.42285693359375, + 0.10624999999999993, + 1.3074291300097751, + -1.3126588465298143, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.504156, + 12.47311669921875, + 0.10624999999999993, + 1.3196480938416422, + -1.3249266862170088, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.524082, + 12.42285693359375, + 0.10729166666666659, + 1.3196480938416422, + -1.3249266862170088, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.544105, + 12.416574462890624, + 0.10729166666666659, + 1.3318670576735092, + -1.3371945259042035, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.564132, + 12.47311669921875, + 0.10729166666666659, + 1.3318670576735092, + -1.3371945259042035, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.584085, + 12.416574462890624, + 0.10833333333333325, + 1.3318670576735092, + -1.3371945259042035, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.604048, + 12.429139404296874, + 0.10833333333333325, + 1.3440860215053763, + -1.349462365591398, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.624336, + 12.47311669921875, + 0.10937499999999992, + 1.3440860215053763, + -1.349462365591398, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.644136, + 12.42285693359375, + 0.10937499999999992, + 1.3563049853372433, + -1.3617302052785925, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.664386, + 12.429139404296874, + 0.10937499999999992, + 1.3563049853372433, + -1.3617302052785925, + 22.894412913528612, + 28.634146870283853, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.684091, + 12.47311669921875, + 0.11041666666666658, + 1.3563049853372433, + -1.3617302052785925, + 22.894412913528612, + 28.63321175559556, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.704116, + 12.416574462890624, + 0.11041666666666658, + 1.3685239491691104, + -1.373998044965787, + 22.894412913528612, + 28.63321175559556, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.72408, + 12.4605517578125, + 0.11145833333333324, + 1.3685239491691104, + -1.373998044965787, + 22.894412913528612, + 28.63321175559556, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.744105, + 12.4102919921875, + 0.11145833333333324, + 1.3929618768328444, + -1.398533724340176, + 22.894412913528612, + 28.63321175559556, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.764109, + 12.4102919921875, + 0.11145833333333324, + 1.3929618768328444, + -1.398533724340176, + 22.894412913528612, + 28.63321175559556, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1016.784275, + 12.454269287109375, + 0.1124999999999999, + 1.3929618768328444, + -1.398533724340176, + 22.894412913528612, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.804069, + 12.4102919921875, + 0.1124999999999999, + 1.4051808406647115, + -1.4108015640273706, + 22.894412913528612, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.824159, + 12.416574462890624, + 0.1124999999999999, + 1.4051808406647115, + -1.4108015640273706, + 22.894412913528612, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.844104, + 12.4605517578125, + 0.11354166666666657, + 1.4051808406647115, + -1.4108015640273706, + 22.894412913528612, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.864138, + 12.404009521484374, + 0.11354166666666657, + 1.4173998044965785, + -1.423069403714565, + 22.894412913528612, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.884096, + 12.416574462890624, + 0.11458333333333323, + 1.4173998044965785, + -1.423069403714565, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.904309, + 12.454269287109375, + 0.11458333333333323, + 1.4296187683284456, + -1.4353372434017595, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.924071, + 12.4102919921875, + 0.11458333333333323, + 1.4296187683284456, + -1.4353372434017595, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.944087, + 12.47311669921875, + 0.1156249999999999, + 1.4296187683284456, + -1.4353372434017595, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1016.96406, + 12.416574462890624, + 0.1156249999999999, + 1.4418377321603126, + -1.447605083088954, + 22.895348028216908, + 28.63321175559556, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1016.984084, + 12.404009521484374, + 0.11666666666666656, + 1.4418377321603126, + -1.447605083088954, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.004133, + 12.4605517578125, + 0.11666666666666656, + 1.4540566959921797, + -1.4598729227761487, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.024092, + 12.4102919921875, + 0.11666666666666656, + 1.4540566959921797, + -1.4598729227761487, + 22.895348028216908, + 28.63321175559556, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.044101, + 12.416574462890624, + 0.11770833333333322, + 1.4540566959921797, + -1.4598729227761487, + 22.895348028216908, + 28.632276640907264, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.064169, + 12.454269287109375, + 0.11770833333333322, + 1.466275659824047, + -1.4721407624633434, + 22.895348028216908, + 28.632276640907264, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.084453, + 12.404009521484374, + 0.11874999999999988, + 1.466275659824047, + -1.4721407624633434, + 22.895348028216908, + 28.632276640907264, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.104142, + 12.42285693359375, + 0.11874999999999988, + 1.478494623655914, + -1.4844086021505378, + 22.895348028216908, + 28.632276640907264, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.124083, + 12.454269287109375, + 0.11874999999999988, + 1.4725806451612906, + -1.4844086021505378, + 22.895348028216908, + 28.632276640907264, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.144102, + 12.391444580078124, + 0.11979166666666655, + 1.4725806451612906, + -1.4844086021505378, + 22.895348028216908, + 28.632276640907264, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.164362, + 12.4605517578125, + 0.11979166666666655, + 1.48475073313783, + -1.4966764418377323, + 22.895348028216908, + 28.632276640907264, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.184032, + 12.39772705078125, + 0.12083333333333321, + 1.48475073313783, + -1.4966764418377323, + 22.895348028216908, + 28.632276640907264, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.204151, + 12.39772705078125, + 0.12083333333333321, + 1.4969208211143696, + -1.5089442815249268, + 22.8962831429052, + 28.631341526218968, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.224087, + 12.44798681640625, + 0.12083333333333321, + 1.4969208211143696, + -1.5089442815249268, + 22.8962831429052, + 28.631341526218968, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.244103, + 12.391444580078124, + 0.12187499999999987, + 1.4969208211143696, + -1.5089442815249268, + 22.8962831429052, + 28.631341526218968, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.264124, + 12.391444580078124, + 0.12187499999999987, + 1.5090909090909093, + -1.5212121212121212, + 22.8962831429052, + 28.631341526218968, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1017.284106, + 12.454269287109375, + 0.12187499999999987, + 1.5090909090909093, + -1.5212121212121212, + 22.8962831429052, + 28.631341526218968, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1017.304112, + 12.391444580078124, + 0.12291666666666654, + 1.5090909090909093, + -1.5212121212121212, + 22.8962831429052, + 28.631341526218968, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.324122, + 12.385162109374999, + 0.12291666666666654, + 1.5212609970674489, + -1.533479960899316, + 22.8962831429052, + 28.631341526218968, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.344204, + 12.44798681640625, + 0.1239583333333332, + 1.5212609970674489, + -1.533479960899316, + 22.8962831429052, + 28.631341526218968, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.364052, + 12.39772705078125, + 0.1239583333333332, + 1.5334310850439885, + -1.5457478005865104, + 22.8962831429052, + 28.631341526218968, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.384068, + 12.441704345703124, + 0.1239583333333332, + 1.5334310850439885, + -1.5457478005865104, + 22.8962831429052, + 28.631341526218968, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.404065, + 12.385162109374999, + 0.12499999999999986, + 1.5334310850439885, + -1.5457478005865104, + 22.8962831429052, + 28.630406411530675, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.424117, + 12.385162109374999, + 0.12499999999999986, + 1.545601173020528, + -1.5580156402737049, + 22.8962831429052, + 28.630406411530675, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.444106, + 12.435421875, + 0.12604166666666652, + 1.545601173020528, + -1.5580156402737049, + 22.8962831429052, + 28.630406411530675, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.464095, + 12.385162109374999, + 0.12604166666666652, + 1.5577712609970675, + -1.5702834799608993, + 22.8962831429052, + 28.630406411530675, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.48406, + 12.391444580078124, + 0.12604166666666652, + 1.5577712609970675, + -1.5702834799608993, + 22.8962831429052, + 28.630406411530675, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.504054, + 12.435421875, + 0.1270833333333332, + 1.5577712609970675, + -1.5702834799608993, + 22.8962831429052, + 28.630406411530675, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.524197, + 12.39772705078125, + 0.1270833333333332, + 1.5821114369501468, + -1.5948191593352885, + 22.897218257593497, + 28.630406411530675, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.544113, + 12.42285693359375, + 0.12812499999999985, + 1.5821114369501468, + -1.5948191593352885, + 22.897218257593497, + 28.630406411530675, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.564135, + 12.435421875, + 0.12812499999999985, + 1.5942815249266864, + -1.607086999022483, + 22.897218257593497, + 28.630406411530675, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.584041, + 12.378879638671874, + 0.12812499999999985, + 1.5942815249266864, + -1.607086999022483, + 22.897218257593497, + 28.630406411530675, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1017.60408, + 12.42285693359375, + 0.1291666666666665, + 1.5942815249266864, + -1.607086999022483, + 22.897218257593497, + 28.630406411530675, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1017.624114, + 12.378879638671874, + 0.1291666666666665, + 1.6064516129032258, + -1.6193548387096774, + 22.897218257593497, + 28.62947129684238, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.644069, + 12.372597167968749, + 0.13020833333333318, + 1.6064516129032258, + -1.6193548387096774, + 22.897218257593497, + 28.62947129684238, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.664107, + 12.416574462890624, + 0.13020833333333318, + 1.6186217008797654, + -1.631622678396872, + 22.897218257593497, + 28.62947129684238, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.68421, + 12.372597167968749, + 0.13020833333333318, + 1.6186217008797654, + -1.631622678396872, + 22.897218257593497, + 28.62947129684238, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.704192, + 12.360032226562499, + 0.13124999999999984, + 1.6186217008797654, + -1.631622678396872, + 22.897218257593497, + 28.62947129684238, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.724147, + 12.429139404296874, + 0.13124999999999984, + 1.630791788856305, + -1.6438905180840664, + 22.897218257593497, + 28.62947129684238, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.744088, + 12.378879638671874, + 0.13124999999999984, + 1.630791788856305, + -1.6438905180840664, + 22.897218257593497, + 28.62947129684238, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.764147, + 12.429139404296874, + 0.1322916666666665, + 1.630791788856305, + -1.6438905180840664, + 22.897218257593497, + 28.62947129684238, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.784079, + 12.429139404296874, + 0.1322916666666665, + 1.6429618768328447, + -1.656158357771261, + 22.897218257593497, + 28.62947129684238, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.804057, + 12.391444580078124, + 0.13333333333333316, + 1.6429618768328447, + -1.656158357771261, + 22.897218257593497, + 28.62947129684238, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.824085, + 12.429139404296874, + 0.13333333333333316, + 1.6551319648093843, + -1.6684261974584556, + 22.897218257593497, + 28.628536182154082, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.844087, + 12.378879638671874, + 0.13333333333333316, + 1.6551319648093843, + -1.6684261974584556, + 22.897218257593497, + 28.628536182154082, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.864108, + 12.372597167968749, + 0.13437499999999983, + 1.6551319648093843, + -1.6684261974584556, + 22.897218257593497, + 28.628536182154082, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.884152, + 12.42285693359375, + 0.13437499999999983, + 1.6673020527859237, + -1.6739980449657867, + 22.897218257593497, + 28.628536182154082, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.904061, + 12.391444580078124, + 0.1354166666666665, + 1.6673020527859237, + -1.6739980449657867, + 22.897218257593497, + 28.628536182154082, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1017.924107, + 12.385162109374999, + 0.1354166666666665, + 1.6794721407624633, + -1.6862170087976538, + 22.897218257593497, + 28.628536182154082, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.944114, + 12.429139404296874, + 0.1354166666666665, + 1.6794721407624633, + -1.6862170087976538, + 22.897218257593497, + 28.628536182154082, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.964092, + 12.385162109374999, + 0.13645833333333315, + 1.6794721407624633, + -1.6862170087976538, + 22.89815337228179, + 28.628536182154082, + 0.0, + 0.0, + 0.0 + ], + [ + 1017.98415, + 12.404009521484374, + 0.13645833333333315, + 1.691642228739003, + -1.6984359726295208, + 22.89815337228179, + 28.628536182154082, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.004109, + 12.391444580078124, + 0.13749999999999982, + 1.691642228739003, + -1.6984359726295208, + 22.89815337228179, + 28.628536182154082, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.024085, + 12.385162109374999, + 0.13749999999999982, + 1.7038123167155426, + -1.7106549364613879, + 22.89815337228179, + 28.628536182154082, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1018.044084, + 12.429139404296874, + 0.13749999999999982, + 1.7038123167155426, + -1.7038123167155426, + 22.89815337228179, + 28.62760106746579, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1018.064052, + 12.366314697265624, + 0.13854166666666648, + 1.7038123167155426, + -1.7038123167155426, + 22.89815337228179, + 28.62760106746579, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.084033, + 12.366314697265624, + 0.13854166666666648, + 1.7159824046920822, + -1.7159824046920822, + 22.89815337228179, + 28.62760106746579, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.104062, + 12.416574462890624, + 0.13958333333333314, + 1.7159824046920822, + -1.7159824046920822, + 22.89815337228179, + 28.62760106746579, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.124121, + 12.366314697265624, + 0.13958333333333314, + 1.7281524926686216, + -1.7281524926686216, + 22.89815337228179, + 28.62760106746579, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.144074, + 12.372597167968749, + 0.13958333333333314, + 1.7281524926686216, + -1.7281524926686216, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.164074, + 12.435421875, + 0.1406249999999998, + 1.7281524926686216, + -1.7281524926686216, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.184097, + 12.360032226562499, + 0.1406249999999998, + 1.7403225806451612, + -1.7403225806451612, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.204309, + 12.435421875, + 0.1406249999999998, + 1.7403225806451612, + -1.747311827956989, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.224078, + 12.372597167968749, + 0.14166666666666647, + 1.7403225806451612, + -1.747311827956989, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.24411, + 12.378879638671874, + 0.14166666666666647, + 1.7524926686217008, + -1.759530791788856, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.264063, + 12.416574462890624, + 0.14270833333333313, + 1.7524926686217008, + -1.759530791788856, + 22.89815337228179, + 28.62760106746579, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.284142, + 12.366314697265624, + 0.14270833333333313, + 1.7646627565982407, + -1.7717497556207236, + 22.89815337228179, + 28.626665952777493, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.304094, + 12.360032226562499, + 0.14270833333333313, + 1.7646627565982407, + -1.7717497556207236, + 22.89815337228179, + 28.626665952777493, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.324089, + 12.4102919921875, + 0.1437499999999998, + 1.7646627565982407, + -1.7717497556207236, + 22.89815337228179, + 28.626665952777493, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.344059, + 12.353749755859374, + 0.1437499999999998, + 1.78900293255132, + -1.7961876832844577, + 22.899088486970086, + 28.626665952777493, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.364206, + 12.341184814453124, + 0.14479166666666646, + 1.78900293255132, + -1.78900293255132, + 22.899088486970086, + 28.626665952777493, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.384039, + 12.404009521484374, + 0.14479166666666646, + 1.8011730205278595, + -1.8011730205278595, + 22.899088486970086, + 28.626665952777493, + 0.0, + 0.0, + 0.0 + ], + [ + 1018.404157, + 12.341184814453124, + 0.14479166666666646, + 1.8011730205278595, + -1.8011730205278595, + 22.899088486970086, + 28.626665952777493, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1018.424095, + 12.39772705078125, + 0.14583333333333312, + 1.8011730205278595, + -1.8011730205278595, + 22.899088486970086, + 28.625730838089197, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1018.444063, + 12.341184814453124, + 0.14583333333333312, + 1.8133431085043992, + -1.8133431085043992, + 22.899088486970086, + 28.625730838089197, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1018.464104, + 12.347467285156249, + 0.14583333333333312, + 1.8133431085043992, + -1.8133431085043992, + 22.899088486970086, + 28.624795723400904, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1018.484066, + 12.385162109374999, + 0.14687499999999978, + 1.8133431085043992, + -1.8133431085043992, + 22.900023601658383, + 28.624795723400904, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1018.504097, + 12.341184814453124, + 0.14687499999999978, + 1.8255131964809386, + -1.8255131964809386, + 22.900023601658383, + 28.623860608712608, + 0.0, + -0.02805344064885261, + 0.0 + ], + [ + 1018.524059, + 12.341184814453124, + 0.14791666666666645, + 1.8255131964809386, + -1.8255131964809386, + 22.900958716346675, + 28.623860608712608, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1018.544047, + 12.385162109374999, + 0.14791666666666645, + 1.8376832844574782, + -1.8376832844574782, + 22.900958716346675, + 28.622925494024315, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.564165, + 12.347467285156249, + 0.14791666666666645, + 1.8303030303030305, + -1.8376832844574782, + 22.900958716346675, + 28.622925494024315, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1018.584044, + 12.347467285156249, + 0.1489583333333331, + 1.8303030303030305, + -1.8376832844574782, + 22.901893831034972, + 28.62199037933602, + 0.018702293765901736, + -0.02805344064885261, + 0.0 + ], + [ + 1018.604119, + 12.39772705078125, + 0.1489583333333331, + 1.8424242424242425, + -1.8498533724340178, + 22.901893831034972, + 28.62199037933602, + 0.018702293765901736, + -0.018702293765901736, + 0.0 + ], + [ + 1018.624148, + 12.334902343749999, + 0.14999999999999977, + 1.8424242424242425, + -1.8498533724340178, + 22.901893831034972, + 28.621055264647723, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.644076, + 12.385162109374999, + 0.14999999999999977, + 1.8545454545454547, + -1.8620234604105574, + 22.902828945723268, + 28.62012014995943, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.664109, + 12.353749755859374, + 0.14999999999999977, + 1.8545454545454547, + -1.8620234604105574, + 22.902828945723268, + 28.62012014995943, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.68413, + 12.328619873046875, + 0.15104166666666644, + 1.8545454545454547, + -1.8620234604105574, + 22.902828945723268, + 28.619185035271133, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.705567, + 12.39772705078125, + 0.15104166666666644, + 1.8666666666666667, + -1.874193548387097, + 22.90376406041156, + 28.619185035271133, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.724095, + 12.341184814453124, + 0.1520833333333331, + 1.8666666666666667, + -1.874193548387097, + 22.90376406041156, + 28.619185035271133, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1018.744092, + 12.32233740234375, + 0.1520833333333331, + 1.878787878787879, + -1.8863636363636367, + 22.904699175099857, + 28.618249920582837, + 0.018702293765901736, + -0.018702293765901736, + 0.0 + ], + [ + 1018.764134, + 12.372597167968749, + 0.1520833333333331, + 1.878787878787879, + -1.8863636363636367, + 22.904699175099857, + 28.617314805894544, + 0.018702293765901736, + -0.02805344064885261, + 0.0 + ], + [ + 1018.784226, + 12.328619873046875, + 0.15312499999999976, + 1.878787878787879, + -1.8863636363636367, + 22.905634289788154, + 28.617314805894544, + 0.018702293765901736, + -0.018702293765901736, + 0.0 + ], + [ + 1018.804074, + 12.316054931640625, + 0.15312499999999976, + 1.890909090909091, + -1.898533724340176, + 22.905634289788154, + 28.617314805894544, + 0.018702293765901736, + -0.018702293765901736, + 0.0 + ], + [ + 1018.824112, + 12.391444580078124, + 0.15416666666666642, + 1.890909090909091, + -1.898533724340176, + 22.905634289788154, + 28.616379691206248, + 0.018702293765901736, + -0.018702293765901736, + 0.0 + ], + [ + 1018.844117, + 12.316054931640625, + 0.15416666666666642, + 1.903030303030303, + -1.9107038123167157, + 22.906569404476446, + 28.616379691206248, + 0.018702293765901736, + -0.018702293765901736, + 0.0 + ], + [ + 1018.864138, + 12.366314697265624, + 0.15416666666666642, + 1.903030303030303, + -1.9107038123167157, + 22.906569404476446, + 28.61544457651795, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1018.884155, + 12.32233740234375, + 0.1552083333333331, + 1.903030303030303, + -1.9107038123167157, + 22.906569404476446, + 28.61544457651795, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1018.904156, + 12.328619873046875, + 0.1552083333333331, + 1.9151515151515153, + -1.9228739002932553, + 22.907504519164743, + 28.61544457651795, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1018.924068, + 12.378879638671874, + 0.1552083333333331, + 1.9151515151515153, + -1.9228739002932553, + 22.907504519164743, + 28.61544457651795, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1018.944177, + 12.316054931640625, + 0.15624999999999975, + 1.9151515151515153, + -1.9228739002932553, + 22.907504519164743, + 28.61544457651795, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1018.964158, + 12.32233740234375, + 0.15624999999999975, + 1.9272727272727272, + -1.935043988269795, + 22.907504519164743, + 28.61544457651795, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1018.984029, + 12.360032226562499, + 0.1572916666666664, + 1.9272727272727272, + -1.935043988269795, + 22.907504519164743, + 28.61450946182966, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.004048, + 12.328619873046875, + 0.1572916666666664, + 1.9393939393939394, + -1.9472140762463346, + 22.907504519164743, + 28.61450946182966, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.024339, + 12.328619873046875, + 0.1572916666666664, + 1.9393939393939394, + -1.9472140762463346, + 22.907504519164743, + 28.61450946182966, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.044116, + 12.378879638671874, + 0.15833333333333308, + 1.9393939393939394, + -1.9472140762463346, + 22.907504519164743, + 28.61450946182966, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.064167, + 12.328619873046875, + 0.15833333333333308, + 1.9515151515151516, + -1.959384164222874, + 22.907504519164743, + 28.61450946182966, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.084105, + 12.385162109374999, + 0.15937499999999974, + 1.9515151515151516, + -1.959384164222874, + 22.907504519164743, + 28.61450946182966, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.104124, + 12.334902343749999, + 0.15937499999999974, + 1.9757575757575758, + -1.9837243401759532, + 22.907504519164743, + 28.61450946182966, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.124132, + 12.316054931640625, + 0.15937499999999974, + 1.9757575757575758, + -1.9837243401759532, + 22.907504519164743, + 28.61450946182966, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.144113, + 12.372597167968749, + 0.1604166666666664, + 1.9757575757575758, + -1.9837243401759532, + 22.907504519164743, + 28.61450946182966, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.164062, + 12.328619873046875, + 0.1604166666666664, + 1.9878787878787878, + -1.9878787878787878, + 22.907504519164743, + 28.61450946182966, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.184073, + 12.316054931640625, + 0.16145833333333307, + 1.9878787878787878, + -1.9878787878787878, + 22.907504519164743, + 28.61450946182966, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.204095, + 12.366314697265624, + 0.16145833333333307, + 2.0, + -2.0, + 22.90843963385304, + 28.613574347141363, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.224071, + 12.328619873046875, + 0.16145833333333307, + 2.0, + -2.0, + 22.90843963385304, + 28.613574347141363, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.244124, + 12.378879638671874, + 0.16249999999999973, + 2.0, + -2.0, + 22.90843963385304, + 28.613574347141363, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.264129, + 12.385162109374999, + 0.16249999999999973, + 2.012121212121212, + -2.012121212121212, + 22.90843963385304, + 28.613574347141363, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.284269, + 12.328619873046875, + 0.1635416666666664, + 2.012121212121212, + -2.012121212121212, + 22.90843963385304, + 28.613574347141363, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.304286, + 12.372597167968749, + 0.1635416666666664, + 2.0242424242424244, + -2.0242424242424244, + 22.90843963385304, + 28.613574347141363, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.324074, + 12.3097724609375, + 0.1635416666666664, + 2.0242424242424244, + -2.0324046920821117, + 22.90843963385304, + 28.613574347141363, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.344152, + 12.316054931640625, + 0.16458333333333305, + 2.0242424242424244, + -2.0324046920821117, + 22.90843963385304, + 28.613574347141363, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.364071, + 12.353749755859374, + 0.16458333333333305, + 2.036363636363636, + -2.044574780058651, + 22.90843963385304, + 28.613574347141363, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.384151, + 12.32233740234375, + 0.16562499999999972, + 2.036363636363636, + -2.044574780058651, + 22.90843963385304, + 28.613574347141363, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.40412, + 12.3097724609375, + 0.16562499999999972, + 2.0484848484848484, + -2.0567448680351905, + 22.90843963385304, + 28.612639232453066, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.424066, + 12.366314697265624, + 0.16562499999999972, + 2.0484848484848484, + -2.0567448680351905, + 22.90843963385304, + 28.612639232453066, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.444114, + 12.3097724609375, + 0.16666666666666638, + 2.0484848484848484, + -2.0567448680351905, + 22.90843963385304, + 28.612639232453066, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.464088, + 12.353749755859374, + 0.16666666666666638, + 2.0606060606060606, + -2.06891495601173, + 22.90843963385304, + 28.612639232453066, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.484122, + 12.347467285156249, + 0.16666666666666638, + 2.0606060606060606, + -2.06891495601173, + 22.90937474854133, + 28.612639232453066, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.504108, + 12.303489990234375, + 0.16770833333333304, + 2.0606060606060606, + -2.06891495601173, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.524068, + 12.353749755859374, + 0.16770833333333304, + 2.0727272727272728, + -2.0810850439882698, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.544105, + 12.290925048828125, + 0.1687499999999997, + 2.0727272727272728, + -2.0810850439882698, + 22.90937474854133, + 28.612639232453066, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1019.564151, + 12.290925048828125, + 0.1687499999999997, + 2.084848484848485, + -2.0932551319648094, + 22.90937474854133, + 28.612639232453066, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1019.584073, + 12.347467285156249, + 0.1687499999999997, + 2.084848484848485, + -2.0932551319648094, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.60407, + 12.303489990234375, + 0.16979166666666637, + 2.084848484848485, + -2.0932551319648094, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.624125, + 12.290925048828125, + 0.16979166666666637, + 2.0969696969696967, + -2.105425219941349, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.644103, + 12.347467285156249, + 0.17083333333333303, + 2.0969696969696967, + -2.0969696969696967, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.664058, + 12.29720751953125, + 0.17083333333333303, + 2.109090909090909, + -2.109090909090909, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.684256, + 12.328619873046875, + 0.17083333333333303, + 2.109090909090909, + -2.109090909090909, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.704034, + 12.334902343749999, + 0.1718749999999997, + 2.109090909090909, + -2.109090909090909, + 22.90937474854133, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.724069, + 12.290925048828125, + 0.1718749999999997, + 2.121212121212121, + -2.121212121212121, + 22.910309863229628, + 28.612639232453066, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.74408, + 12.334902343749999, + 0.17291666666666636, + 2.121212121212121, + -2.121212121212121, + 22.910309863229628, + 28.611704117764774, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.76411, + 12.27207763671875, + 0.17291666666666636, + 2.1333333333333337, + -2.1333333333333337, + 22.910309863229628, + 28.611704117764774, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.784065, + 12.284642578125, + 0.17291666666666636, + 2.1333333333333337, + -2.1333333333333337, + 22.911244977917924, + 28.611704117764774, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.804035, + 12.353749755859374, + 0.17395833333333302, + 2.1333333333333337, + -2.1333333333333337, + 22.911244977917924, + 28.611704117764774, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.824098, + 12.290925048828125, + 0.17395833333333302, + 2.1454545454545455, + -2.1454545454545455, + 22.911244977917924, + 28.611704117764774, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.844086, + 12.290925048828125, + 0.17395833333333302, + 2.1454545454545455, + -2.1454545454545455, + 22.911244977917924, + 28.610769003076477, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.864108, + 12.341184814453124, + 0.17499999999999968, + 2.1454545454545455, + -2.1454545454545455, + 22.911244977917924, + 28.610769003076477, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1019.884234, + 12.278360107421875, + 0.17499999999999968, + 2.16969696969697, + -2.16969696969697, + 22.911244977917924, + 28.610769003076477, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.904133, + 12.341184814453124, + 0.17604166666666635, + 2.16969696969697, + -2.16969696969697, + 22.911244977917924, + 28.610769003076477, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.924112, + 12.328619873046875, + 0.17604166666666635, + 2.181818181818182, + -2.181818181818182, + 22.911244977917924, + 28.610769003076477, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1019.94407, + 12.27207763671875, + 0.17604166666666635, + 2.181818181818182, + -2.181818181818182, + 22.911244977917924, + 28.610769003076477, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.964066, + 12.334902343749999, + 0.177083333333333, + 2.181818181818182, + -2.1730205278592374, + 22.911244977917924, + 28.610769003076477, + 0.0, + 0.0, + 0.0 + ], + [ + 1019.984091, + 12.2595126953125, + 0.177083333333333, + 2.1939393939393943, + -2.185092864125122, + 22.911244977917924, + 28.610769003076477, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.00408, + 12.29720751953125, + 0.17812499999999967, + 2.185092864125122, + -2.185092864125122, + 22.911244977917924, + 28.60983388838818, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.024192, + 12.316054931640625, + 0.17812499999999967, + 2.197165200391007, + -2.197165200391007, + 22.912180092606217, + 28.60983388838818, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.044101, + 12.284642578125, + 0.17812499999999967, + 2.197165200391007, + -2.197165200391007, + 22.912180092606217, + 28.60983388838818, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.064024, + 12.27207763671875, + 0.17916666666666634, + 2.197165200391007, + -2.197165200391007, + 22.912180092606217, + 28.60983388838818, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.084159, + 12.32233740234375, + 0.17916666666666634, + 2.2092375366568917, + -2.2092375366568917, + 22.913115207294513, + 28.608898773699888, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1020.104082, + 12.27207763671875, + 0.180208333333333, + 2.2092375366568917, + -2.2092375366568917, + 22.913115207294513, + 28.608898773699888, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1020.1241, + 12.316054931640625, + 0.180208333333333, + 2.221309872922776, + -2.2303030303030305, + 22.913115207294513, + 28.60796365901159, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1020.144073, + 12.316054931640625, + 0.180208333333333, + 2.221309872922776, + -2.2303030303030305, + 22.913115207294513, + 28.607028544323295, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1020.164061, + 12.2595126953125, + 0.18124999999999966, + 2.221309872922776, + -2.2303030303030305, + 22.913115207294513, + 28.607028544323295, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1020.184186, + 12.316054931640625, + 0.18124999999999966, + 2.233382209188661, + -2.2424242424242427, + 22.913115207294513, + 28.606093429635003, + 0.0, + -0.02805344064885261, + 0.0 + ], + [ + 1020.204106, + 12.278360107421875, + 0.18124999999999966, + 2.233382209188661, + -2.2424242424242427, + 22.91405032198281, + 28.606093429635003, + 0.0, + -0.02805344064885261, + 0.0 + ], + [ + 1020.224065, + 12.284642578125, + 0.18229166666666632, + 2.233382209188661, + -2.2424242424242427, + 22.914985436671103, + 28.605158314946706, + 0.0, + -0.02805344064885261, + 0.0 + ], + [ + 1020.244269, + 12.303489990234375, + 0.18229166666666632, + 2.2454545454545456, + -2.254545454545455, + 22.914985436671103, + 28.605158314946706, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1020.264184, + 12.27207763671875, + 0.18229166666666632, + 2.2454545454545456, + -2.254545454545455, + 22.914985436671103, + 28.60422320025841, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1020.284205, + 12.278360107421875, + 0.183333333333333, + 2.2454545454545456, + -2.2454545454545456, + 22.914985436671103, + 28.603288085570117, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1020.304131, + 12.32233740234375, + 0.183333333333333, + 2.25752688172043, + -2.25752688172043, + 22.914985436671103, + 28.603288085570117, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1020.324085, + 12.27207763671875, + 0.183333333333333, + 2.25752688172043, + -2.25752688172043, + 22.914985436671103, + 28.603288085570117, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1020.344179, + 12.316054931640625, + 0.18437499999999965, + 2.25752688172043, + -2.25752688172043, + 22.9159205513594, + 28.60235297088182, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1020.36441, + 12.24694775390625, + 0.18437499999999965, + 2.2695992179863147, + -2.2695992179863147, + 22.9159205513594, + 28.60235297088182, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1020.384129, + 12.265795166015625, + 0.1854166666666663, + 2.2695992179863147, + -2.2695992179863147, + 22.9159205513594, + 28.60235297088182, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1020.404082, + 12.290925048828125, + 0.1854166666666663, + 2.2816715542521995, + -2.2816715542521995, + 22.9159205513594, + 28.60235297088182, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.424041, + 12.240665283203125, + 0.1854166666666663, + 2.2816715542521995, + -2.2816715542521995, + 22.9159205513594, + 28.601417856193528, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1020.444613, + 12.2343828125, + 0.18645833333333298, + 2.2816715542521995, + -2.2816715542521995, + 22.9159205513594, + 28.601417856193528, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.464319, + 12.303489990234375, + 0.18645833333333298, + 2.293743890518084, + -2.293743890518084, + 22.9159205513594, + 28.601417856193528, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.484148, + 12.228100341796875, + 0.18645833333333298, + 2.293743890518084, + -2.293743890518084, + 22.9159205513594, + 28.601417856193528, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.504086, + 12.228100341796875, + 0.18749999999999964, + 2.293743890518084, + -2.293743890518084, + 22.9159205513594, + 28.601417856193528, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.524079, + 12.27207763671875, + 0.18749999999999964, + 2.3058162267839686, + -2.3058162267839686, + 22.9159205513594, + 28.601417856193528, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.544267, + 12.253230224609375, + 0.18749999999999964, + 2.3058162267839686, + -2.3058162267839686, + 22.916855666047695, + 28.600482741505232, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.564169, + 12.278360107421875, + 0.1885416666666663, + 2.3058162267839686, + -2.3058162267839686, + 22.916855666047695, + 28.600482741505232, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.584118, + 12.240665283203125, + 0.1885416666666663, + 2.3178885630498534, + -2.3178885630498534, + 22.916855666047695, + 28.600482741505232, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.604111, + 12.2343828125, + 0.18958333333333297, + 2.3178885630498534, + -2.3178885630498534, + 22.916855666047695, + 28.600482741505232, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1020.624123, + 12.290925048828125, + 0.18958333333333297, + 2.329960899315738, + -2.329960899315738, + 22.916855666047695, + 28.600482741505232, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1020.644404, + 12.253230224609375, + 0.18958333333333297, + 2.329960899315738, + -2.329960899315738, + 22.916855666047695, + 28.600482741505232, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.664072, + 12.2343828125, + 0.19062499999999963, + 2.329960899315738, + -2.329960899315738, + 22.916855666047695, + 28.600482741505232, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.684082, + 12.265795166015625, + 0.19062499999999963, + 2.3541055718475072, + -2.3541055718475072, + 22.916855666047695, + 28.600482741505232, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.704167, + 12.22181787109375, + 0.1916666666666663, + 2.3541055718475072, + -2.3541055718475072, + 22.916855666047695, + 28.599547626816936, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.724024, + 12.2092529296875, + 0.1916666666666663, + 2.366177908113392, + -2.366177908113392, + 22.916855666047695, + 28.599547626816936, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.744183, + 12.265795166015625, + 0.1916666666666663, + 2.366177908113392, + -2.366177908113392, + 22.917790780735988, + 28.599547626816936, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.764089, + 12.19668798828125, + 0.19270833333333295, + 2.366177908113392, + -2.366177908113392, + 22.917790780735988, + 28.599547626816936, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.784114, + 12.265795166015625, + 0.19270833333333295, + 2.3782502443792763, + -2.3782502443792763, + 22.917790780735988, + 28.599547626816936, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.804083, + 12.2092529296875, + 0.19374999999999962, + 2.3686217008797654, + -2.3782502443792763, + 22.917790780735988, + 28.599547626816936, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1020.824088, + 12.2092529296875, + 0.19374999999999962, + 2.3806451612903228, + -2.390322580645161, + 22.917790780735988, + 28.599547626816936, + 0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1020.844116, + 12.253230224609375, + 0.19374999999999962, + 2.3806451612903228, + -2.390322580645161, + 22.917790780735988, + 28.598612512128643, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.864041, + 12.215535400390625, + 0.19479166666666628, + 2.3806451612903228, + -2.390322580645161, + 22.917790780735988, + 28.598612512128643, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.884076, + 12.202970458984375, + 0.19479166666666628, + 2.3926686217008797, + -2.402394916911046, + 22.917790780735988, + 28.598612512128643, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.904047, + 12.253230224609375, + 0.19479166666666628, + 2.3926686217008797, + -2.402394916911046, + 22.917790780735988, + 28.598612512128643, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.924106, + 12.2092529296875, + 0.19583333333333294, + 2.3926686217008797, + -2.402394916911046, + 22.917790780735988, + 28.598612512128643, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1020.944071, + 12.253230224609375, + 0.19583333333333294, + 2.404692082111437, + -2.4144672531769302, + 22.917790780735988, + 28.598612512128643, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.964081, + 12.265795166015625, + 0.1968749999999996, + 2.404692082111437, + -2.4144672531769302, + 22.918725895424284, + 28.598612512128643, + 0.0, + 0.0, + 0.0 + ], + [ + 1020.984065, + 12.215535400390625, + 0.1968749999999996, + 2.4167155425219944, + -2.426539589442815, + 22.918725895424284, + 28.598612512128643, + 0.0, + 0.0, + 0.0 + ], + [ + 1021.004064, + 12.278360107421875, + 0.1968749999999996, + 2.4167155425219944, + -2.426539589442815, + 22.918725895424284, + 28.597677397440346, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1021.024076, + 12.22181787109375, + 0.19791666666666627, + 2.4167155425219944, + -2.426539589442815, + 22.918725895424284, + 28.597677397440346, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1021.044323, + 12.19668798828125, + 0.19791666666666627, + 2.4287390029325513, + -2.4386119257087, + 22.918725895424284, + 28.597677397440346, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1021.064102, + 12.27207763671875, + 0.19791666666666627, + 2.4287390029325513, + -2.4386119257087, + 22.918725895424284, + 28.597677397440346, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1021.08406, + 12.22181787109375, + 0.19895833333333293, + 2.4287390029325513, + -2.4386119257087, + 22.918725895424284, + 28.597677397440346, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1021.104134, + 12.2092529296875, + 0.19895833333333293, + 2.4407624633431086, + -2.4506842619745846, + 22.918725895424284, + 28.59674228275205, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1021.124076, + 12.2595126953125, + 0.19895833333333293, + 2.4407624633431086, + -2.4506842619745846, + 22.919661010112577, + 28.59674228275205, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1021.144109, + 12.202970458984375, + 0.1999999999999996, + 2.4407624633431086, + -2.4506842619745846, + 22.919661010112577, + 28.59674228275205, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1021.164076, + 12.2595126953125, + 0.1999999999999996, + 2.4527859237536656, + -2.462756598240469, + 22.919661010112577, + 28.595807168063757, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1021.18408, + 12.27207763671875, + 0.20104166666666626, + 2.4527859237536656, + -2.462756598240469, + 22.919661010112577, + 28.595807168063757, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1021.204137, + 12.215535400390625, + 0.20104166666666626, + 2.464809384164223, + -2.4748289345063537, + 22.919661010112577, + 28.59487205337546, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1021.224061, + 12.27207763671875, + 0.20104166666666626, + 2.464809384164223, + -2.4748289345063537, + 22.920596124800873, + 28.59487205337546, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1021.244198, + 12.19668798828125, + 0.20208333333333292, + 2.464809384164223, + -2.4547898338220917, + 22.920596124800873, + 28.593936938687165, + 0.0, + -0.02805344064885261, + 0.0 + ], + [ + 1021.264081, + 12.215535400390625, + 0.20208333333333292, + 2.4768328445747803, + -2.4667644183773216, + 22.920596124800873, + 28.593936938687165, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1021.284086, + 12.265795166015625, + 0.20208333333333292, + 2.4667644183773216, + -2.4667644183773216, + 22.92153123948917, + 28.593001823998872, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1021.304111, + 12.202970458984375, + 0.20312499999999958, + 2.4667644183773216, + -2.4667644183773216, + 22.92153123948917, + 28.593001823998872, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1021.324032, + 12.202970458984375, + 0.20312499999999958, + 2.478739002932551, + -2.478739002932551, + 22.92153123948917, + 28.592066709310576, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1021.344194, + 12.2595126953125, + 0.20312499999999958, + 2.478739002932551, + -2.478739002932551, + 22.922466354177462, + 28.592066709310576, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1021.365971, + 12.202970458984375, + 0.20416666666666625, + 2.478739002932551, + -2.478739002932551, + 22.922466354177462, + 28.59113159462228, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1021.384047, + 12.27207763671875, + 0.20416666666666625, + 2.490713587487781, + -2.490713587487781, + 22.922466354177462, + 28.59113159462228, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1021.404116, + 12.265795166015625, + 0.2052083333333329, + 2.490713587487781, + -2.5008797653958945, + 22.92340146886576, + 28.59113159462228, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1021.424182, + 12.215535400390625, + 0.2052083333333329, + 2.502688172043011, + -2.512903225806452, + 22.92340146886576, + 28.59113159462228, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1021.444114, + 12.27207763671875, + 0.2052083333333329, + 2.502688172043011, + -2.512903225806452, + 22.92340146886576, + 28.590196479933986, + 0.009351146882950868, + -0.018702293765901736, + 0.0 + ], + [ + 1021.464112, + 12.215535400390625, + 0.20624999999999957, + 2.502688172043011, + -2.512903225806452, + 22.92340146886576, + 28.590196479933986, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1021.484084, + 12.19668798828125, + 0.20624999999999957, + 2.5146627565982405, + -2.524926686217009, + 22.92340146886576, + 28.590196479933986, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1021.504279, + 12.253230224609375, + 0.20729166666666624, + 2.5146627565982405, + -2.524926686217009, + 22.92340146886576, + 28.58926136524569, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1021.524121, + 12.202970458984375, + 0.20729166666666624, + 2.5386119257087, + -2.5489736070381235, + 22.92340146886576, + 28.58926136524569, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1021.544073, + 12.184123046875, + 0.20729166666666624, + 2.5386119257087, + -2.5489736070381235, + 22.924336583554055, + 28.588326250557394, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1021.56408, + 12.24694775390625, + 0.20729166666666624, + 2.5386119257087, + -2.5386119257087, + 22.924336583554055, + 28.5873911358691, + 0.0, + -0.02805344064885261, + 0.0 + ], + [ + 1021.584303, + 12.190405517578125, + 0.20729166666666624, + 2.5386119257087, + -2.5386119257087, + 22.925271698242348, + 28.586456021180805, + 0.0, + -0.03740458753180347, + 0.0 + ], + [ + 1021.604128, + 12.24694775390625, + 0.20729166666666624, + 2.5386119257087, + -2.5386119257087, + 22.925271698242348, + 28.586456021180805, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1021.624074, + 12.22181787109375, + 0.20729166666666624, + 2.5386119257087, + -2.5386119257087, + 22.926206812930644, + 28.58552090649251, + 0.009351146882950868, + -0.03740458753180347, + 0.0 + ], + [ + 1021.644226, + 12.202970458984375, + 0.20729166666666624, + 2.5386119257087, + -2.5386119257087, + 22.926206812930644, + 28.58552090649251, + 0.018702293765901736, + -0.02805344064885261, + 0.0 + ], + [ + 1021.664111, + 12.22181787109375, + 0.2083333333333329, + 2.5386119257087, + -2.5386119257087, + 22.926206812930644, + 28.584585791804216, + 0.018702293765901736, + -0.02805344064885261, + 0.0 + ], + [ + 1021.684083, + 12.165275634765624, + 0.2083333333333329, + 2.55058651026393, + -2.55058651026393, + 22.926206812930644, + 28.582715562427623, + 0.018702293765901736, + -0.03740458753180347, + 0.0 + ], + [ + 1021.704094, + 12.17155810546875, + 0.20937499999999956, + 2.55058651026393, + -2.55058651026393, + 22.92714192761894, + 28.582715562427623, + 0.009351146882950868, + -0.03740458753180347, + 0.0 + ], + [ + 1021.724084, + 12.215535400390625, + 0.20937499999999956, + 2.5625610948191593, + -2.5625610948191593, + 22.92714192761894, + 28.580845333051034, + 0.009351146882950868, + -0.04675573441475434, + 0.0 + ], + [ + 1021.74408, + 12.165275634765624, + 0.20937499999999956, + 2.5625610948191593, + -2.5625610948191593, + 22.928077042307233, + 28.57991021836274, + 0.009351146882950868, + -0.05610688129770522, + 0.0 + ], + [ + 1021.7641, + 12.184123046875, + 0.20937499999999956, + 2.5625610948191593, + -2.5625610948191593, + 22.928077042307233, + 28.578975103674445, + 0.009351146882950868, + -0.05610688129770522, + 0.0 + ], + [ + 1021.784108, + 12.2092529296875, + 0.21041666666666622, + 2.5625610948191593, + -2.5625610948191593, + 22.92901215699553, + 28.57803998898615, + 0.018702293765901736, + -0.04675573441475434, + 0.0 + ], + [ + 1021.804172, + 12.17155810546875, + 0.21041666666666622, + 2.574535679374389, + -2.574535679374389, + 22.929947271683826, + 28.577104874297856, + 0.018702293765901736, + -0.05610688129770522, + 0.0 + ], + [ + 1021.824092, + 12.22181787109375, + 0.2114583333333329, + 2.574535679374389, + -2.574535679374389, + 22.929947271683826, + 28.57616975960956, + 0.018702293765901736, + -0.04675573441475434, + 0.0 + ], + [ + 1021.844317, + 12.190405517578125, + 0.2114583333333329, + 2.5865102639296187, + -2.5865102639296187, + 22.93088238637212, + 28.575234644921263, + 0.018702293765901736, + -0.04675573441475434, + 0.0 + ], + [ + 1021.864165, + 12.152710693359374, + 0.2114583333333329, + 2.5865102639296187, + -2.5865102639296187, + 22.93088238637212, + 28.575234644921263, + 0.018702293765901736, + -0.04675573441475434, + 0.0 + ], + [ + 1021.884105, + 12.2092529296875, + 0.21249999999999955, + 2.5865102639296187, + -2.5865102639296187, + 22.931817501060415, + 28.573364415544674, + 0.018702293765901736, + -0.05610688129770522, + 0.0 + ], + [ + 1021.904117, + 12.1589931640625, + 0.21249999999999955, + 2.5984848484848486, + -2.5984848484848486, + 22.93275261574871, + 28.572429300856378, + 0.018702293765901736, + -0.05610688129770522, + 0.0 + ], + [ + 1021.924038, + 12.14642822265625, + 0.21249999999999955, + 2.5984848484848486, + -2.5984848484848486, + 22.93275261574871, + 28.569623956791492, + 0.018702293765901736, + -0.06545802818065607, + 0.0 + ], + [ + 1021.944119, + 12.19668798828125, + 0.21249999999999955, + 2.5984848484848486, + -2.5984848484848486, + 22.933687730437004, + 28.5686888421032, + 0.018702293765901736, + -0.07480917506360694, + 0.0 + ], + [ + 1021.964143, + 12.152710693359374, + 0.2135416666666662, + 2.5984848484848486, + -2.5984848484848486, + 22.9346228451253, + 28.566818612726607, + 0.02805344064885261, + -0.06545802818065607, + 0.0 + ], + [ + 1021.984119, + 12.152710693359374, + 0.2135416666666662, + 2.610459433040078, + -2.610459433040078, + 22.935557959813597, + 28.565883498038314, + 0.02805344064885261, + -0.06545802818065607, + 0.0 + ], + [ + 1022.004197, + 12.19668798828125, + 0.2135416666666662, + 2.610459433040078, + -2.610459433040078, + 22.93649307450189, + 28.56401326866172, + 0.02805344064885261, + -0.06545802818065607, + 0.0 + ], + [ + 1022.02408, + 12.14642822265625, + 0.21458333333333288, + 2.610459433040078, + -2.610459433040078, + 22.937428189190186, + 28.56307815397343, + 0.03740458753180347, + -0.06545802818065607, + 0.0 + ], + [ + 1022.044099, + 12.202970458984375, + 0.21458333333333288, + 2.622434017595308, + -2.622434017595308, + 22.938363303878482, + 28.561207924596836, + 0.03740458753180347, + -0.06545802818065607, + 0.0 + ], + [ + 1022.064097, + 12.14642822265625, + 0.21458333333333288, + 2.622434017595308, + -2.622434017595308, + 22.939298418566775, + 28.560272809908543, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1022.08412, + 12.13386328125, + 0.21562499999999954, + 2.622434017595308, + -2.622434017595308, + 22.941168647943364, + 28.558402580531954, + 0.04675573441475434, + -0.07480917506360694, + 0.0 + ], + [ + 1022.104202, + 12.19668798828125, + 0.21562499999999954, + 2.6344086021505375, + -2.6344086021505375, + 22.94210376263166, + 28.557467465843658, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1022.124098, + 12.1589931640625, + 0.21562499999999954, + 2.6344086021505375, + -2.6344086021505375, + 22.943038877319957, + 28.55559723646707, + 0.04675573441475434, + -0.07480917506360694, + 0.0 + ], + [ + 1022.144105, + 12.1589931640625, + 0.21562499999999954, + 2.6344086021505375, + -2.6344086021505375, + 22.944909106696546, + 28.554662121778772, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1022.164025, + 12.2343828125, + 0.2166666666666662, + 2.6344086021505375, + -2.6344086021505375, + 22.945844221384842, + 28.552791892402183, + 0.05610688129770522, + -0.07480917506360694, + 0.0 + ], + [ + 1022.184175, + 12.165275634765624, + 0.2166666666666662, + 2.6463831867057674, + -2.6463831867057674, + 22.945844221384842, + 28.551856777713887, + 0.05610688129770522, + -0.06545802818065607, + 0.0 + ], + [ + 1022.204078, + 12.17155810546875, + 0.2166666666666662, + 2.6463831867057674, + -2.6463831867057674, + 22.946779336073135, + 28.55092166302559, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1022.22406, + 12.215535400390625, + 0.21770833333333287, + 2.6463831867057674, + -2.6463831867057674, + 22.94771445076143, + 28.549051433649, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1022.244088, + 12.1589931640625, + 0.21770833333333287, + 2.658357771260997, + -2.658357771260997, + 22.948649565449728, + 28.548116318960705, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1022.264067, + 12.2343828125, + 0.21770833333333287, + 2.658357771260997, + -2.658357771260997, + 22.94958468013802, + 28.547181204272412, + 0.03740458753180347, + -0.05610688129770522, + 0.0 + ], + [ + 1022.284124, + 12.140145751953124, + 0.21770833333333287, + 2.658357771260997, + -2.658357771260997, + 22.951454909514613, + 28.54531097489582, + 0.03740458753180347, + -0.06545802818065607, + 0.0 + ], + [ + 1022.304059, + 12.177840576171874, + 0.21874999999999953, + 2.658357771260997, + -2.658357771260997, + 22.951454909514613, + 28.54344074551923, + 0.03740458753180347, + -0.07480917506360694, + 0.0 + ], + [ + 1022.32407, + 12.22181787109375, + 0.21874999999999953, + 2.670332355816227, + -2.670332355816227, + 22.952390024202906, + 28.54157051614264, + 0.04675573441475434, + -0.07480917506360694, + 0.0 + ], + [ + 1022.344031, + 12.165275634765624, + 0.21874999999999953, + 2.670332355816227, + -2.670332355816227, + 22.9542602535795, + 28.540635401454345, + 0.04675573441475434, + -0.07480917506360694, + 0.0 + ], + [ + 1022.364094, + 12.152710693359374, + 0.2197916666666662, + 2.670332355816227, + -2.670332355816227, + 22.956130482956087, + 28.538765172077756, + 0.04675573441475434, + -0.08416032194655781, + 0.0 + ], + [ + 1022.384154, + 12.2092529296875, + 0.2197916666666662, + 2.6823069403714563, + -2.6823069403714563, + 22.958000712332677, + 28.536894942701167, + 0.05610688129770522, + -0.08416032194655781, + 0.0 + ], + [ + 1022.404142, + 12.152710693359374, + 0.2197916666666662, + 2.6823069403714563, + -2.6823069403714563, + 22.95987094170927, + 28.535024713324574, + 0.05610688129770522, + -0.08416032194655781, + 0.0 + ], + [ + 1022.424135, + 12.14642822265625, + 0.2197916666666662, + 2.6823069403714563, + -2.6823069403714563, + 22.96174117108586, + 28.533154483947985, + 0.06545802818065607, + -0.08416032194655781, + 0.0 + ], + [ + 1022.444128, + 12.2092529296875, + 0.22083333333333285, + 2.6823069403714563, + -2.6823069403714563, + 22.96267628577415, + 28.53221936925969, + 0.07480917506360694, + -0.08416032194655781, + 0.0 + ], + [ + 1022.46407, + 12.17155810546875, + 0.22083333333333285, + 2.6942815249266863, + -2.6942815249266863, + 22.964546515150744, + 28.5303491398831, + 0.07480917506360694, + -0.08416032194655781, + 0.0 + ], + [ + 1022.484134, + 12.228100341796875, + 0.22187499999999952, + 2.6942815249266863, + -2.6942815249266863, + 22.965481629839037, + 28.529414025194804, + 0.07480917506360694, + -0.07480917506360694, + 0.0 + ], + [ + 1022.504087, + 12.165275634765624, + 0.22187499999999952, + 2.7062561094819158, + -2.7062561094819158, + 22.966416744527333, + 28.527543795818215, + 0.07480917506360694, + -0.07480917506360694, + 0.0 + ], + [ + 1022.524101, + 12.17155810546875, + 0.22187499999999952, + 2.7062561094819158, + -2.7062561094819158, + 22.966416744527333, + 28.526608681129918, + 0.06545802818065607, + -0.06545802818065607, + 0.0 + ], + [ + 1022.544075, + 12.2343828125, + 0.22187499999999952, + 2.7062561094819158, + -2.7062561094819158, + 22.96735185921563, + 28.525673566441625, + 0.05610688129770522, + -0.06545802818065607, + 0.0 + ], + [ + 1022.564074, + 12.17155810546875, + 0.22291666666666618, + 2.7062561094819158, + -2.7062561094819158, + 22.968286973903922, + 28.525673566441625, + 0.04675573441475434, + -0.04675573441475434, + 0.0 + ], + [ + 1022.584086, + 12.177840576171874, + 0.22291666666666618, + 2.730205278592375, + -2.730205278592375, + 22.96922208859222, + 28.525673566441625, + 0.03740458753180347, + -0.03740458753180347, + 0.0 + ], + [ + 1022.604084, + 12.228100341796875, + 0.22291666666666618, + 2.730205278592375, + -2.730205278592375, + 22.96922208859222, + 28.52473845175333, + 0.02805344064885261, + -0.02805344064885261, + 0.0 + ], + [ + 1022.62412, + 12.165275634765624, + 0.22395833333333284, + 2.730205278592375, + -2.730205278592375, + 22.96922208859222, + 28.52473845175333, + 0.02805344064885261, + -0.018702293765901736, + 0.0 + ], + [ + 1022.644174, + 12.17155810546875, + 0.22395833333333284, + 2.742179863147605, + -2.742179863147605, + 22.96922208859222, + 28.52473845175333, + 0.018702293765901736, + -0.009351146882950868, + 0.0 + ], + [ + 1022.664027, + 12.19668798828125, + 0.22395833333333284, + 2.742179863147605, + -2.742179863147605, + 22.96922208859222, + 28.52473845175333, + 0.018702293765901736, + -0.009351146882950868, + 0.0 + ], + [ + 1022.684135, + 12.165275634765624, + 0.2249999999999995, + 2.742179863147605, + -2.742179863147605, + 22.96922208859222, + 28.52473845175333, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1022.704061, + 12.177840576171874, + 0.2249999999999995, + 2.7541544477028346, + -2.7541544477028346, + 22.96922208859222, + 28.52473845175333, + 0.0, + 0.0, + 0.0 + ], + [ + 1022.724064, + 12.13386328125, + 0.22604166666666617, + 2.7429130009775173, + -2.7541544477028346, + 22.96922208859222, + 28.52473845175333, + 0.0, + 0.0, + 0.0 + ], + [ + 1022.744091, + 12.115015869140624, + 0.22604166666666617, + 2.7548387096774194, + -2.7661290322580645, + 22.96922208859222, + 28.52473845175333, + 0.0, + 0.0, + 0.0 + ], + [ + 1022.764281, + 12.215535400390625, + 0.22604166666666617, + 2.7548387096774194, + -2.7661290322580645, + 22.96922208859222, + 28.52473845175333, + 0.0, + 0.0, + 0.0 + ], + [ + 1022.784104, + 12.13386328125, + 0.22708333333333283, + 2.7548387096774194, + -2.7661290322580645, + 22.96922208859222, + 28.523803337065033, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.804061, + 12.121298339843749, + 0.22708333333333283, + 2.766764418377322, + -2.778103616813294, + 22.96922208859222, + 28.523803337065033, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.824057, + 12.165275634765624, + 0.2281249999999995, + 2.766764418377322, + -2.778103616813294, + 22.96922208859222, + 28.523803337065033, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.844076, + 12.115015869140624, + 0.2281249999999995, + 2.778690127077224, + -2.778690127077224, + 22.96922208859222, + 28.523803337065033, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.864461, + 12.202970458984375, + 0.2281249999999995, + 2.778690127077224, + -2.778690127077224, + 22.96922208859222, + 28.523803337065033, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.88406, + 12.152710693359374, + 0.22916666666666616, + 2.778690127077224, + -2.778690127077224, + 22.96922208859222, + 28.523803337065033, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.904057, + 12.108733398437499, + 0.22916666666666616, + 2.790615835777126, + -2.790615835777126, + 22.96922208859222, + 28.523803337065033, + 0.0, + 0.0, + 0.0 + ], + [ + 1022.924116, + 12.184123046875, + 0.23020833333333282, + 2.790615835777126, + -2.790615835777126, + 22.970157203280515, + 28.52286822237674, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.944057, + 12.096168457031249, + 0.23020833333333282, + 2.8025415444770285, + -2.8025415444770285, + 22.970157203280515, + 28.52286822237674, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.964164, + 12.102450927734374, + 0.23020833333333282, + 2.8025415444770285, + -2.8025415444770285, + 22.970157203280515, + 28.52286822237674, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1022.984089, + 12.152710693359374, + 0.23124999999999948, + 2.8025415444770285, + -2.8025415444770285, + 22.970157203280515, + 28.52286822237674, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1023.004219, + 12.108733398437499, + 0.23124999999999948, + 2.8144672531769306, + -2.8144672531769306, + 22.970157203280515, + 28.52286822237674, + 0.009351146882950868, + -0.009351146882950868, + 0.0 + ], + [ + 1023.024097, + 12.089885986328124, + 0.23124999999999948, + 2.8144672531769306, + -2.8144672531769306, + 22.970157203280515, + 28.52286822237674, + 0.0, + 0.0, + 0.0 + ], + [ + 1023.044072, + 12.152710693359374, + 0.23229166666666615, + 2.8144672531769306, + -2.8144672531769306, + 22.970157203280515, + 28.52286822237674, + 0.0, + 0.0, + 0.0 + ], + [ + 1023.064093, + 12.102450927734374, + 0.23229166666666615, + 2.826392961876833, + -2.826392961876833, + 22.971092317968807, + 28.521933107688444, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1023.084087, + 12.13386328125, + 0.2333333333333328, + 2.826392961876833, + -2.826392961876833, + 22.971092317968807, + 28.521933107688444, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1023.104115, + 12.13386328125, + 0.2333333333333328, + 2.838318670576735, + -2.838318670576735, + 22.971092317968807, + 28.520997993000147, + 0.0, + -0.018702293765901736, + 0.0 + ], + [ + 1023.124098, + 12.096168457031249, + 0.2333333333333328, + 2.838318670576735, + -2.838318670576735, + 22.972027432657104, + 28.520062878311855, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1023.144205, + 12.127580810546874, + 0.23437499999999947, + 2.838318670576735, + -2.838318670576735, + 22.972027432657104, + 28.520062878311855, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1023.164068, + 12.089885986328124, + 0.23437499999999947, + 2.850244379276637, + -2.850244379276637, + 22.972027432657104, + 28.51912776362356, + 0.009351146882950868, + -0.02805344064885261, + 0.0 + ], + [ + 1023.18409, + 12.083603515624999, + 0.23541666666666614, + 2.850244379276637, + -2.850244379276637, + 22.9729625473454, + 28.518192648935262, + 0.009351146882950868, + -0.03740458753180347, + 0.0 + ], + [ + 1023.204114, + 12.14642822265625, + 0.23541666666666614, + 2.86217008797654, + -2.86217008797654, + 22.973897662033693, + 28.516322419558673, + 0.009351146882950868, + -0.04675573441475434, + 0.0 + ], + [ + 1023.224205, + 12.096168457031249, + 0.23541666666666614, + 2.86217008797654, + -2.86217008797654, + 22.97483277672199, + 28.514452190182084, + 0.018702293765901736, + -0.05610688129770522, + 0.0 + ], + [ + 1023.244067, + 12.115015869140624, + 0.2364583333333328, + 2.86217008797654, + -2.86217008797654, + 22.975767891410285, + 28.513517075493787, + 0.02805344064885261, + -0.06545802818065607, + 0.0 + ], + [ + 1023.264061, + 12.1589931640625, + 0.2364583333333328, + 2.874095796676442, + -2.874095796676442, + 22.977638120786875, + 28.512581960805495, + 0.02805344064885261, + -0.06545802818065607, + 0.0 + ], + [ + 1023.284116, + 12.096168457031249, + 0.23749999999999946, + 2.874095796676442, + -2.874095796676442, + 22.97857323547517, + 28.510711731428902, + 0.03740458753180347, + -0.07480917506360694, + 0.0 + ], + [ + 1023.304063, + 12.152710693359374, + 0.23749999999999946, + 2.8860215053763443, + -2.8860215053763443, + 22.98044346485176, + 28.50977661674061, + 0.04675573441475434, + -0.06545802818065607, + 0.0 + ], + [ + 1023.324093, + 12.152710693359374, + 0.23749999999999946, + 2.8860215053763443, + -2.874193548387097, + 22.981378579540056, + 28.508841502052313, + 0.05610688129770522, + -0.05610688129770522, + 0.0 + ], + [ + 1023.344091, + 12.108733398437499, + 0.23854166666666612, + 2.8860215053763443, + -2.874193548387097, + 22.983248808916645, + 28.506971272675724, + 0.05610688129770522, + -0.06545802818065607, + 0.0 + ], + [ + 1023.36425, + 12.140145751953124, + 0.23854166666666612, + 2.909872922776149, + -2.8979472140762463, + 22.985119038293234, + 28.506036157987428, + 0.06545802818065607, + -0.06545802818065607, + 0.0 + ], + [ + 1023.38406, + 12.115015869140624, + 0.23854166666666612, + 2.909872922776149, + -2.8979472140762463, + 22.98605415298153, + 28.50416592861084, + 0.06545802818065607, + -0.06545802818065607, + 0.0 + ], + [ + 1023.40408, + 12.102450927734374, + 0.2395833333333328, + 2.909872922776149, + -2.8979472140762463, + 22.98792438235812, + 28.501360584545953, + 0.06545802818065607, + -0.08416032194655781, + 0.0 + ], + [ + 1023.42409, + 12.152710693359374, + 0.2395833333333328, + 2.9217986314760513, + -2.9098240469208214, + 22.98979461173471, + 28.49949035516936, + 0.06545802818065607, + -0.09351146882950868, + 0.0 + ], + [ + 1023.444175, + 12.102450927734374, + 0.24062499999999945, + 2.9217986314760513, + -2.9098240469208214, + 22.9916648411113, + 28.49668501110448, + 0.07480917506360694, + -0.10286261571245955, + 0.0 + ], + [ + 1023.464084, + 12.115015869140624, + 0.24062499999999945, + 2.9217986314760513, + -2.921700879765396, + 22.994470185176187, + 28.493879667039593, + 0.07480917506360694, + -0.1215649094783613, + 0.0 + ], + [ + 1023.484096, + 12.17155810546875, + 0.24062499999999945, + 2.9337243401759534, + -2.9096774193548387, + 22.997275529241072, + 28.491074322974708, + 0.08416032194655781, + -0.13091605636131215, + 0.0 + ], + [ + 1023.504094, + 12.121298339843749, + 0.2416666666666661, + 2.9337243401759534, + -2.9096774193548387, + 23.000080873305958, + 28.487333864221526, + 0.10286261571245955, + -0.14026720324426303, + 0.0 + ], + [ + 1023.524076, + 12.17155810546875, + 0.2416666666666661, + 2.9456500488758555, + -2.921505376344086, + 23.00288621737084, + 28.48452852015664, + 0.11221376259541044, + -0.1496183501272139, + 0.0 + ], + [ + 1023.544073, + 12.165275634765624, + 0.2416666666666661, + 2.9456500488758555, + -2.921505376344086, + 23.005691561435725, + 28.479852946715166, + 0.1215649094783613, + -0.16832064389311563, + 0.0 + ], + [ + 1023.564339, + 12.083603515624999, + 0.24270833333333278, + 2.9456500488758555, + -2.921505376344086, + 23.009432020188907, + 28.474242258585395, + 0.13091605636131215, + -0.19637408454196825, + 0.0 + ], + [ + 1023.584141, + 12.127580810546874, + 0.24270833333333278, + 2.957575757575758, + -2.933333333333333, + 23.01317247894209, + 28.46956668514392, + 0.14026720324426303, + -0.21507637830786996, + 0.0 + ], + [ + 1023.60407, + 12.108733398437499, + 0.24374999999999944, + 2.957575757575758, + -2.933333333333333, + 23.016912937695267, + 28.46956668514392, + 0.1496183501272139, + -0.21507637830786996, + 0.0 + ], + [ + 1023.624109, + 12.115015869140624, + 0.24374999999999944, + 2.96950146627566, + -2.945161290322581, + 23.02065339644845, + 28.463020882325853, + 0.15896949701016477, + -0.2431298189567226, + 0.0 + ], + [ + 1023.644257, + 12.17155810546875, + 0.24374999999999944, + 2.96950146627566, + -2.945161290322581, + 23.025328969889923, + 28.457410194196083, + 0.16832064389311563, + -0.27118325960557516, + 0.0 + ], + [ + 1023.664098, + 12.108733398437499, + 0.24374999999999944, + 2.96950146627566, + -2.945161290322581, + 23.030004543331398, + 28.451799506066312, + 0.1776717907760665, + -0.28053440648852607, + 0.0 + ], + [ + 1023.684079, + 12.115015869140624, + 0.2447916666666661, + 2.96950146627566, + -2.945161290322581, + 23.034680116772876, + 28.441513244495066, + 0.18702293765901737, + -0.28053440648852607, + 0.0 + ], + [ + 1023.704056, + 12.152710693359374, + 0.2447916666666661, + 2.9814271749755625, + -2.956989247311828, + 23.040290804902646, + 28.437772785741885, + 0.2057252314249191, + -0.25248096583967344, + 0.0 + ], + [ + 1023.724107, + 12.089885986328124, + 0.24583333333333277, + 2.9814271749755625, + -2.956989247311828, + 23.045901493032414, + 28.432162097612117, + 0.21507637830786996, + -0.2431298189567226, + 0.0 + ], + [ + 1023.744114, + 12.1589931640625, + 0.24583333333333277, + 2.9933528836754646, + -2.968817204301075, + 23.051512181162185, + 28.42748652417064, + 0.2337786720737717, + -0.2431298189567226, + 0.0 + ], + [ + 1023.764074, + 12.089885986328124, + 0.24583333333333277, + 2.9933528836754646, + -2.968817204301075, + 23.057122869291955, + 28.42187583604087, + 0.2431298189567226, + -0.25248096583967344, + 0.0 + ], + [ + 1023.784034, + 12.096168457031249, + 0.24687499999999943, + 2.9933528836754646, + -2.968817204301075, + 23.061798442733433, + 28.415330033222805, + 0.25248096583967344, + -0.2618321127226243, + 0.0 + ], + [ + 1023.804139, + 12.152710693359374, + 0.24687499999999943, + 3.0052785923753667, + -2.9929618768328448, + 23.0674091308632, + 28.408784230404738, + 0.2618321127226243, + -0.2898855533714769, + 0.0 + ], + [ + 1023.824023, + 12.064756103515625, + 0.2479166666666661, + 3.0052785923753667, + -2.9929618768328448, + 23.07208470430468, + 28.402238427586674, + 0.2618321127226243, + -0.3085878471373787, + 0.0 + ], + [ + 1023.844354, + 12.108733398437499, + 0.2479166666666661, + 3.0048387096774194, + -3.0048387096774194, + 23.078630507122742, + 28.39475751008031, + 0.2618321127226243, + -0.32729014090328035, + 0.0 + ], + [ + 1023.864084, + 12.127580810546874, + 0.2479166666666661, + 3.0048387096774194, + -3.0048387096774194, + 23.086111424629106, + 28.39475751008031, + 0.27118325960557516, + -0.32729014090328035, + 0.0 + ], + [ + 1023.884028, + 12.0584736328125, + 0.24895833333333275, + 3.0048387096774194, + -3.0048387096774194, + 23.093592342135466, + 28.37605521631441, + 0.28053440648852607, + -0.3927481690839365, + 0.0 + ], + [ + 1023.904066, + 12.04590869140625, + 0.24895833333333275, + 3.016715542521994, + -3.016715542521994, + 23.101073259641826, + 28.367639184119756, + 0.2992367002544278, + -0.4208016097327891, + 0.0 + ], + [ + 1023.924229, + 12.140145751953124, + 0.24895833333333275, + 3.016715542521994, + -3.016715542521994, + 23.109489291836482, + 28.356417807860215, + 0.32729014090328035, + -0.45820619726459255, + 0.0 + ], + [ + 1023.944078, + 12.027061279296875, + 0.24999999999999942, + 3.016715542521994, + -3.016715542521994, + 23.11790532403114, + 28.345196431600673, + 0.34599243466918217, + -0.495610784796396, + 0.0 + ], + [ + 1023.964075, + 12.083603515624999, + 0.24999999999999942, + 3.028592375366569, + -3.0161290322580645, + 23.128191585602384, + 28.33397505534113, + 0.37404587531803474, + -0.5236642254452486, + 0.0 + ], + [ + 1023.984109, + 12.03334375, + 0.2510416666666661, + 3.028592375366569, + -3.0161290322580645, + 23.137542732485333, + 28.321818564393297, + 0.40209931596688736, + -0.5423665192111503, + 0.0 + ], + [ + 1024.004096, + 12.03334375, + 0.2510416666666661, + 3.0404692082111437, + -3.0279569892473117, + 23.148764108744874, + 28.308726958757163, + 0.4208016097327891, + -0.5797711067429538, + 0.0 + ], + [ + 1024.024964, + 12.096168457031249, + 0.2510416666666661, + 3.0404692082111437, + -3.0279569892473117, + 23.161855714381005, + 28.29470023843274, + 0.45820619726459255, + -0.6171756942747574, + 0.0 + ], + [ + 1024.044119, + 12.0584736328125, + 0.25208333333333277, + 3.0404692082111437, + -3.0279569892473117, + 23.161855714381005, + 28.29470023843274, + 0.45820619726459255, + -0.6171756942747574, + 0.0 + ], + [ + 1024.064118, + 12.03334375, + 0.25208333333333277, + 3.0523460410557184, + -3.039784946236559, + 23.174947320017136, + 28.28160863279661, + 0.495610784796396, + -0.6452291349236099, + 0.0 + ], + [ + 1024.084041, + 12.077321044921874, + 0.25312499999999943, + 3.0523460410557184, + -3.039784946236559, + 23.203935875354286, + 28.26571168309559, + 0.5797711067429538, + -0.6732825755724625, + 0.0 + ], + [ + 1024.104209, + 12.039626220703125, + 0.25312499999999943, + 3.0642228739002935, + -3.051612903225806, + 23.218897710367006, + 28.249814733394572, + 0.6265268411577083, + -0.720038309987217, + 0.0 + ], + [ + 1024.124034, + 12.039626220703125, + 0.25312499999999943, + 3.0642228739002935, + -3.051612903225806, + 23.232924430691433, + 28.232047554316967, + 0.6639314286895116, + -0.7667940444019712, + 0.0 + ], + [ + 1024.144098, + 12.115015869140624, + 0.2541666666666661, + 3.0642228739002935, + -3.051612903225806, + 23.247886265704153, + 28.215215489927655, + 0.6919848693383643, + -0.7948474850508238, + 0.0 + ], + [ + 1024.164151, + 12.027061279296875, + 0.2541666666666661, + 3.0879765395894427, + -3.075268817204301, + 23.265653444781762, + 28.192772737408575, + 0.720038309987217, + -0.8790078069973817, + 0.0 + ], + [ + 1024.18405, + 12.121298339843749, + 0.2541666666666661, + 3.0879765395894427, + -3.075268817204301, + 23.283420623859367, + 28.17220021426608, + 0.7387406037531186, + -0.9351146882950868, + 0.0 + ], + [ + 1024.204117, + 12.089885986328124, + 0.25520833333333276, + 3.0879765395894427, + -3.075268817204301, + 23.301187802936973, + 28.149757461747, + 0.7667940444019712, + -1.000572716475743, + 0.0 + ], + [ + 1024.224109, + 12.064756103515625, + 0.25520833333333276, + 3.099853372434018, + -3.087096774193548, + 23.32082521139117, + 28.128249823916214, + 0.8041986319337747, + -1.0379773040075464, + 0.0 + ], + [ + 1024.244087, + 12.089885986328124, + 0.2562499999999994, + 3.099853372434018, + -3.087096774193548, + 23.339527505157072, + 28.10580707139713, + 0.8416032194655781, + -1.0847330384223006, + 0.0 + ], + [ + 1024.264034, + 12.083603515624999, + 0.2562499999999994, + 3.1117302052785925, + -3.0989247311827954, + 23.36103514298786, + 28.083364318878047, + 0.8883589538803326, + -1.1034353321882024, + 0.0 + ], + [ + 1024.284092, + 12.083603515624999, + 0.2562499999999994, + 3.1117302052785925, + -3.1245356793743895, + 23.381607666130353, + 28.038478813839884, + 0.9257635414121359, + -1.1127864790711532, + 0.0 + ], + [ + 1024.304082, + 12.115015869140624, + 0.2572916666666661, + 3.1117302052785925, + -3.1245356793743895, + 23.404050418649433, + 28.015100946632508, + 0.9631681289439395, + -1.131488772837055, + 0.0 + ], + [ + 1024.324444, + 12.03334375, + 0.2572916666666661, + 3.1364613880742915, + -3.1364613880742915, + 23.426493171168516, + 27.990787964736835, + 1.000572716475743, + -1.150191066602957, + 0.0 + ], + [ + 1024.344086, + 12.071038574218749, + 0.25833333333333275, + 3.1364613880742915, + -3.1364613880742915, + 23.426493171168516, + 27.990787964736835, + 1.000572716475743, + -1.150191066602957, + 0.0 + ], + [ + 1024.364114, + 12.115015869140624, + 0.25833333333333275, + 3.1483870967741936, + -3.1483870967741936, + 23.47511913495986, + 27.9402917715689, + 1.0753818915393498, + -1.2062979479006621, + 0.0 + ], + [ + 1024.384059, + 12.052191162109375, + 0.25833333333333275, + 3.1483870967741936, + -3.1483870967741936, + 23.500367231543827, + 27.912238330920047, + 1.1127864790711532, + -1.2717559760813182, + 0.0 + ], + [ + 1024.404293, + 12.077321044921874, + 0.2593749999999994, + 3.1483870967741936, + -3.1483870967741936, + 23.523745098751206, + 27.8832497755829, + 1.150191066602957, + -1.3185117104960726, + 0.0 + ], + [ + 1024.42408, + 12.077321044921874, + 0.2593749999999994, + 3.160312805474096, + -3.160312805474096, + 23.549928310023468, + 27.851455876180868, + 1.1782445072518093, + -1.3933208855596793, + 0.0 + ], + [ + 1024.444069, + 12.064756103515625, + 0.2593749999999994, + 3.160312805474096, + -3.147360703812317, + 23.577046635984026, + 27.814986403337358, + 1.2062979479006621, + -1.5242369419209916, + 0.0 + ], + [ + 1024.46409, + 12.115015869140624, + 0.2604166666666661, + 3.160312805474096, + -3.147360703812317, + 23.606035191321173, + 27.78038715987044, + 1.2437025354324653, + -1.5990461169845984, + 0.0 + ], + [ + 1024.484108, + 12.083603515624999, + 0.2604166666666661, + 3.1462365591397847, + -3.1592375366568914, + 23.634088631970027, + 27.74672303109182, + 1.281107122964269, + -1.6458018513993529, + 0.0 + ], + [ + 1024.504098, + 12.071038574218749, + 0.26145833333333274, + 3.1462365591397847, + -3.1592375366568914, + 23.663077187307174, + 27.713058902313193, + 1.3185117104960726, + -1.7019087326970581, + 0.0 + ], + [ + 1024.524541, + 12.077321044921874, + 0.26145833333333274, + 3.158064516129032, + -3.171114369501466, + 23.693000857332617, + 27.679394773534572, + 1.3652674449108269, + -1.7206110264629597, + 0.0 + ], + [ + 1024.544134, + 12.0584736328125, + 0.26145833333333274, + 3.158064516129032, + -3.171114369501466, + 23.693000857332617, + 27.679394773534572, + 1.3652674449108269, + -1.7206110264629597, + 0.0 + ], + [ + 1024.564184, + 12.0584736328125, + 0.2624999999999994, + 3.158064516129032, + -3.171114369501466, + 23.72479475673465, + 27.645730644755947, + 1.4026720324426303, + -1.6925575858141073, + 0.0 + ], + [ + 1024.584087, + 12.13386328125, + 0.2624999999999994, + 3.169892473118279, + -3.182991202346041, + 23.754718426760093, + 27.610196286600733, + 1.440076619974434, + -1.7019087326970581, + 0.0 + ], + [ + 1024.604123, + 12.071038574218749, + 0.2624999999999994, + 3.169892473118279, + -3.169892473118279, + 23.822981799005632, + 27.574661928445522, + 1.5148857950380408, + -1.7206110264629597, + 0.0 + ], + [ + 1024.62408, + 12.14642822265625, + 0.26354166666666606, + 3.169892473118279, + -3.169892473118279, + 23.856645927784257, + 27.53725734091372, + 1.5522903825698442, + -1.7580156139947634, + 0.0 + ], + [ + 1024.644117, + 12.071038574218749, + 0.26354166666666606, + 3.194868035190616, + -3.181720430107527, + 23.892180285939467, + 27.49704740931703, + 1.5990461169845984, + -1.8141224952924684, + 0.0 + ], + [ + 1024.664106, + 12.083603515624999, + 0.26354166666666606, + 3.194868035190616, + -3.181720430107527, + 23.92771464409468, + 27.415692431435357, + 1.6458018513993529, + -1.9356874047708297, + 0.0 + ], + [ + 1024.684091, + 12.127580810546874, + 0.2645833333333327, + 3.194868035190616, + -3.181720430107527, + 23.965119231626485, + 27.374547385150372, + 1.6925575858141073, + -2.0104965798344367, + 0.0 + ], + [ + 1024.70409, + 12.077321044921874, + 0.2645833333333327, + 3.2067448680351904, + -3.193548387096774, + 24.002523819158288, + 27.332467224177094, + 1.7299621733459105, + -2.0479011673662404, + 0.0 + ], + [ + 1024.724114, + 12.089885986328124, + 0.2656249999999994, + 3.2067448680351904, + -3.193548387096774, + 24.03712306262521, + 27.29506263664529, + 1.7673667608777142, + -2.0198477267173875, + 0.0 + ], + [ + 1024.744085, + 12.121298339843749, + 0.2656249999999994, + 3.2186217008797655, + -3.2053763440860212, + 24.07265742078042, + 27.252047360983717, + 1.7860690546436158, + -2.0479011673662404, + 0.0 + ], + [ + 1024.764126, + 12.083603515624999, + 0.2656249999999994, + 3.2186217008797655, + -3.2186217008797655, + 24.110062008312223, + 27.209967200010436, + 1.795420201526567, + -2.0479011673662404, + 0.0 + ], + [ + 1024.784073, + 12.071038574218749, + 0.26666666666666605, + 3.2186217008797655, + -3.2186217008797655, + 24.148401710532323, + 27.16601680966057, + 1.8047713484095176, + -2.0853057548980436, + 0.0 + ], + [ + 1024.804078, + 12.13386328125, + 0.26666666666666605, + 3.2172043010752684, + -3.23049853372434, + 24.1904818715056, + 27.121131304622406, + 1.8234736421754194, + -2.1227103424298472, + 0.0 + ], + [ + 1024.824027, + 12.027061279296875, + 0.2677083333333327, + 3.2172043010752684, + -3.23049853372434, + 24.229756688413996, + 27.07250534083106, + 1.8515270828242718, + -2.2349241050252573, + 0.0 + ], + [ + 1024.844077, + 12.089885986328124, + 0.2677083333333327, + 3.2290322580645157, + -3.242375366568915, + 24.27277196407557, + 27.025749606416305, + 1.8982828172390263, + -2.26297754567411, + 0.0 + ], + [ + 1024.864068, + 12.03334375, + 0.2677083333333327, + 3.2290322580645157, + -3.242375366568915, + 24.314852125048848, + 26.98273433075473, + 1.9543896985367315, + -2.272328692557061, + 0.0 + ], + [ + 1024.884068, + 12.014496337890625, + 0.2687499999999994, + 3.2290322580645157, + -3.242375366568915, + 24.355062056645536, + 26.93878394040486, + 2.0104965798344367, + -2.26297754567411, + 0.0 + ], + [ + 1024.904099, + 12.064756103515625, + 0.2687499999999994, + 3.2408602150537633, + -3.2542521994134894, + 24.395271988242225, + 26.8929633206784, + 2.0479011673662404, + -2.281679839440012, + 0.0 + ], + [ + 1024.924072, + 12.03334375, + 0.2687499999999994, + 3.2408602150537633, + -3.2408602150537633, + 24.43641703452721, + 26.842467127510467, + 2.057252314249191, + -2.291030986322963, + 0.0 + ], + [ + 1024.944064, + 12.083603515624999, + 0.26979166666666604, + 3.2408602150537633, + -3.2408602150537633, + 24.48036742487708, + 26.791970934342533, + 2.057252314249191, + -2.337786720737717, + 0.0 + ], + [ + 1024.964171, + 12.102450927734374, + 0.26979166666666604, + 3.2526881720430105, + -3.2526881720430105, + 24.524317815226947, + 26.740539626486303, + 2.066603461132142, + -2.421947042684275, + 0.0 + ], + [ + 1024.984058, + 12.027061279296875, + 0.2708333333333327, + 3.2526881720430105, + -3.2526881720430105, + 24.570138434953407, + 26.68817320394178, + 2.0853057548980436, + -2.506107364630833, + 0.0 + ], + [ + 1025.004311, + 12.13386328125, + 0.2708333333333327, + 3.276344086021505, + -3.276344086021505, + 24.61315371061498, + 26.635806781397253, + 2.1227103424298472, + -2.562214245928538, + 0.0 + ], + [ + 1025.024058, + 12.0584736328125, + 0.2708333333333327, + 3.276344086021505, + -3.276344086021505, + 24.658039215653144, + 26.58531058822932, + 2.160114929961651, + -2.5715653928114888, + 0.0 + ], + [ + 1025.044807, + 12.001931396484375, + 0.27187499999999937, + 3.276344086021505, + -3.276344086021505, + 24.70292472069131, + 26.53387928037309, + 2.197519517493454, + -2.5809165396944396, + 0.0 + ], + [ + 1025.064113, + 12.052191162109375, + 0.27187499999999937, + 3.288172043010752, + -3.288172043010752, + 24.70292472069131, + 26.53387928037309, + 2.197519517493454, + -2.5809165396944396, + 0.0 + ], + [ + 1025.084131, + 12.001931396484375, + 0.27187499999999937, + 3.288172043010752, + -3.2745845552297164, + 24.749680455106063, + 26.48057774314027, + 2.216221811259356, + -2.6089699803432924, + 0.0 + ], + [ + 1025.1041, + 12.0584736328125, + 0.27291666666666603, + 3.288172043010752, + -3.2745845552297164, + 24.851607956130227, + 26.367428865856564, + 2.272328692557061, + -2.69313030228985, + 0.0 + ], + [ + 1025.124106, + 12.039626220703125, + 0.27291666666666603, + 3.3, + -3.286363636363636, + 24.851607956130227, + 26.367428865856564, + 2.272328692557061, + -2.69313030228985, + 0.0 + ], + [ + 1025.144047, + 11.983083984375, + 0.2739583333333327, + 3.3, + -3.286363636363636, + 24.95353545715439, + 26.308516640493973, + 2.3938936020354222, + -2.777290624236408, + 0.0 + ], + [ + 1025.164103, + 12.02077880859375, + 0.2739583333333327, + 3.311827956989247, + -3.298142717497556, + 25.00403165032233, + 26.19349753383368, + 2.4593516302160783, + -2.861450946182966, + 0.0 + ], + [ + 1025.184063, + 12.039626220703125, + 0.2739583333333327, + 3.311827956989247, + -3.298142717497556, + 25.059203416931737, + 26.137390652535974, + 2.5154585115137835, + -2.880153239948868, + 0.0 + ], + [ + 1025.204124, + 11.97051904296875, + 0.27499999999999936, + 3.311827956989247, + -3.298142717497556, + 25.11624541291774, + 26.077543312485087, + 2.562214245928538, + -2.8988555337147695, + 0.0 + ], + [ + 1025.224104, + 12.039626220703125, + 0.27499999999999936, + 3.3236559139784942, + -3.309921798631476, + 25.171417179527147, + 26.01582574305761, + 2.6089699803432924, + -2.9175578274806706, + 0.0 + ], + [ + 1025.244035, + 12.083603515624999, + 0.276041666666666, + 3.3236559139784942, + -3.3236559139784942, + 25.22658894613656, + 25.952237944253547, + 2.6557257147580464, + -2.992367002544278, + 0.0 + ], + [ + 1025.264039, + 11.989366455078125, + 0.276041666666666, + 3.3354838709677415, + -3.3354838709677415, + 25.281760712745967, + 25.88865014544948, + 2.702481449172801, + -3.057825030724934, + 0.0 + ], + [ + 1025.284075, + 12.071038574218749, + 0.276041666666666, + 3.3354838709677415, + -3.3354838709677415, + 25.339737823420265, + 25.824127231957117, + 2.7398860367046045, + -3.132634205788541, + 0.0 + ], + [ + 1025.304088, + 11.99564892578125, + 0.2770833333333327, + 3.3354838709677415, + -3.3354838709677415, + 25.399585163471148, + 25.759604318464756, + 2.777290624236408, + -3.1793899402032952, + 0.0 + ], + [ + 1025.324045, + 12.027061279296875, + 0.2770833333333327, + 3.3473118279569887, + -3.3473118279569887, + 25.45475693008056, + 25.695081404972395, + 2.814695211768212, + -3.216794527735099, + 0.0 + ], + [ + 1025.344285, + 12.0584736328125, + 0.27812499999999934, + 3.3473118279569887, + -3.3473118279569887, + 25.51179892606656, + 25.62962337679174, + 2.824046358651162, + -3.216794527735099, + 0.0 + ], + [ + 1025.364111, + 12.001931396484375, + 0.27812499999999934, + 3.3591397849462363, + -3.3591397849462363, + 25.56884092205256, + 25.563230233922788, + 2.842748652417064, + -3.2448479683839517, + 0.0 + ], + [ + 1025.38416, + 12.0082138671875, + 0.27812499999999934, + 3.3591397849462363, + -3.3591397849462363, + 25.630558491480034, + 25.491226402924067, + 2.8520997993000146, + -3.329008290330509, + 0.0 + ], + [ + 1025.404467, + 12.115015869140624, + 0.279166666666666, + 3.3591397849462363, + -3.3591397849462363, + 25.694146290284102, + 25.42202791599023, + 2.889504386831818, + -3.375764024745264, + 0.0 + ], + [ + 1025.424129, + 12.027061279296875, + 0.279166666666666, + 3.3709677419354835, + -3.3709677419354835, + 25.694146290284102, + 25.42202791599023, + 2.889504386831818, + -3.375764024745264, + 0.0 + ], + [ + 1025.444063, + 12.096168457031249, + 0.279166666666666, + 3.3709677419354835, + -3.3709677419354835, + 25.816646314450757, + 25.35002408499151, + 2.964313561895425, + -3.459924346691821, + 0.0 + ], + [ + 1025.464103, + 12.083603515624999, + 0.28020833333333267, + 3.3709677419354835, + -3.3709677419354835, + 25.882104342631415, + 25.277085139304493, + 3.0204204431931303, + -3.5347335217554283, + 0.0 + ], + [ + 1025.484077, + 11.989366455078125, + 0.28020833333333267, + 3.3827956989247308, + -3.3827956989247308, + 25.946627256123776, + 25.204146193617476, + 3.076527324490836, + -3.6001915499360844, + 0.0 + ], + [ + 1025.504106, + 12.071038574218749, + 0.28124999999999933, + 3.3827956989247308, + -3.3827956989247308, + 26.01021505492784, + 25.056398072866852, + 3.1139319120226396, + -3.6562984312337896, + 0.0 + ], + [ + 1025.524137, + 12.03334375, + 0.28124999999999933, + 3.394623655913978, + -3.394623655913978, + 26.073802853731905, + 24.98439424186813, + 3.151336499554443, + -3.637596137467888, + 0.0 + ], + [ + 1025.544071, + 12.04590869140625, + 0.28124999999999933, + 3.394623655913978, + -3.394623655913978, + 26.14019599660086, + 24.903974378674754, + 3.1700387933203444, + -3.7311076062973965, + 0.0 + ], + [ + 1025.564078, + 12.102450927734374, + 0.282291666666666, + 3.394623655913978, + -3.380596285434995, + 26.2084593688464, + 24.82823008892285, + 3.198092233969197, + -3.7498099000632985, + 0.0 + ], + [ + 1025.584104, + 12.027061279296875, + 0.282291666666666, + 3.406451612903225, + -3.3923753665689147, + 26.27672274109194, + 24.753420913859244, + 3.2354968215010005, + -3.7591610469462493, + 0.0 + ], + [ + 1025.604118, + 12.039626220703125, + 0.28333333333333266, + 3.406451612903225, + -3.3923753665689147, + 26.34498611333748, + 24.676741509419045, + 3.272901409032804, + -3.7965656344780525, + 0.0 + ], + [ + 1025.624083, + 12.083603515624999, + 0.28333333333333266, + 3.4182795698924733, + -3.4041544477028354, + 26.415119714959612, + 24.59258118747249, + 3.3196571434475586, + -3.927481690839365, + 0.0 + ], + [ + 1025.644198, + 12.039626220703125, + 0.28333333333333266, + 3.4182795698924733, + -3.4041544477028354, + 26.488993775334926, + 24.511226209590816, + 3.375764024745264, + -3.927481690839365, + 0.0 + ], + [ + 1025.664052, + 12.108733398437499, + 0.2843749999999993, + 3.4182795698924733, + -3.4041544477028354, + 26.559127376957058, + 24.431741461085736, + 3.4318709060429686, + -3.964886278371168, + 0.0 + ], + [ + 1025.684058, + 12.121298339843749, + 0.2843749999999993, + 3.4301075268817205, + -3.415933528836755, + 26.632066322644075, + 24.353191827268947, + 3.4879777873406743, + -3.992939719020021, + 0.0 + ], + [ + 1025.704059, + 12.052191162109375, + 0.285416666666666, + 3.4301075268817205, + -3.415933528836755, + 26.70687549770768, + 24.269966620010685, + 3.5347335217554283, + -4.0677488940836275, + 0.0 + ], + [ + 1025.724101, + 12.102450927734374, + 0.285416666666666, + 3.441935483870968, + -3.4561583577712613, + 26.784490016836173, + 24.182065839310948, + 3.5814892561701828, + -4.114504628498382, + 0.0 + ], + [ + 1025.74436, + 12.014496337890625, + 0.285416666666666, + 3.441935483870968, + -3.4561583577712613, + 26.856493847834894, + 24.102581090805863, + 3.637596137467888, + -4.08645118784953, + 0.0 + ], + [ + 1025.764112, + 12.064756103515625, + 0.28645833333333265, + 3.441935483870968, + -3.4561583577712613, + 26.856493847834894, + 24.102581090805863, + 3.637596137467888, + -4.08645118784953, + 0.0 + ], + [ + 1025.784137, + 12.115015869140624, + 0.28645833333333265, + 3.4655913978494626, + -3.479912023460411, + 26.92943279352191, + 24.014680310106126, + 3.6656495781167404, + -4.142558069147235, + 0.0 + ], + [ + 1025.804109, + 12.064756103515625, + 0.28645833333333265, + 3.4655913978494626, + -3.479912023460411, + 27.006112197962107, + 23.925844414718092, + 3.693703018765593, + -4.264122978625596, + 0.0 + ], + [ + 1025.824066, + 12.064756103515625, + 0.2874999999999993, + 3.4655913978494626, + -3.479912023460411, + 27.1594710068425, + 23.839813863394944, + 3.7404587531803473, + -4.301527566157399, + 0.0 + ], + [ + 1025.844087, + 12.108733398437499, + 0.2874999999999993, + 3.47741935483871, + -3.4917888563049857, + 27.235215296594404, + 23.75845888551327, + 3.7498099000632985, + -4.226718391093793, + 0.0 + ], + [ + 1025.864044, + 12.052191162109375, + 0.288541666666666, + 3.47741935483871, + -3.4917888563049857, + 27.31750538916437, + 23.666817646060352, + 3.777863340712151, + -4.348283300572154, + 0.0 + ], + [ + 1025.884071, + 12.108733398437499, + 0.288541666666666, + 3.489247311827957, + -3.474828934506354, + 27.39605502298116, + 23.575176406607433, + 3.8246190751269054, + -4.432443622518712, + 0.0 + ], + [ + 1025.904081, + 12.108733398437499, + 0.288541666666666, + 3.489247311827957, + -3.474828934506354, + 27.474604656797947, + 23.49008096997258, + 3.8620236626587086, + -4.357634447455105, + 0.0 + ], + [ + 1025.924202, + 12.04590869140625, + 0.28958333333333264, + 3.489247311827957, + -3.474828934506354, + 27.55782986405621, + 23.396569501143073, + 3.908779397073463, + -4.432443622518712, + 0.0 + ], + [ + 1025.944099, + 12.089885986328124, + 0.28958333333333264, + 3.5010752688172047, + -3.4866080156402743, + 27.639184841937883, + 23.303058032313565, + 3.9368328377223154, + -4.554008531997073, + 0.0 + ], + [ + 1025.96409, + 12.039626220703125, + 0.2906249999999993, + 3.5010752688172047, + -3.4866080156402743, + 27.717734475754668, + 23.220767939743595, + 3.9835885721370703, + -4.469848210050515, + 0.0 + ], + [ + 1025.984124, + 12.039626220703125, + 0.2906249999999993, + 3.512903225806452, + -3.498387096774194, + 27.79815433894805, + 23.124451126849202, + 4.011642012785923, + -4.497901650699368, + 0.0 + ], + [ + 1026.004093, + 12.0584736328125, + 0.2906249999999993, + 3.512903225806452, + -3.498387096774194, + 27.88137954620631, + 23.027199199266512, + 4.0209931596688735, + -4.638168853943631, + 0.0 + ], + [ + 1026.024196, + 12.052191162109375, + 0.29166666666666596, + 3.512903225806452, + -3.498387096774194, + 27.960864294711392, + 22.94397399200825, + 4.030344306551824, + -4.52595509134822, + 0.0 + ], + [ + 1026.044104, + 11.989366455078125, + 0.29166666666666596, + 3.524731182795699, + -3.524731182795699, + 28.04689484603454, + 22.84485183504897, + 4.049046600317726, + -4.582061972645926, + 0.0 + ], + [ + 1026.064061, + 12.04590869140625, + 0.29166666666666596, + 3.524731182795699, + -3.524731182795699, + 28.133860512045985, + 22.747599907466284, + 4.0677488940836275, + -4.6942757352413365, + 0.0 + ], + [ + 1026.084071, + 11.989366455078125, + 0.2927083333333326, + 3.524731182795699, + -3.524731182795699, + 28.222696407434015, + 22.664374700208022, + 4.114504628498382, + -4.610115413294778, + 0.0 + ], + [ + 1026.104116, + 12.077321044921874, + 0.2927083333333326, + 3.5365591397849463, + -3.5365591397849463, + 28.306856729380574, + 22.569928116690217, + 4.170611509796087, + -4.572710825762974, + 0.0 + ], + [ + 1026.124095, + 12.0082138671875, + 0.2937499999999993, + 3.5365591397849463, + -3.5365591397849463, + 28.396627739456903, + 22.476416647860706, + 4.236069537976743, + -4.675573441475434, + 0.0 + ], + [ + 1026.14415, + 12.001931396484375, + 0.2937499999999993, + 3.5365591397849463, + -3.5483870967741935, + 28.48265829078005, + 22.385710523096083, + 4.282825272391498, + -4.591413119528877, + 0.0 + ], + [ + 1026.164083, + 12.052191162109375, + 0.2937499999999993, + 3.5483870967741935, + -3.5483870967741935, + 28.571494186168085, + 22.285653251448508, + 4.329581006806253, + -4.656871147709532, + 0.0 + ], + [ + 1026.184208, + 12.014496337890625, + 0.29479166666666595, + 3.5483870967741935, + -3.5483870967741935, + 28.658459852179526, + 22.192141782619, + 4.357634447455105, + -4.722329175890189, + 0.0 + ], + [ + 1026.204137, + 11.989366455078125, + 0.29479166666666595, + 3.560215053763441, + -3.5455034213098733, + 28.750101091632445, + 22.101435657854378, + 4.376336741221007, + -4.684924588358385, + 0.0 + ], + [ + 1026.224199, + 12.03334375, + 0.29479166666666595, + 3.560215053763441, + -3.5455034213098733, + 28.839872101708774, + 21.999508156830213, + 4.404390181869859, + -4.759733763421992, + 0.0 + ], + [ + 1026.244105, + 11.983083984375, + 0.2958333333333326, + 3.560215053763441, + -3.5455034213098733, + 28.931513341161693, + 21.904126458624113, + 4.432443622518712, + -4.815840644719697, + 0.0 + ], + [ + 1026.264109, + 11.964236572265625, + 0.2958333333333326, + 3.5720430107526884, + -3.557282502443793, + 29.023154580614612, + 21.809679875106312, + 4.469848210050515, + -4.759733763421992, + 0.0 + ], + [ + 1026.284122, + 12.04590869140625, + 0.2958333333333326, + 3.5720430107526884, + -3.557282502443793, + 29.114795820067528, + 21.709622603458737, + 4.497901650699368, + -4.8251917916026485, + 0.0 + ], + [ + 1026.30416, + 11.976801513671875, + 0.2968749999999993, + 3.5720430107526884, + -3.557282502443793, + 29.207372174208743, + 21.608630217122865, + 4.535306238231171, + -4.9187032604321566, + 0.0 + ], + [ + 1026.324236, + 12.0082138671875, + 0.2968749999999993, + 3.5838709677419356, + -3.569061583577713, + 29.30088364303825, + 21.512313404228472, + 4.563359678880024, + -4.881298672900353, + 0.0 + ], + [ + 1026.344065, + 11.976801513671875, + 0.2968749999999993, + 3.5838709677419356, + -3.569061583577713, + 29.39439511186776, + 21.4122561325809, + 4.591413119528877, + -4.9187032604321566, + 0.0 + ], + [ + 1026.364297, + 11.976801513671875, + 0.29791666666666594, + 3.5838709677419356, + -3.5838709677419356, + 29.486036351320678, + 21.208401130532568, + 4.610115413294778, + -4.974810141729861, + 0.0 + ], + [ + 1026.384196, + 12.039626220703125, + 0.29791666666666594, + 3.595698924731183, + -3.595698924731183, + 29.58141804952678, + 21.110214088261586, + 4.619466560177729, + -5.002863582378715, + 0.0 + ], + [ + 1026.404063, + 12.001931396484375, + 0.2989583333333326, + 3.595698924731183, + -3.595698924731183, + 29.677734862421172, + 21.009221701925718, + 4.638168853943631, + -5.030917023027567, + 0.0 + ], + [ + 1026.424106, + 11.99564892578125, + 0.2989583333333326, + 3.60752688172043, + -3.60752688172043, + 29.775921904692154, + 20.904488856836668, + 4.666222294592483, + -5.077672757442322, + 0.0 + ], + [ + 1026.444089, + 12.039626220703125, + 0.2989583333333326, + 3.60752688172043, + -3.60752688172043, + 29.87410894696314, + 20.798820897059322, + 4.703626882124286, + -5.124428491857076, + 0.0 + ], + [ + 1026.464068, + 11.983083984375, + 0.29999999999999927, + 3.60752688172043, + -3.60752688172043, + 29.97136087454583, + 20.697828510723454, + 4.750382616539041, + -5.152481932505929, + 0.0 + ], + [ + 1026.484064, + 11.989366455078125, + 0.29999999999999927, + 3.6193548387096777, + -3.6193548387096777, + 30.072353260881698, + 20.589355206881223, + 4.806489497836746, + -5.199237666920683, + 0.0 + ], + [ + 1026.504068, + 12.039626220703125, + 0.29999999999999927, + 3.6193548387096777, + -3.6193548387096777, + 30.172410532529273, + 20.48742770585706, + 4.862596379134452, + -5.217939960686585, + 0.0 + ], + [ + 1026.524098, + 11.99564892578125, + 0.30104166666666593, + 3.6193548387096777, + -3.6193548387096777, + 30.274338033553438, + 20.3836299754563, + 4.909352113549206, + -5.199237666920683, + 0.0 + ], + [ + 1026.544088, + 12.0584736328125, + 0.30104166666666593, + 3.631182795698925, + -3.631182795698925, + 30.375330419889305, + 20.2704810981726, + 4.956107847963961, + -5.292749135750192, + 0.0 + ], + [ + 1026.56404, + 12.03334375, + 0.30104166666666593, + 3.631182795698925, + -3.631182795698925, + 30.478193035601766, + 20.170423826525024, + 5.002863582378715, + -5.264695695101339, + 0.0 + ], + [ + 1026.584501, + 11.983083984375, + 0.3020833333333326, + 3.631182795698925, + -3.631182795698925, + 30.583860995379112, + 20.058210063929614, + 5.040268169910518, + -5.311451429516093, + 0.0 + ], + [ + 1026.604079, + 12.0584736328125, + 0.3020833333333326, + 3.6548387096774193, + -3.6548387096774193, + 30.583860995379112, + 20.058210063929614, + 5.040268169910518, + -5.311451429516093, + 0.0 + ], + [ + 1026.624112, + 12.014496337890625, + 0.30312499999999926, + 3.6548387096774193, + -3.6548387096774193, + 30.790521341492326, + 19.836587882803677, + 5.124428491857076, + -5.470420926526258, + 0.0 + ], + [ + 1026.644061, + 12.039626220703125, + 0.30312499999999926, + 3.6666666666666665, + -3.6666666666666665, + 30.89618930126967, + 19.721568776143382, + 5.152481932505929, + -5.489123220292161, + 0.0 + ], + [ + 1026.664071, + 12.077321044921874, + 0.30312499999999926, + 3.6666666666666665, + -3.6666666666666665, + 30.99905191698213, + 19.614030586989447, + 5.17118422627183, + -5.563932395355766, + 0.0 + ], + [ + 1026.684407, + 11.983083984375, + 0.3041666666666659, + 3.6666666666666665, + -3.6666666666666665, + 31.10191453269459, + 19.50275193908233, + 5.1898865200377315, + -5.554581248472816, + 0.0 + ], + [ + 1026.704111, + 12.001931396484375, + 0.3041666666666659, + 3.678494623655914, + -3.678494623655914, + 31.10191453269459, + 19.50275193908233, + 5.1898865200377315, + -5.554581248472816, + 0.0 + ], + [ + 1026.72429, + 12.027061279296875, + 0.3052083333333326, + 3.678494623655914, + -3.678494623655914, + 31.207582492471932, + 19.279259528579807, + 5.199237666920683, + -5.582634689121669, + 0.0 + ], + [ + 1026.744107, + 12.02077880859375, + 0.3052083333333326, + 3.6903225806451614, + -3.6903225806451614, + 31.314185566937574, + 19.279259528579807, + 5.199237666920683, + -5.582634689121669, + 0.0 + ], + [ + 1026.764071, + 12.071038574218749, + 0.3052083333333326, + 3.6903225806451614, + -3.6903225806451614, + 31.425464214844688, + 19.163305307231216, + 5.217939960686585, + -5.582634689121669, + 0.0 + ], + [ + 1026.784118, + 12.027061279296875, + 0.30624999999999925, + 3.6903225806451614, + -3.6903225806451614, + 31.641475707840854, + 18.94168312610528, + 5.311451429516093, + -5.60133698288757, + 0.0 + ], + [ + 1026.804073, + 12.02077880859375, + 0.30624999999999925, + 3.7021505376344086, + -3.7021505376344086, + 31.749949011683086, + 18.839755625081114, + 5.358207163930848, + -5.507825514058061, + 0.0 + ], + [ + 1026.824031, + 12.077321044921874, + 0.3072916666666659, + 3.7021505376344086, + -3.7021505376344086, + 31.854681856772135, + 18.721931174355934, + 5.395611751462651, + -5.573283542238717, + 0.0 + ], + [ + 1026.844116, + 12.02077880859375, + 0.3072916666666659, + 3.713978494623656, + -3.698631476050831, + 31.965025389990952, + 18.60504183831905, + 5.404962898345602, + -5.582634689121669, + 0.0 + ], + [ + 1026.864148, + 12.02077880859375, + 0.3072916666666659, + 3.713978494623656, + -3.698631476050831, + 32.07630403789807, + 18.48908761697046, + 5.404962898345602, + -5.694848451717079, + 0.0 + ], + [ + 1026.884089, + 12.083603515624999, + 0.30833333333333257, + 3.698631476050831, + -3.698631476050831, + 32.189452915181775, + 18.37032805155698, + 5.414314045228553, + -5.71355074548298, + 0.0 + ], + [ + 1026.904073, + 12.0082138671875, + 0.30833333333333257, + 3.710410557184751, + -3.710410557184751, + 32.30260179246548, + 18.25998451833816, + 5.442367485877405, + -5.797711067429539, + 0.0 + ], + [ + 1026.924109, + 12.027061279296875, + 0.30833333333333257, + 3.710410557184751, + -3.710410557184751, + 32.41201021099601, + 18.139354723548095, + 5.489123220292161, + -5.825764508078391, + 0.0 + ], + [ + 1026.944084, + 12.077321044921874, + 0.30937499999999923, + 3.710410557184751, + -3.710410557184751, + 32.52422397359142, + 18.0243356168878, + 5.535878954706915, + -5.80706221431249, + 0.0 + ], + [ + 1026.964085, + 12.02077880859375, + 0.30937499999999923, + 3.722189638318671, + -3.722189638318671, + 32.63363239212194, + 17.90838139553921, + 5.563932395355766, + -5.80706221431249, + 0.0 + ], + [ + 1026.984095, + 12.089885986328124, + 0.3104166666666659, + 3.722189638318671, + -3.722189638318671, + 32.74584615471735, + 17.784946256684258, + 5.563932395355766, + -5.844466801844293, + 0.0 + ], + [ + 1027.004066, + 12.014496337890625, + 0.3104166666666659, + 3.733968719452591, + -3.733968719452591, + 32.85618968793617, + 17.667121805959077, + 5.563932395355766, + -5.92862712379085, + 0.0 + ], + [ + 1027.02434, + 12.0082138671875, + 0.3104166666666659, + 3.733968719452591, + -3.733968719452591, + 32.967468335843286, + 17.54088132303924, + 5.5452301015898655, + -5.975382858205604, + 0.0 + ], + [ + 1027.044182, + 12.071038574218749, + 0.31145833333333256, + 3.733968719452591, + -3.733968719452591, + 32.967468335843286, + 17.54088132303924, + 5.5452301015898655, + -5.975382858205604, + 0.0 + ], + [ + 1027.06409, + 12.014496337890625, + 0.31145833333333256, + 3.7457478005865106, + -3.7457478005865106, + 33.08716301594506, + 17.421186642937467, + 5.554581248472816, + -5.966031711322655, + 0.0 + ], + [ + 1027.084112, + 11.983083984375, + 0.3124999999999992, + 3.7457478005865106, + -3.7457478005865106, + 33.31439588520077, + 17.298686618770812, + 5.6387415704193735, + -6.096947767683966, + 0.0 + ], + [ + 1027.104163, + 12.0584736328125, + 0.3124999999999992, + 3.7575268817204304, + -3.7575268817204304, + 33.42754476248447, + 17.180862168045632, + 5.676146157951178, + -6.050192033269211, + 0.0 + ], + [ + 1027.124026, + 11.99564892578125, + 0.3124999999999992, + 3.7575268817204304, + -3.7575268817204304, + 33.542563869144765, + 17.050881226372613, + 5.694848451717079, + -6.171756942747573, + 0.0 + ], + [ + 1027.144068, + 12.001931396484375, + 0.3135416666666659, + 3.7575268817204304, + -3.7575268817204304, + 33.65945320518165, + 16.799335375221236, + 5.71355074548298, + -6.283970705342984, + 0.0 + ], + [ + 1027.164093, + 12.02077880859375, + 0.3135416666666659, + 3.76930596285435, + -3.76930596285435, + 33.77727765590683, + 16.672159777613103, + 5.722901892365932, + -6.274619558460033, + 0.0 + ], + [ + 1027.184096, + 11.97051904296875, + 0.31458333333333255, + 3.76930596285435, + -3.76930596285435, + 33.8979074506969, + 16.546854409381563, + 5.750955333014785, + -6.321375292874787, + 0.0 + ], + [ + 1027.204078, + 12.0082138671875, + 0.31458333333333255, + 3.78108504398827, + -3.78108504398827, + 34.01573190142208, + 16.415003238331956, + 5.788359920546587, + -6.34942873352364, + 0.0 + ], + [ + 1027.224095, + 11.97051904296875, + 0.31458333333333255, + 3.78108504398827, + -3.78108504398827, + 34.138231925588734, + 16.285957411347233, + 5.853817948727244, + -6.368131027289542, + 0.0 + ], + [ + 1027.244128, + 11.9579541015625, + 0.3156249999999992, + 3.78108504398827, + -3.78108504398827, + 34.2597968350671, + 16.154106240297626, + 5.9099248300249485, + -6.4522913492360985, + 0.0 + ], + [ + 1027.264173, + 12.064756103515625, + 0.3156249999999992, + 3.7928641251221897, + -3.7928641251221897, + 34.38136174454546, + 16.02225506924802, + 5.966031711322655, + -6.4896959367679035, + 0.0 + ], + [ + 1027.28411, + 11.951671630859375, + 0.3166666666666659, + 3.7928641251221897, + -3.7928641251221897, + 34.50199153933553, + 15.889468783510116, + 6.003436298854457, + -6.573856258714461, + 0.0 + ], + [ + 1027.304068, + 11.94538916015625, + 0.3166666666666659, + 3.8046432062561095, + -3.8046432062561095, + 34.620751104749, + 15.759487841837098, + 6.02213859262036, + -6.555153964948559, + 0.0 + ], + [ + 1027.324112, + 11.989366455078125, + 0.3166666666666659, + 3.8046432062561095, + -3.8046432062561095, + 34.74418624360395, + 15.621090867969427, + 6.040840886386261, + -6.658016580661018, + 0.0 + ], + [ + 1027.344119, + 11.9579541015625, + 0.31770833333333254, + 3.8046432062561095, + -3.8046432062561095, + 34.86107557964084, + 15.496720614426179, + 6.040840886386261, + -6.573856258714461, + 0.0 + ], + [ + 1027.364109, + 12.0082138671875, + 0.31770833333333254, + 3.8282013685239495, + -3.8282013685239495, + 34.983575603807495, + 15.358323640558506, + 6.031489739503311, + -6.639314286895117, + 0.0 + ], + [ + 1027.384651, + 12.039626220703125, + 0.31770833333333254, + 3.8282013685239495, + -3.8282013685239495, + 35.10046493984438, + 15.23769384576844, + 6.012787445737409, + -6.517749377416755, + 0.0 + ], + [ + 1027.404053, + 11.989366455078125, + 0.3187499999999992, + 3.8282013685239495, + -3.8282013685239495, + 35.10046493984438, + 15.23769384576844, + 6.012787445737409, + -6.517749377416755, + 0.0 + ], + [ + 1027.424057, + 11.989366455078125, + 0.3187499999999992, + 3.8399804496578693, + -3.8399804496578693, + 35.34827033224258, + 15.091815954394407, + 6.012787445737409, + -6.695421168192822, + 0.0 + ], + [ + 1027.444073, + 11.976801513671875, + 0.31979166666666586, + 3.8399804496578693, + -3.8399804496578693, + 35.472640585785825, + 14.961835012721389, + 6.031489739503311, + -6.592558552480362, + 0.0 + ], + [ + 1027.464069, + 11.989366455078125, + 0.31979166666666586, + 3.851759530791789, + -3.851759530791789, + 35.59794595401737, + 14.826243382918602, + 6.078245473918065, + -6.704772315075774, + 0.0 + ], + [ + 1027.484073, + 12.014496337890625, + 0.31979166666666586, + 3.851759530791789, + -3.851759530791789, + 35.7241864369372, + 14.69158686780411, + 6.125001208332819, + -6.667367727543969, + 0.0 + ], + [ + 1027.504072, + 11.94538916015625, + 0.3208333333333325, + 3.851759530791789, + -3.851759530791789, + 35.85042691985704, + 14.557865467377912, + 6.1811080896305235, + -6.798283783905282, + 0.0 + ], + [ + 1027.524066, + 11.989366455078125, + 0.3208333333333325, + 3.863538611925709, + -3.863538611925709, + 35.97479717340028, + 14.419468493510239, + 6.218512677162328, + -6.714123461958723, + 0.0 + ], + [ + 1027.544051, + 12.04590869140625, + 0.3218749999999992, + 3.863538611925709, + -3.863538611925709, + 36.09916742694353, + 14.15109057796955, + 6.24656611781118, + -6.751528049490528, + 0.0 + ], + [ + 1027.564107, + 11.9076943359375, + 0.3218749999999992, + 3.8753176930596287, + -3.8753176930596287, + 36.22353768048678, + 14.020174521608237, + 6.255917264694131, + -6.714123461958723, + 0.0 + ], + [ + 1027.584055, + 12.03334375, + 0.3218749999999992, + 3.8753176930596287, + -3.8753176930596287, + 36.34884304871832, + 13.874296630234204, + 6.255917264694131, + -6.779581490139379, + 0.0 + ], + [ + 1027.60412, + 12.001931396484375, + 0.32291666666666585, + 3.8753176930596287, + -3.8753176930596287, + 36.475083531638155, + 13.74338057387289, + 6.24656611781118, + -6.751528049490528, + 0.0 + ], + [ + 1027.624155, + 11.97051904296875, + 0.32291666666666585, + 3.8870967741935485, + -3.8870967741935485, + 36.60225912924629, + 13.595632453122267, + 6.255917264694131, + -6.845039518320036, + 0.0 + ], + [ + 1027.644171, + 12.02077880859375, + 0.32291666666666585, + 3.8870967741935485, + -3.8870967741935485, + 36.72662938278954, + 13.462846167384365, + 6.265268411577082, + -6.882444105851839, + 0.0 + ], + [ + 1027.664064, + 11.983083984375, + 0.3239583333333325, + 3.8870967741935485, + -3.8870967741935485, + 36.851934751021076, + 13.319773620075217, + 6.265268411577082, + -6.994657868447249, + 0.0 + ], + [ + 1027.684172, + 11.9579541015625, + 0.3239583333333325, + 3.8988758553274683, + -3.8988758553274683, + 36.976305004564324, + 13.17857130214266, + 6.274619558460033, + -7.022711309096103, + 0.0 + ], + [ + 1027.704068, + 12.014496337890625, + 0.3249999999999992, + 3.8988758553274683, + -3.8988758553274683, + 37.10348060217245, + 13.036433869521806, + 6.274619558460033, + -7.078818190393807, + 0.0 + ], + [ + 1027.724335, + 11.93282421875, + 0.3249999999999992, + 3.910654936461388, + -3.910654936461388, + 37.229721085092294, + 12.884945290018003, + 6.274619558460033, + -7.1629785123403655, + 0.0 + ], + [ + 1027.744125, + 12.0082138671875, + 0.3249999999999992, + 3.910654936461388, + -3.910654936461388, + 37.229721085092294, + 12.884945290018003, + 6.274619558460033, + -7.1629785123403655, + 0.0 + ], + [ + 1027.76423, + 12.014496337890625, + 0.32604166666666584, + 3.910654936461388, + -3.910654936461388, + 37.35783179738872, + 12.748418545526919, + 6.283970705342984, + -7.134925071691512, + 0.0 + ], + [ + 1027.784081, + 11.989366455078125, + 0.32604166666666584, + 3.922434017595308, + -3.922434017595308, + 37.485942509685145, + 12.59786508071141, + 6.302672999108886, + -7.21908539363807, + 0.0 + ], + [ + 1027.804062, + 12.071038574218749, + 0.3270833333333325, + 3.922434017595308, + -3.906158357771261, + 37.617793680734756, + 12.457597877467148, + 6.330726439757738, + -7.200383099872169, + 0.0 + ], + [ + 1027.824149, + 12.027061279296875, + 0.3270833333333325, + 3.9342130987292276, + -3.9178885630498534, + 37.748709737096064, + 12.306109297963342, + 6.377482174172492, + -7.293894568701678, + 0.0 + ], + [ + 1027.844061, + 11.989366455078125, + 0.3270833333333325, + 3.9342130987292276, + -3.9178885630498534, + 37.8758853347042, + 12.158361177212718, + 6.4055356148213445, + -7.2564899811698735, + 0.0 + ], + [ + 1027.864143, + 12.052191162109375, + 0.32812499999999917, + 3.9342130987292276, + -3.9178885630498534, + 38.14800370899807, + 11.85351378882852, + 6.499047083650854, + -7.443512918828892, + 0.0 + ], + [ + 1027.88407, + 11.989366455078125, + 0.32812499999999917, + 3.945992179863148, + -3.929618768328446, + 38.28640068286574, + 11.708571012142782, + 6.56450511183151, + -7.499619800126597, + 0.0 + ], + [ + 1027.904076, + 12.014496337890625, + 0.32916666666666583, + 3.945992179863148, + -3.929618768328446, + 38.41918696860364, + 11.555212203262387, + 6.629963140012166, + -7.518322093892499, + 0.0 + ], + [ + 1027.92426, + 12.03334375, + 0.32916666666666583, + 3.9577712609970677, + -3.941348973607038, + 38.55384348371813, + 11.403723623758584, + 6.686070021309871, + -7.462215212594793, + 0.0 + ], + [ + 1027.94413, + 11.99564892578125, + 0.32916666666666583, + 3.9577712609970677, + -3.941348973607038, + 38.68662976945604, + 11.25223504425478, + 6.723474608841674, + -7.565077828307253, + 0.0 + ], + [ + 1027.964114, + 11.976801513671875, + 0.3302083333333325, + 3.9577712609970677, + -3.9577712609970677, + 38.82035116988224, + 11.107292267569042, + 6.742176902607576, + -7.462215212594793, + 0.0 + ], + [ + 1027.984139, + 12.04590869140625, + 0.3302083333333325, + 3.9695503421309875, + -3.9695503421309875, + 38.82035116988224, + 11.107292267569042, + 6.742176902607576, + -7.462215212594793, + 0.0 + ], + [ + 1028.004138, + 11.99564892578125, + 0.33124999999999916, + 3.9695503421309875, + -3.9695503421309875, + 38.95500768499673, + 10.960479261506713, + 6.732825755724625, + -7.4809175063606945, + 0.0 + ], + [ + 1028.024102, + 12.04590869140625, + 0.33124999999999916, + 3.9813294232649072, + -3.9813294232649072, + 39.09527488824099, + 10.809925796691203, + 6.723474608841674, + -7.443512918828892, + 0.0 + ], + [ + 1028.04406, + 12.02077880859375, + 0.33124999999999916, + 3.9813294232649072, + -3.9813294232649072, + 39.22993140335549, + 10.659372331875694, + 6.742176902607576, + -7.518322093892499, + 0.0 + ], + [ + 1028.064289, + 12.0082138671875, + 0.3322916666666658, + 3.9813294232649072, + -3.9813294232649072, + 39.5123360392206, + 10.360135631621267, + 6.816986077671183, + -7.471566359477744, + 0.0 + ], + [ + 1028.084106, + 12.001931396484375, + 0.3322916666666658, + 3.993108504398827, + -3.993108504398827, + 39.654473471841456, + 10.360135631621267, + 6.863741812085937, + -7.471566359477744, + 0.0 + ], + [ + 1028.104029, + 11.951671630859375, + 0.3322916666666658, + 3.993108504398827, + -3.993108504398827, + 39.79193533102083, + 10.200231019922807, + 6.919848693383642, + -7.602482415839056, + 0.0 + ], + [ + 1028.124028, + 11.9579541015625, + 0.3333333333333325, + 3.993108504398827, + -3.993108504398827, + 39.9303323048885, + 9.891643172785429, + 6.966604427798398, + -7.686642737785614, + 0.0 + ], + [ + 1028.144026, + 12.014496337890625, + 0.3333333333333325, + 4.004887585532747, + -4.004887585532747, + 40.06872927875617, + 9.743895052034805, + 6.9853067215642985, + -7.574428975190203, + 0.0 + ], + [ + 1028.16407, + 11.964236572265625, + 0.33437499999999915, + 4.004887585532747, + -4.004887585532747, + 40.21086671137703, + 9.58305532564805, + 6.9853067215642985, + -7.780154206615123, + 0.0 + ], + [ + 1028.184138, + 11.983083984375, + 0.33437499999999915, + 4.028445747800586, + -4.028445747800586, + 40.3492636852447, + 9.424085828637885, + 6.975955574681349, + -7.75210076596627, + 0.0 + ], + [ + 1028.204107, + 11.964236572265625, + 0.33437499999999915, + 4.028445747800586, + -4.028445747800586, + 40.49233623255385, + 9.26698656100431, + 6.966604427798398, + -7.892367969210533, + 0.0 + ], + [ + 1028.224459, + 11.99564892578125, + 0.3354166666666658, + 4.028445747800586, + -4.028445747800586, + 40.630733206421525, + 9.108952178682442, + 6.966604427798398, + -7.826909941029877, + 0.0 + ], + [ + 1028.244067, + 11.989366455078125, + 0.3354166666666658, + 4.040224828934506, + -4.040224828934506, + 40.630733206421525, + 9.108952178682442, + 6.966604427798398, + -7.826909941029877, + 0.0 + ], + [ + 1028.264279, + 12.03334375, + 0.33645833333333247, + 4.040224828934506, + -4.040224828934506, + 40.919683645104705, + 8.791948299350407, + 7.032062455979053, + -7.911070262976435, + 0.0 + ], + [ + 1028.284074, + 11.92025927734375, + 0.33645833333333247, + 4.052003910068426, + -4.052003910068426, + 41.06275619241385, + 8.791948299350407, + 7.078818190393807, + -7.911070262976435, + 0.0 + ], + [ + 1028.304143, + 11.976801513671875, + 0.33645833333333247, + 4.052003910068426, + -4.052003910068426, + 41.208634083787885, + 8.631108572963651, + 7.116222777925611, + -7.86431452856168, + 0.0 + ], + [ + 1028.324092, + 11.93282421875, + 0.33749999999999913, + 4.052003910068426, + -4.052003910068426, + 41.35357686047362, + 8.475879534706667, + 7.153627365457415, + -7.920421409859387, + 0.0 + ], + [ + 1028.344145, + 11.92025927734375, + 0.33749999999999913, + 4.063782991202346, + -4.063782991202346, + 41.500389866535954, + 8.316910037696502, + 7.191031952989217, + -7.911070262976435, + 0.0 + ], + [ + 1028.364079, + 11.976801513671875, + 0.33749999999999913, + 4.063782991202346, + -4.063782991202346, + 41.64813798728658, + 8.157940540686338, + 7.228436540521022, + -7.929772556742336, + 0.0 + ], + [ + 1028.384033, + 11.939106689453125, + 0.3385416666666658, + 4.063782991202346, + -4.063782991202346, + 41.80243191085527, + 7.997100814299583, + 7.275192274935776, + -7.939123703625287, + 0.0 + ], + [ + 1028.404129, + 11.901411865234374, + 0.3385416666666658, + 4.0755620723362656, + -4.0755620723362656, + 41.95298537567078, + 7.839066431977713, + 7.340650303116432, + -7.985879438040042, + 0.0 + ], + [ + 1028.424077, + 11.94538916015625, + 0.33958333333333246, + 4.0755620723362656, + -4.0755620723362656, + 42.10914952861606, + 7.672616017461188, + 7.406108331297087, + -8.023284025571845, + 0.0 + ], + [ + 1028.444091, + 11.926541748046875, + 0.33958333333333246, + 4.087341153470185, + -4.053421309872922, + 42.25596253467838, + 7.521127437957383, + 7.4809175063606945, + -7.967177144274141, + 0.0 + ], + [ + 1028.464116, + 11.976801513671875, + 0.33958333333333246, + 4.087341153470185, + -4.053421309872922, + 42.41212668762366, + 7.354677023440858, + 7.5276732407754485, + -8.023284025571845, + 0.0 + ], + [ + 1028.484058, + 11.976801513671875, + 0.3406249999999991, + 4.087341153470185, + -4.053421309872922, + 42.55893969368599, + 7.199447985183873, + 7.565077828307253, + -7.985879438040042, + 0.0 + ], + [ + 1028.50407, + 11.888846923828124, + 0.3406249999999991, + 4.099120234604105, + -4.065102639296187, + 42.712298502566384, + 7.036738029420529, + 7.574428975190203, + -8.013932878688895, + 0.0 + ], + [ + 1028.524087, + 11.989366455078125, + 0.3416666666666658, + 4.099120234604105, + -4.065102639296187, + 42.86659242613508, + 6.874963188345479, + 7.583780122073155, + -7.967177144274141, + 0.0 + ], + [ + 1028.544057, + 11.939106689453125, + 0.3416666666666658, + 4.110899315738025, + -4.076783968719452, + 43.020886349703765, + 6.715058576647019, + 7.593131268956105, + -8.060688613103649, + 0.0 + ], + [ + 1028.564086, + 11.93282421875, + 0.3416666666666658, + 4.110899315738025, + -4.076783968719452, + 43.17892073202564, + 6.548608162130493, + 7.611833562722007, + -8.0700397599866, + 0.0 + ], + [ + 1028.584052, + 11.989366455078125, + 0.34270833333333245, + 4.110899315738025, + -4.076783968719452, + 43.33508488497092, + 6.385898206367148, + 7.658589297136761, + -8.126146641284304, + 0.0 + ], + [ + 1028.604185, + 11.9076943359375, + 0.34270833333333245, + 4.122678396871946, + -4.105571847507331, + 43.49779484073426, + 6.223188250603803, + 7.714696178434467, + -8.144848935050206, + 0.0 + ], + [ + 1028.624145, + 11.93282421875, + 0.34270833333333245, + 4.122678396871946, + -4.105571847507331, + 43.65395899367954, + 6.053932492022392, + 7.780154206615123, + -8.219658110113814, + 0.0 + ], + [ + 1028.644085, + 11.976801513671875, + 0.3437499999999991, + 4.105571847507331, + -4.105571847507331, + 43.813863605377996, + 5.894962995012228, + 7.845612234795779, + -8.20095581634791, + 0.0 + ], + [ + 1028.664145, + 11.913976806640624, + 0.3437499999999991, + 4.117302052785924, + -4.117302052785924, + 43.96909264363499, + 5.727577465807407, + 7.883016822327582, + -8.219658110113814, + 0.0 + ], + [ + 1028.684093, + 11.99564892578125, + 0.3447916666666658, + 4.117302052785924, + -4.117302052785924, + 44.12525679658026, + 5.561127051290882, + 7.892367969210533, + -8.247711550762666, + 0.0 + ], + [ + 1028.704077, + 11.989366455078125, + 0.3447916666666658, + 4.129032258064516, + -4.129032258064516, + 44.282356064213836, + 5.394676636774356, + 7.892367969210533, + -8.28511613829447, + 0.0 + ], + [ + 1028.724152, + 11.94538916015625, + 0.3447916666666658, + 4.129032258064516, + -4.129032258064516, + 44.44039044653571, + 5.231031566322716, + 7.883016822327582, + -8.219658110113814, + 0.0 + ], + [ + 1028.744057, + 11.99564892578125, + 0.34583333333333244, + 4.129032258064516, + -4.129032258064516, + 44.603100402299056, + 5.065516266494486, + 7.873665675444631, + -8.29446728517742, + 0.0 + ], + [ + 1028.764069, + 11.92025927734375, + 0.34583333333333244, + 4.140762463343108, + -4.140762463343108, + 44.76113478462092, + 4.894390278536485, + 7.873665675444631, + -8.350574166475125, + 0.0 + ], + [ + 1028.784087, + 11.93282421875, + 0.3468749999999991, + 4.140762463343108, + -4.140762463343108, + 44.921974511007676, + 4.728874978708254, + 7.901719116093484, + -8.313169578943322, + 0.0 + ], + [ + 1028.804081, + 12.014496337890625, + 0.3468749999999991, + 4.152492668621701, + -4.152492668621701, + 45.080944008017845, + 4.556813876061958, + 7.929772556742336, + -8.369276460241027, + 0.0 + ], + [ + 1028.824135, + 11.94538916015625, + 0.3468749999999991, + 4.152492668621701, + -4.152492668621701, + 45.24458907846948, + 4.388493232168843, + 7.957825997391189, + -8.434734488421684, + 0.0 + ], + [ + 1028.844122, + 11.93282421875, + 0.34791666666666576, + 4.152492668621701, + -4.152492668621701, + 45.408234148921125, + 4.216432129522547, + 7.985879438040042, + -8.490841369719389, + 0.0 + ], + [ + 1028.864101, + 11.989366455078125, + 0.34791666666666576, + 4.164222873900293, + -4.164222873900293, + 45.57187921937276, + 4.0462412562528405, + 8.023284025571845, + -8.462787929070537, + 0.0 + ], + [ + 1028.88407, + 11.94538916015625, + 0.34791666666666576, + 4.164222873900293, + -4.164222873900293, + 45.7364594045127, + 3.879790841736315, + 8.0700397599866, + -8.50019251660234, + 0.0 + ], + [ + 1028.904085, + 11.989366455078125, + 0.3489583333333324, + 4.164222873900293, + -4.164222873900293, + 45.90571516309411, + 3.712405312531495, + 8.126146641284304, + -8.453436782187586, + 0.0 + ], + [ + 1028.924091, + 11.99564892578125, + 0.3489583333333324, + 4.164222873900293, + -4.158553274682307, + 46.074035806987226, + 3.5394090951969037, + 8.191604669464962, + -8.50019251660234, + 0.0 + ], + [ + 1028.94406, + 11.976801513671875, + 0.3499999999999991, + 4.1759530791788855, + -4.158553274682307, + 46.24235645088034, + 3.378569368810149, + 8.266413844528568, + -8.38797875400693, + 0.0 + ], + [ + 1028.964083, + 12.027061279296875, + 0.3499999999999991, + 4.19941348973607, + -4.1819159335288365, + 46.40974198008516, + 3.2065082661638526, + 8.322520725826273, + -8.41603219465578, + 0.0 + ], + [ + 1028.984079, + 11.964236572265625, + 0.3499999999999991, + 4.19941348973607, + -4.1819159335288365, + 46.57899773866657, + 3.033512048829262, + 8.359925313358076, + -8.453436782187586, + 0.0 + ], + [ + 1029.004161, + 11.939106689453125, + 0.35104166666666575, + 4.19941348973607, + -4.1819159335288365, + 46.75012372662457, + 2.866126519624441, + 8.39732990088988, + -8.462787929070537, + 0.0 + ], + [ + 1029.024026, + 12.03334375, + 0.35104166666666575, + 4.211143695014663, + -4.1935972629521014, + 46.92405505864746, + 2.69126007291326, + 8.425383341538733, + -8.472139075953486, + 0.0 + ], + [ + 1029.044171, + 11.951671630859375, + 0.3520833333333324, + 4.211143695014663, + -4.1935972629521014, + 47.09611616129376, + 2.517328740890374, + 8.453436782187586, + -8.61240627919775, + 0.0 + ], + [ + 1029.064071, + 11.9579541015625, + 0.3520833333333324, + 4.222873900293255, + -4.205278592375366, + 47.270982608004935, + 2.344332523555783, + 8.50019251660234, + -8.61240627919775, + 0.0 + ], + [ + 1029.084086, + 12.014496337890625, + 0.3520833333333324, + 4.222873900293255, + -4.222873900293255, + 47.442108595962935, + 2.1657256180914213, + 8.556299397900045, + -8.677864307378405, + 0.0 + ], + [ + 1029.10406, + 11.939106689453125, + 0.3531249999999991, + 4.222873900293255, + -4.222873900293255, + 47.616039927985824, + 1.9936645154451251, + 8.61240627919775, + -8.72462004179316, + 0.0 + ], + [ + 1029.124186, + 12.02077880859375, + 0.3531249999999991, + 4.234604105571847, + -4.234604105571847, + 47.789971260008706, + 1.8169278393573538, + 8.649810866729554, + -8.743322335559062, + 0.0 + ], + [ + 1029.144042, + 11.926541748046875, + 0.3531249999999991, + 4.234604105571847, + -4.234604105571847, + 47.962032362655, + 1.6401911632695823, + 8.659162013612505, + -8.780726923090866, + 0.0 + ], + [ + 1029.164234, + 11.94538916015625, + 0.35416666666666574, + 4.234604105571847, + -4.234604105571847, + 48.135028579989594, + 1.4671949459349913, + 8.659162013612505, + -8.780726923090866, + 0.0 + ], + [ + 1029.184189, + 11.99564892578125, + 0.35416666666666574, + 4.24633431085044, + -4.24633431085044, + 48.30708968263589, + 1.282042237652564, + 8.649810866729554, + -8.743322335559062, + 0.0 + ], + [ + 1029.204104, + 11.93282421875, + 0.3552083333333324, + 4.24633431085044, + -4.24633431085044, + 48.47821567059389, + 1.1081109056296778, + 8.631108572963651, + -8.855536098154474, + 0.0 + ], + [ + 1029.224251, + 11.951671630859375, + 0.3552083333333324, + 4.258064516129032, + -4.258064516129032, + 48.64934165855189, + 0.9295040001653163, + 8.6217574260807, + -8.874238391920374, + 0.0 + ], + [ + 1029.244094, + 11.989366455078125, + 0.3552083333333324, + 4.258064516129032, + -4.258064516129032, + 48.824208105263075, + 0.742481062506299, + 8.61240627919775, + -8.958398713866933, + 0.0 + ], + [ + 1029.264028, + 11.9076943359375, + 0.35624999999999907, + 4.258064516129032, + -4.258064516129032, + 49.000944781350846, + 0.5591985836004619, + 8.6217574260807, + -9.070612476462342, + 0.0 + ], + [ + 1029.284033, + 11.92025927734375, + 0.35624999999999907, + 4.269794721407624, + -4.269794721407624, + 49.180486801503505, + 0.37591610469462494, + 8.649810866729554, + -9.1547727984089, + 0.0 + ], + [ + 1029.304269, + 12.014496337890625, + 0.35729166666666573, + 4.269794721407624, + -4.269794721407624, + 49.35815859227957, + 0.01496183501272139, + 8.696566601144308, + -9.145421651525949, + 0.0 + ], + [ + 1029.324199, + 11.9579541015625, + 0.35729166666666573, + 4.281524926686217, + -4.281524926686217, + 49.546116644626885, + 0.01496183501272139, + 8.771375776207915, + -9.145421651525949, + 0.0 + ], + [ + 1029.344084, + 11.983083984375, + 0.35729166666666573, + 4.281524926686217, + -4.281524926686217, + 49.729399123532716, + -0.16832064389311563, + 8.864887245037425, + -9.117368210877096, + 0.0 + ], + [ + 1029.36408, + 11.901411865234374, + 0.3583333333333324, + 4.281524926686217, + -4.281524926686217, + 49.90987625837367, + -0.35160312279895267, + 8.967749860749883, + -9.108017063994145, + 0.0 + ], + [ + 1029.384127, + 11.93282421875, + 0.3583333333333324, + 4.293255131964809, + -4.293255131964809, + 50.09222362259121, + -0.5292749135750192, + 9.04255903581349, + -9.05191018269644, + 0.0 + ], + [ + 1029.404077, + 11.9579541015625, + 0.3583333333333324, + 4.293255131964809, + -4.293255131964809, + 50.27270075743216, + -0.7078818190393807, + 9.089314770228244, + -8.995803301398736, + 0.0 + ], + [ + 1029.424284, + 11.97051904296875, + 0.35937499999999906, + 4.293255131964809, + -4.293255131964809, + 50.454113006961414, + -1.0781872356042352, + 9.108017063994145, + -9.108017063994145, + 0.0 + ], + [ + 1029.444078, + 11.951671630859375, + 0.35937499999999906, + 4.3049853372434015, + -4.3049853372434015, + 50.454113006961414, + -1.0781872356042352, + 9.108017063994145, + -9.108017063994145, + 0.0 + ], + [ + 1029.464122, + 11.976801513671875, + 0.3604166666666657, + 4.3049853372434015, + -4.3049853372434015, + 50.640200829932134, + -1.2614697145100722, + 9.108017063994145, + -9.108017063994145, + 0.0 + ], + [ + 1029.4842, + 11.926541748046875, + 0.3604166666666657, + 4.316715542521994, + -4.316715542521994, + 50.822548194149675, + -1.45223311092227, + 9.108017063994145, + -9.220230826589557, + 0.0 + ], + [ + 1029.504038, + 11.89512939453125, + 0.3604166666666657, + 4.316715542521994, + -4.316715542521994, + 51.01237647587358, + -1.6392560485812873, + 9.117368210877096, + -9.313742295419065, + 0.0 + ], + [ + 1029.52406, + 11.951671630859375, + 0.3614583333333324, + 4.316715542521994, + -4.316715542521994, + 51.20407498697407, + -1.8262789862403046, + 9.164123945291852, + -9.332444589184966, + 0.0 + ], + [ + 1029.544122, + 11.901411865234374, + 0.3614583333333324, + 4.328445747800586, + -4.328445747800586, + 51.3892276952565, + -2.0179774973407976, + 9.229581973472508, + -9.397902617365624, + 0.0 + ], + [ + 1029.564122, + 11.94538916015625, + 0.36249999999999905, + 4.328445747800586, + -4.2923753665689155, + 51.57251017416233, + -2.20593554968811, + 9.295040001653163, + -9.425956058014474, + 0.0 + ], + [ + 1029.584072, + 11.888846923828124, + 0.36249999999999905, + 4.340175953079179, + -4.304007820136853, + 51.753922423691584, + -2.3910882579705373, + 9.313742295419065, + -9.397902617365624, + 0.0 + ], + [ + 1029.604046, + 11.851152099609374, + 0.36249999999999905, + 4.340175953079179, + -4.304007820136853, + 52.122357610879845, + -2.58278676907103, + 9.276337707887262, + -9.435307204897427, + 0.0 + ], + [ + 1029.624183, + 11.939106689453125, + 0.3635416666666657, + 4.340175953079179, + -4.304007820136853, + 52.307510319162276, + -2.778225738924703, + 9.229581973472508, + -9.538169820609886, + 0.0 + ], + [ + 1029.644067, + 11.89512939453125, + 0.3635416666666657, + 4.351906158357771, + -4.3156402737047905, + 52.48985768337982, + -2.969924250025196, + 9.201528532823655, + -9.510116379961033, + 0.0 + ], + [ + 1029.664053, + 11.882564453125, + 0.3635416666666657, + 4.351906158357771, + -4.3156402737047905, + 52.674075276973944, + -3.1625578758139836, + 9.182826239057754, + -9.575574408141689, + 0.0 + ], + [ + 1029.684076, + 11.92025927734375, + 0.36458333333333237, + 4.351906158357771, + -4.3156402737047905, + 52.859227985256375, + -3.3636075337974276, + 9.192177385940704, + -9.715841611385953, + 0.0 + ], + [ + 1029.704059, + 11.913976806640624, + 0.36458333333333237, + 4.363636363636363, + -4.327272727272727, + 53.04999138166857, + -3.5581113889628053, + 9.210879679706604, + -9.762597345800707, + 0.0 + ], + [ + 1029.724146, + 11.913976806640624, + 0.36562499999999903, + 4.363636363636363, + -4.327272727272727, + 53.23888454870418, + -3.7516801294398885, + 9.24828426723841, + -9.725192758268904, + 0.0 + ], + [ + 1029.744093, + 11.93282421875, + 0.36562499999999903, + 4.387096774193548, + -4.350537634408602, + 53.43245328918126, + -3.9461839846052666, + 9.295040001653163, + -9.762597345800707, + 0.0 + ], + [ + 1029.764085, + 11.913976806640624, + 0.36562499999999903, + 4.387096774193548, + -4.350537634408602, + 53.62508691497005, + -4.14349318383553, + 9.36984917671677, + -9.818704227098412, + 0.0 + ], + [ + 1029.784106, + 11.951671630859375, + 0.3666666666666657, + 4.387096774193548, + -4.350537634408602, + 53.816785426070545, + -4.3370619243126125, + 9.444658351780378, + -9.734543905151854, + 0.0 + ], + [ + 1029.80408, + 11.89512939453125, + 0.3666666666666657, + 4.39882697947214, + -4.36217008797654, + 54.00661370779444, + -4.530630664789696, + 9.510116379961033, + -9.706490464503002, + 0.0 + ], + [ + 1029.824372, + 11.888846923828124, + 0.36770833333333236, + 4.39882697947214, + -4.36217008797654, + 54.19270153076517, + -4.922443719185337, + 9.538169820609886, + -9.762597345800707, + 0.0 + ], + [ + 1029.844225, + 11.939106689453125, + 0.36770833333333236, + 4.410557184750733, + -4.373802541544477, + 54.19270153076517, + -4.922443719185337, + 9.538169820609886, + -9.762597345800707, + 0.0 + ], + [ + 1029.864069, + 11.93282421875, + 0.36770833333333236, + 4.410557184750733, + -4.373802541544477, + 54.38627027124225, + -5.116947574350715, + 9.547520967492837, + -9.725192758268904, + 0.0 + ], + [ + 1029.884123, + 11.913976806640624, + 0.368749999999999, + 4.410557184750733, + -4.373802541544477, + 54.57703366765445, + -5.323607920463929, + 9.538169820609886, + -9.865459961513167, + 0.0 + ], + [ + 1029.904187, + 11.94538916015625, + 0.368749999999999, + 4.422287390029325, + -4.385434995112415, + 54.77901844032619, + -5.521852234382488, + 9.547520967492837, + -9.912215695927921, + 0.0 + ], + [ + 1029.924095, + 11.913976806640624, + 0.368749999999999, + 4.422287390029325, + -4.385434995112415, + 54.97726275424475, + -5.724772121742522, + 9.58492555502464, + -9.996376017874478, + 0.0 + ], + [ + 1029.94411, + 11.964236572265625, + 0.3697916666666657, + 4.422287390029325, + -4.385434995112415, + 55.1764421828516, + -5.92488666503767, + 9.659734730088248, + -10.024429458523333, + 0.0 + ], + [ + 1029.964065, + 11.9579541015625, + 0.3697916666666657, + 4.4340175953079175, + -4.397067448680352, + 55.370010923328685, + -6.129676781774294, + 9.753246198917756, + -10.11794092735284, + 0.0 + ], + [ + 1029.984111, + 11.939106689453125, + 0.3697916666666657, + 4.4340175953079175, + -4.397067448680352, + 55.565449893182354, + -6.343818045393869, + 9.809353080215462, + -10.11794092735284, + 0.0 + ], + [ + 1030.004084, + 12.0082138671875, + 0.37083333333333235, + 4.4340175953079175, + -4.397067448680352, + 55.75714840428285, + -6.533646327117772, + 9.828055373981362, + -10.136643221118742, + 0.0 + ], + [ + 1030.024086, + 11.913976806640624, + 0.37083333333333235, + 4.44574780058651, + -4.40869990224829, + 55.951652259448224, + -6.740306673230986, + 9.809353080215462, + -10.155345514884644, + 0.0 + ], + [ + 1030.044126, + 11.901411865234374, + 0.371874999999999, + 4.44574780058651, + -4.40869990224829, + 56.1461561146136, + -6.951642592785675, + 9.781299639566608, + -10.267559277480053, + 0.0 + ], + [ + 1030.06404, + 11.9579541015625, + 0.371874999999999, + 4.457478005865102, + -4.420332355816227, + 56.3378546257141, + -7.1611082829637756, + 9.734543905151854, + -10.323666158777758, + 0.0 + ], + [ + 1030.084198, + 11.926541748046875, + 0.371874999999999, + 4.457478005865102, + -4.420332355816227, + 56.728732565421446, + -7.58284500738486, + 9.669085876971199, + -10.482635655787924, + 0.0 + ], + [ + 1030.104064, + 11.939106689453125, + 0.3729166666666657, + 4.457478005865102, + -4.420332355816227, + 56.93165245278148, + -7.792310697562959, + 9.678437023854148, + -10.520040243319727, + 0.0 + ], + [ + 1030.124112, + 11.964236572265625, + 0.3729166666666657, + 4.469208211143695, + -4.431964809384165, + 57.133637225453214, + -8.00364661711765, + 9.734543905151854, + -10.520040243319727, + 0.0 + ], + [ + 1030.144026, + 11.926541748046875, + 0.37395833333333234, + 4.469208211143695, + -4.431964809384165, + 57.33655711281325, + -8.212177192607452, + 9.818704227098412, + -10.520040243319727, + 0.0 + ], + [ + 1030.164071, + 11.989366455078125, + 0.37395833333333234, + 4.480938416422287, + -4.4435972629521014, + 57.54134722954988, + -8.421642882785552, + 9.912215695927921, + -10.491986802670874, + 0.0 + ], + [ + 1030.18407, + 11.989366455078125, + 0.37395833333333234, + 4.480938416422287, + -4.4435972629521014, + 57.74707246097479, + -8.630173458275356, + 10.024429458523333, + -10.473284508904971, + 0.0 + ], + [ + 1030.204082, + 11.92025927734375, + 0.374999999999999, + 4.480938416422287, + -4.462267839687194, + 57.95092746302312, + -8.837768919076867, + 10.10858978046989, + -10.45458221513907, + 0.0 + ], + [ + 1030.224033, + 11.99564892578125, + 0.374999999999999, + 4.492668621700879, + -4.473949169110459, + 58.155717579759745, + -9.054715526761326, + 10.164696661767593, + -10.510689096436776, + 0.0 + ], + [ + 1030.244049, + 11.89512939453125, + 0.374999999999999, + 4.492668621700879, + -4.473949169110459, + 58.36331304056126, + -9.26698656100431, + 10.202101249299398, + -10.538742537085628, + 0.0 + ], + [ + 1030.26403, + 11.882564453125, + 0.37604166666666566, + 4.492668621700879, + -4.473949169110459, + 58.56997338667447, + -9.481127824623886, + 10.23015468994825, + -10.594849418383333, + 0.0 + ], + [ + 1030.284069, + 11.964236572265625, + 0.37604166666666566, + 4.504398826979472, + -4.485630498533724, + 58.77943907685257, + -9.69900954699664, + 10.267559277480053, + -10.688360887212841, + 0.0 + ], + [ + 1030.304067, + 11.913976806640624, + 0.3770833333333323, + 4.504398826979472, + -4.485630498533724, + 58.98890476703067, + -9.91408592530451, + 10.304963865011858, + -10.781872356042353, + 0.0 + ], + [ + 1030.324068, + 11.876281982421874, + 0.3770833333333323, + 4.516129032258064, + -4.497311827956989, + 59.19837045720877, + -10.126356959547495, + 10.351719599426612, + -10.716414327861695, + 0.0 + ], + [ + 1030.344169, + 11.964236572265625, + 0.3770833333333323, + 4.516129032258064, + -4.497311827956989, + 59.40970637676346, + -10.347044025985136, + 10.398475333841366, + -10.800574649808253, + 0.0 + ], + [ + 1030.364108, + 11.89512939453125, + 0.378124999999999, + 4.516129032258064, + -4.459677419354839, + 59.61823695225326, + -10.564925748357892, + 10.43587992137317, + -10.828628090457107, + 0.0 + ], + [ + 1030.384076, + 11.913976806640624, + 0.378124999999999, + 4.527859237536656, + -4.471260997067449, + 59.826767527743066, + -10.787483044172122, + 10.463933362022022, + -10.87538382487186, + 0.0 + ], + [ + 1030.40409, + 11.964236572265625, + 0.37916666666666565, + 4.527859237536656, + -4.471260997067449, + 60.03436298854458, + -11.012845684051237, + 10.473284508904971, + -10.87538382487186, + 0.0 + ], + [ + 1030.424069, + 11.844869628906249, + 0.37916666666666565, + 4.539589442815249, + -4.482844574780059, + 60.24476379341097, + -11.012845684051237, + 10.473284508904971, + -10.87538382487186, + 0.0 + ], + [ + 1030.444077, + 11.926541748046875, + 0.37916666666666565, + 4.539589442815249, + -4.482844574780059, + 60.45609971296566, + -11.218570915476157, + 10.463933362022022, + -10.912788412403664, + 0.0 + ], + [ + 1030.46415, + 11.901411865234374, + 0.3802083333333323, + 4.539589442815249, + -4.482844574780059, + 60.67117609127353, + -11.439257981913798, + 10.463933362022022, + -10.922139559286615, + 0.0 + ], + [ + 1030.484127, + 11.9076943359375, + 0.3802083333333323, + 4.551319648093841, + -4.494428152492669, + 60.89279827239947, + -11.647788557403603, + 10.491986802670874, + -10.837979237340056, + 0.0 + ], + [ + 1030.504175, + 11.92025927734375, + 0.381249999999999, + 4.551319648093841, + -4.494428152492669, + 61.11067999477222, + -11.863800050399767, + 10.566795977734483, + -10.7725212091594, + 0.0 + ], + [ + 1030.524115, + 11.876281982421874, + 0.381249999999999, + 4.574780058651026, + -4.517595307917889, + 61.33323729058645, + -12.081681772772523, + 10.679009740329892, + -10.809925796691203, + 0.0 + ], + [ + 1030.544094, + 11.876281982421874, + 0.381249999999999, + 4.574780058651026, + -4.517595307917889, + 61.54831366889432, + -12.294887921703802, + 10.791223502925302, + -10.7725212091594, + 0.0 + ], + [ + 1030.564103, + 11.913976806640624, + 0.38229166666666564, + 4.574780058651026, + -4.517595307917889, + 61.77087096470855, + -12.512769644076558, + 10.894086118637762, + -10.744467768510548, + 0.0 + ], + [ + 1030.584093, + 11.838587158203124, + 0.38229166666666564, + 4.586510263929618, + -4.529178885630499, + 61.98781757239301, + -12.726910907696132, + 10.959544146818418, + -10.781872356042353, + 0.0 + ], + [ + 1030.604103, + 11.89512939453125, + 0.38229166666666564, + 4.586510263929618, + -4.529178885630499, + 62.20663440945406, + -12.947597974133773, + 10.978246440584321, + -10.847330384223008, + 0.0 + ], + [ + 1030.624212, + 11.913976806640624, + 0.3833333333333323, + 4.586510263929618, + -4.529178885630499, + 62.42545124651511, + -13.164544581818232, + 10.959544146818418, + -10.819276943574154, + 0.0 + ], + [ + 1030.644075, + 11.86999951171875, + 0.3833333333333323, + 4.598240469208211, + -4.540762463343109, + 62.64520319826446, + -13.379620960126102, + 10.950192999935467, + -10.866032677988908, + 0.0 + ], + [ + 1030.664054, + 11.888846923828124, + 0.38437499999999897, + 4.598240469208211, + -4.540762463343109, + 62.864955150013806, + -13.602178255940334, + 10.940841853052516, + -10.88473497175481, + 0.0 + ], + [ + 1030.684089, + 11.844869628906249, + 0.38437499999999897, + 4.609970674486803, + -4.571554252199413, + 63.08470710176315, + -13.822865322377973, + 10.950192999935467, + -10.959544146818418, + 0.0 + ], + [ + 1030.704118, + 11.86999951171875, + 0.38437499999999897, + 4.609970674486803, + -4.571554252199413, + 63.30071859475932, + -14.045422618192205, + 10.968895293701369, + -10.98759758746727, + 0.0 + ], + [ + 1030.724069, + 11.876281982421874, + 0.38541666666666563, + 4.590762463343109, + -4.571554252199413, + 63.519535431820366, + -14.26891502869473, + 10.968895293701369, + -11.043704468764977, + 0.0 + ], + [ + 1030.744021, + 11.876281982421874, + 0.38541666666666563, + 4.602443792766373, + -4.583186705767351, + 63.74022249825801, + -14.494277668573845, + 10.950192999935467, + -11.127864790711532, + 0.0 + ], + [ + 1030.76414, + 11.813457275390624, + 0.3864583333333323, + 4.602443792766373, + -4.583186705767351, + 63.95155841781269, + -14.719640308452963, + 10.912788412403664, + -11.183971672009239, + 0.0 + ], + [ + 1030.784226, + 11.926541748046875, + 0.3864583333333323, + 4.6141251221896376, + -4.594819159335288, + 64.17037525487375, + -14.949678521773553, + 10.88473497175481, + -11.2868342877217, + 0.0 + ], + [ + 1030.804108, + 11.838587158203124, + 0.3864583333333323, + 4.6141251221896376, + -4.594819159335288, + 64.39573789475286, + -15.18065184978244, + 10.866032677988908, + -11.240078553306944, + 0.0 + ], + [ + 1030.824107, + 11.89512939453125, + 0.38749999999999896, + 4.6141251221896376, + -4.594819159335288, + 64.62203564932027, + -15.404144260284966, + 10.894086118637762, + -11.352292315902355, + 0.0 + ], + [ + 1030.844061, + 11.888846923828124, + 0.38749999999999896, + 4.6258064516129025, + -4.6258064516129025, + 64.84833340388768, + -15.631377129540672, + 10.959544146818418, + -11.380345756551208, + 0.0 + ], + [ + 1030.864049, + 11.876281982421874, + 0.3885416666666656, + 4.6258064516129025, + -4.6258064516129025, + 65.0755662731434, + -15.859545113484673, + 11.053055615647926, + -11.389696903434158, + 0.0 + ], + [ + 1030.884067, + 11.926541748046875, + 0.3885416666666656, + 4.637487781036167, + -4.637487781036167, + 65.29999379833421, + -16.093323785558443, + 11.146567084477434, + -11.41775034408301, + 0.0 + ], + [ + 1030.904223, + 11.876281982421874, + 0.3885416666666656, + 4.637487781036167, + -4.637487781036167, + 65.51881063539525, + -16.331778031073693, + 11.221376259541042, + -11.604773281742027, + 0.0 + ], + [ + 1030.924088, + 11.826022216796874, + 0.3895833333333323, + 4.637487781036167, + -4.637487781036167, + 65.73762747245631, + -16.56275135908258, + 11.240078553306944, + -11.595422134859078, + 0.0 + ], + [ + 1030.944092, + 11.939106689453125, + 0.3895833333333323, + 4.649169110459432, + -4.649169110459432, + 65.95831453889394, + -16.799335375221236, + 11.20267396577514, + -11.660880163039733, + 0.0 + ], + [ + 1030.964098, + 11.882564453125, + 0.3895833333333323, + 4.649169110459432, + -4.649169110459432, + 66.1780664906433, + -17.030308703230123, + 11.127864790711532, + -11.707635897454487, + 0.0 + ], + [ + 1030.98419, + 11.851152099609374, + 0.39062499999999895, + 4.649169110459432, + -4.649169110459432, + 66.39407798363946, + -17.275308751563436, + 11.053055615647926, + -11.82920080693285, + 0.0 + ], + [ + 1031.00407, + 11.976801513671875, + 0.39062499999999895, + 4.660850439882697, + -4.6218475073313785, + 66.61850550883028, + -17.512827882390386, + 11.006299881233172, + -11.810498513166948, + 0.0 + ], + [ + 1031.024094, + 11.89512939453125, + 0.39062499999999895, + 4.660850439882697, + -4.6218475073313785, + 66.8429330340211, + -17.769984421671534, + 10.99694873435022, + -12.062979479006621, + 0.0 + ], + [ + 1031.044072, + 11.94538916015625, + 0.3916666666666656, + 4.660850439882697, + -4.6218475073313785, + 67.06549032983533, + -18.01311424062826, + 11.025002174999074, + -12.137788654070228, + 0.0 + ], + [ + 1031.064048, + 11.901411865234374, + 0.3916666666666656, + 4.672531769305962, + -4.633431085043989, + 67.28430716689638, + -18.26185474771475, + 11.062406762530877, + -12.324811591729246, + 0.0 + ], + [ + 1031.084153, + 11.888846923828124, + 0.39270833333333227, + 4.672531769305962, + -4.633431085043989, + 67.50499423333403, + -18.516205942931016, + 11.081109056296778, + -12.399620766792852, + 0.0 + ], + [ + 1031.104162, + 11.9076943359375, + 0.39270833333333227, + 4.684213098729227, + -4.645014662756599, + 67.72381107039507, + -18.76868690877069, + 11.081109056296778, + -12.549239116920067, + 0.0 + ], + [ + 1031.124072, + 11.9076943359375, + 0.39270833333333227, + 4.684213098729227, + -4.645014662756599, + 67.9463683662093, + -19.021167874610363, + 11.07175790941383, + -12.511834529388262, + 0.0 + ], + [ + 1031.144101, + 11.901411865234374, + 0.39374999999999893, + 4.684213098729227, + -4.645014662756599, + 68.16892566202354, + -19.27832441389151, + 11.053055615647926, + -12.633399438866624, + 0.0 + ], + [ + 1031.164095, + 11.94538916015625, + 0.39374999999999893, + 4.695894428152492, + -4.67624633431085, + 68.39802876065583, + -19.530805379731184, + 11.053055615647926, + -12.689506320164327, + 0.0 + ], + [ + 1031.184043, + 11.86999951171875, + 0.3947916666666656, + 4.695894428152492, + -4.67624633431085, + 68.62806697397643, + -19.778610772129383, + 11.090460203179731, + -12.614697145100722, + 0.0 + ], + [ + 1031.204151, + 11.888846923828124, + 0.3947916666666656, + 4.707575757575757, + -4.6878787878787875, + 68.86278076073849, + -20.032961967345646, + 11.165269378243337, + -12.661452879515476, + 0.0 + ], + [ + 1031.224096, + 11.951671630859375, + 0.3947916666666656, + 4.707575757575757, + -4.6878787878787875, + 69.09468920343568, + -20.288248277250204, + 11.277483140838747, + -12.661452879515476, + 0.0 + ], + [ + 1031.24411, + 11.89512939453125, + 0.39583333333333226, + 4.707575757575757, + -4.6878787878787875, + 69.33314344895092, + -20.547275045907945, + 11.408399197200058, + -12.70820861393023, + 0.0 + ], + [ + 1031.264067, + 11.93282421875, + 0.39583333333333226, + 4.719257086999022, + -4.699511241446725, + 69.56224654758321, + -20.811912502695453, + 11.52996410667842, + -12.811071229642689, + 0.0 + ], + [ + 1031.284136, + 11.888846923828124, + 0.3968749999999989, + 4.719257086999022, + -4.699511241446725, + 69.79976567841017, + -21.070939271353193, + 11.61412442862498, + -12.932636139121051, + 0.0 + ], + [ + 1031.304116, + 11.882564453125, + 0.3968749999999989, + 4.742619745845552, + -4.7227761485826, + 70.03354435048394, + -21.319679778439685, + 11.670231309922682, + -12.867178110940396, + 0.0 + ], + [ + 1031.324175, + 11.93282421875, + 0.3968749999999989, + 4.742619745845552, + -4.7227761485826, + 70.26638790786942, + -21.59086303804526, + 11.688933603688586, + -13.044849901716463, + 0.0 + ], + [ + 1031.344116, + 11.876281982421874, + 0.3979166666666656, + 4.742619745845552, + -4.7227761485826, + 70.50671238276125, + -21.849889806703, + 11.707635897454487, + -13.02614760795056, + 0.0 + ], + [ + 1031.364073, + 11.882564453125, + 0.3979166666666656, + 4.754301075268817, + -4.734408602150538, + 70.74236128421161, + -22.115462378178805, + 11.726338191220389, + -13.03549875483351, + 0.0 + ], + [ + 1031.384169, + 11.926541748046875, + 0.3979166666666656, + 4.754301075268817, + -4.734408602150538, + 70.97988041503856, + -22.376359376213134, + 11.763742778752192, + -13.063552195482364, + 0.0 + ], + [ + 1031.404152, + 11.876281982421874, + 0.39895833333333225, + 4.754301075268817, + -4.734408602150538, + 71.21739954586552, + -22.648477750507002, + 11.810498513166948, + -13.278628573790234, + 0.0 + ], + [ + 1031.424145, + 11.888846923828124, + 0.39895833333333225, + 4.765982404692082, + -4.746041055718475, + 71.45398356200418, + -22.90937474854133, + 11.838551953815799, + -13.185117104960725, + 0.0 + ], + [ + 1031.444074, + 11.913976806640624, + 0.3999999999999989, + 4.765982404692082, + -4.746041055718475, + 71.68869734876624, + -23.42368782710363, + 11.847903100698751, + -13.072903342365315, + 0.0 + ], + [ + 1031.46405, + 11.876281982421874, + 0.3999999999999989, + 4.777663734115347, + -4.757673509286413, + 71.68869734876624, + -23.42368782710363, + 11.847903100698751, + -13.072903342365315, + 0.0 + ], + [ + 1031.484076, + 11.9076943359375, + 0.3999999999999989, + 4.777663734115347, + -4.7376832844574785, + 71.9262164795932, + -23.68458482513796, + 11.847903100698751, + -13.082254489248264, + 0.0 + ], + [ + 1031.50414, + 11.876281982421874, + 0.4010416666666656, + 4.777663734115347, + -4.7376832844574785, + 72.1721516426148, + -23.94735205254888, + 11.847903100698751, + -12.988743020418756, + 0.0 + ], + [ + 1031.524214, + 11.901411865234374, + 0.4010416666666656, + 4.789345063538612, + -4.749266862170089, + 72.41902192032471, + -24.211054394648095, + 11.885307688230553, + -12.998094167301709, + 0.0 + ], + [ + 1031.544101, + 11.93282421875, + 0.40208333333333224, + 4.789345063538612, + -4.749266862170089, + 72.67337311554097, + -24.472886507370717, + 11.969468010177112, + -13.03549875483351, + 0.0 + ], + [ + 1031.564057, + 11.826022216796874, + 0.40208333333333224, + 4.801026392961877, + -4.760850439882698, + 72.92585408138065, + -24.73845907884652, + 12.100384066538423, + -13.157063664311872, + 0.0 + ], + [ + 1031.58403, + 11.832304687499999, + 0.40208333333333224, + 4.801026392961877, + -4.760850439882698, + 73.1811403912852, + -24.99935607688085, + 12.268704710431539, + -13.147712517428921, + 0.0 + ], + [ + 1031.604064, + 11.876281982421874, + 0.4031249999999989, + 4.801026392961877, + -4.760850439882698, + 73.43081601306, + -25.271474451174722, + 12.427674207441704, + -13.222521692492528, + 0.0 + ], + [ + 1031.624409, + 11.86999951171875, + 0.4031249999999989, + 4.8127077223851416, + -4.772434017595308, + 73.94045351818082, + -25.784852415048725, + 12.605345998217771, + -13.12901022366302, + 0.0 + ], + [ + 1031.644114, + 11.813457275390624, + 0.40416666666666556, + 4.8127077223851416, + -4.792570869990224, + 73.94045351818082, + -25.784852415048725, + 12.605345998217771, + -13.12901022366302, + 0.0 + ], + [ + 1031.664094, + 11.89512939453125, + 0.40416666666666556, + 4.8243890518084065, + -4.804203323558162, + 74.19761005746196, + -26.05229521590112, + 12.633399438866624, + -13.119659076780067, + 0.0 + ], + [ + 1031.684073, + 11.788327392578125, + 0.40416666666666556, + 4.8243890518084065, + -4.804203323558162, + 74.45476659674311, + -26.31693267268863, + 12.661452879515476, + -13.185117104960725, + 0.0 + ], + [ + 1031.704147, + 11.851152099609374, + 0.4052083333333322, + 4.8243890518084065, + -4.804203323558162, + 74.71379336540085, + -26.580635014787845, + 12.69885746704728, + -13.110307929897118, + 0.0 + ], + [ + 1031.724069, + 11.788327392578125, + 0.4052083333333322, + 4.8360703812316705, + -4.815835777126099, + 74.96814456061712, + -26.84620758626365, + 12.745613201462033, + -13.194468251843677, + 0.0 + ], + [ + 1031.74411, + 11.800892333984375, + 0.4052083333333322, + 4.8360703812316705, + -4.815835777126099, + 75.22062552645679, + -27.106169469609682, + 12.792368935876787, + -13.203819398726626, + 0.0 + ], + [ + 1031.764178, + 11.89512939453125, + 0.4062499999999989, + 4.8360703812316705, + -4.815835777126099, + 75.47217137760816, + -27.366131352955716, + 12.811071229642689, + -13.13836137054597, + 0.0 + ], + [ + 1031.784156, + 11.8071748046875, + 0.4062499999999989, + 4.8477517106549355, + -4.827468230694037, + 75.72465234344784, + -27.619547433483685, + 12.792368935876787, + -13.016796461067608, + 0.0 + ], + [ + 1031.804096, + 11.819739746093749, + 0.4062499999999989, + 4.8477517106549355, + -4.807184750733138, + 75.98648445617046, + -27.878574202141426, + 12.754964348344984, + -12.970040726652854, + 0.0 + ], + [ + 1031.824107, + 11.838587158203124, + 0.40729166666666555, + 4.8477517106549355, + -4.807184750733138, + 76.25018679826968, + -28.137600970799163, + 12.745613201462033, + -12.91393384535515, + 0.0 + ], + [ + 1031.84408, + 11.79460986328125, + 0.40729166666666555, + 4.839100684261974, + -4.818768328445748, + 76.51575936974548, + -28.40036819821008, + 12.792368935876787, + -12.932636139121051, + 0.0 + ], + [ + 1031.864076, + 11.89512939453125, + 0.4083333333333322, + 4.839100684261974, + -4.818768328445748, + 76.78133194122128, + -28.66126519624441, + 12.885880404706295, + -12.970040726652854, + 0.0 + ], + [ + 1031.884095, + 11.888846923828124, + 0.4083333333333322, + 4.850733137829913, + -4.830351906158358, + 77.0469045126971, + -28.9296431117851, + 13.007445314184658, + -13.110307929897118, + 0.0 + ], + [ + 1031.904319, + 11.86999951171875, + 0.4093749999999989, + 4.850733137829913, + -4.830351906158358, + 77.58366034377848, + -29.466398942866483, + 13.222521692492528, + -13.297330867556134, + 0.0 + ], + [ + 1031.92441, + 11.93282421875, + 0.4093749999999989, + 4.86236559139785, + -4.8419354838709685, + 77.85671383276063, + -29.735711973095466, + 13.287979720673185, + -13.36278889573679, + 0.0 + ], + [ + 1031.944085, + 11.844869628906249, + 0.4093749999999989, + 4.86236559139785, + -4.8419354838709685, + 77.85671383276063, + -29.735711973095466, + 13.287979720673185, + -13.36278889573679, + 0.0 + ] + ], + "slow-backward": [ + [ + 1075.984116, + 12.53594140625, + 0.0, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.004121, + 12.529658935546875, + 0.0, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.02405, + 12.49824658203125, + 0.0, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.044192, + 12.542223876953125, + -0.0010416666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.064273, + 12.485681640625, + -0.0010416666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.084082, + 12.485681640625, + -0.0010416666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.104062, + 12.542223876953125, + -0.0020833333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.124056, + 12.49824658203125, + -0.0020833333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.144064, + 12.485681640625, + -0.0020833333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.164053, + 12.529658935546875, + -0.003125, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.184094, + 12.485681640625, + -0.003125, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.204052, + 12.53594140625, + -0.004166666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.224106, + 12.542223876953125, + -0.004166666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.244193, + 12.491964111328125, + -0.004166666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.264111, + 12.52337646484375, + -0.005208333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.284085, + 12.479399169921875, + -0.005208333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.304051, + 12.479399169921875, + -0.0062499999999999995, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.324058, + 12.529658935546875, + -0.0062499999999999995, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.344069, + 12.485681640625, + -0.0062499999999999995, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.364125, + 12.491964111328125, + -0.007291666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.384077, + 12.542223876953125, + -0.007291666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.404068, + 12.485681640625, + -0.008333333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.424112, + 12.542223876953125, + -0.008333333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.444097, + 12.53594140625, + -0.008333333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.464294, + 12.491964111328125, + -0.009375, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.484058, + 12.53594140625, + -0.009375, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.504203, + 12.485681640625, + -0.010416666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.524079, + 12.49824658203125, + -0.010416666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.54409, + 12.542223876953125, + -0.010416666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.564093, + 12.491964111328125, + -0.011458333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.584565, + 12.491964111328125, + -0.011458333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.60411, + 12.529658935546875, + -0.011458333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.624056, + 12.479399169921875, + -0.012499999999999999, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.64409, + 12.53594140625, + -0.012499999999999999, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.664082, + 12.485681640625, + -0.013541666666666665, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.684098, + 12.479399169921875, + -0.013541666666666665, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.704052, + 12.53594140625, + -0.013541666666666665, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.724103, + 12.485681640625, + -0.014583333333333332, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.74407, + 12.485681640625, + -0.014583333333333332, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.764036, + 12.53594140625, + -0.015624999999999998, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.784051, + 12.485681640625, + -0.015624999999999998, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.804375, + 12.491964111328125, + -0.015624999999999998, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.824069, + 12.52337646484375, + -0.016666666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.844071, + 12.491964111328125, + -0.016666666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.864091, + 12.529658935546875, + -0.017708333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.884071, + 12.491964111328125, + -0.017708333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.904109, + 12.491964111328125, + -0.017708333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.924088, + 12.53594140625, + -0.01875, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.944134, + 12.491964111328125, + -0.01875, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.964096, + 12.479399169921875, + -0.019791666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1076.984067, + 12.52337646484375, + -0.019791666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.00411, + 12.479399169921875, + -0.019791666666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.024097, + 12.485681640625, + -0.020833333333333332, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.04409, + 12.529658935546875, + -0.020833333333333332, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.064099, + 12.479399169921875, + -0.021875, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.084209, + 12.529658935546875, + -0.021875, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.104109, + 12.485681640625, + -0.021875, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.124111, + 12.479399169921875, + -0.022916666666666665, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.144116, + 12.542223876953125, + -0.022916666666666665, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.164103, + 12.49824658203125, + -0.022916666666666665, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.184078, + 12.485681640625, + -0.02395833333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.204091, + 12.542223876953125, + -0.02395833333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.224099, + 12.491964111328125, + -0.024999999999999998, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.244107, + 12.491964111328125, + -0.024999999999999998, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.264101, + 12.54850634765625, + -0.024999999999999998, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.284026, + 12.49824658203125, + -0.026041666666666664, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.304019, + 12.529658935546875, + -0.026041666666666664, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.324106, + 12.485681640625, + -0.02708333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.344069, + 12.491964111328125, + -0.02708333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.364079, + 12.53594140625, + -0.02708333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.384019, + 12.479399169921875, + -0.028124999999999997, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.404056, + 12.491964111328125, + -0.028124999999999997, + 0.0, + 0.0, + 105.49122310125705, + -57.6498205333921, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.424024, + 12.542223876953125, + -0.028124999999999997, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1077.444132, + 12.479399169921875, + -0.029166666666666664, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1077.464086, + 12.479399169921875, + -0.029166666666666664, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1077.48416, + 12.529658935546875, + -0.03020833333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1077.504123, + 12.491964111328125, + -0.03020833333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1077.524073, + 12.529658935546875, + -0.03020833333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.544171, + 12.485681640625, + -0.031249999999999997, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.564051, + 12.485681640625, + -0.031249999999999997, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.584112, + 12.542223876953125, + -0.03229166666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.604129, + 12.491964111328125, + -0.03229166666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.624118, + 12.485681640625, + -0.03229166666666666, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.644102, + 12.529658935546875, + -0.03333333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.66407, + 12.485681640625, + -0.03333333333333333, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.684208, + 12.53594140625, + -0.034375, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.704058, + 12.529658935546875, + -0.034375, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.72411, + 12.479399169921875, + -0.034375, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.744105, + 12.542223876953125, + -0.03541666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.764147, + 12.479399169921875, + -0.03541666666666667, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.784092, + 12.491964111328125, + -0.03645833333333334, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.804059, + 12.517093994140625, + -0.03645833333333334, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.824057, + 12.485681640625, + -0.03645833333333334, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.844068, + 12.479399169921875, + -0.03750000000000001, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.864103, + 12.542223876953125, + -0.03750000000000001, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.884092, + 12.491964111328125, + -0.03854166666666668, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.904108, + 12.53594140625, + -0.03854166666666668, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.924084, + 12.53594140625, + -0.03854166666666668, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.944105, + 12.485681640625, + -0.03958333333333335, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.964108, + 12.529658935546875, + -0.03958333333333335, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1077.984082, + 12.485681640625, + -0.03958333333333335, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.004216, + 12.479399169921875, + -0.04062500000000002, + 0.0, + 0.0, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.02416, + 12.54850634765625, + -0.04062500000000002, + -0.5049853372434018, + 0.5069892473118279, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.04413, + 12.479399169921875, + -0.04166666666666669, + -0.5049853372434018, + 0.5069892473118279, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.064092, + 12.491964111328125, + -0.04166666666666669, + -0.5173020527859237, + 0.5193548387096774, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.084141, + 12.54850634765625, + -0.04166666666666669, + -0.5152492668621701, + 0.5193548387096774, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.104116, + 12.479399169921875, + -0.04270833333333336, + -0.5152492668621701, + 0.5193548387096774, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.12413, + 12.529658935546875, + -0.04270833333333336, + -0.5275171065493646, + 0.5317204301075269, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.144028, + 12.542223876953125, + -0.04375000000000003, + -0.5275171065493646, + 0.5317204301075269, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.16406, + 12.485681640625, + -0.04375000000000003, + -0.5397849462365593, + 0.5440860215053764, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.184078, + 12.52337646484375, + -0.04375000000000003, + -0.5397849462365593, + 0.5440860215053764, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.204381, + 12.47311669921875, + -0.0447916666666667, + -0.5397849462365593, + 0.5440860215053764, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.224096, + 12.479399169921875, + -0.0447916666666667, + -0.5520527859237537, + 0.5564516129032259, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.244108, + 12.529658935546875, + -0.04583333333333337, + -0.5520527859237537, + 0.5564516129032259, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.264025, + 12.47311669921875, + -0.04583333333333337, + -0.5643206256109482, + 0.5688172043010753, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.284063, + 12.479399169921875, + -0.04583333333333337, + -0.5643206256109482, + 0.5688172043010753, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.304052, + 12.529658935546875, + -0.04687500000000004, + -0.5643206256109482, + 0.5688172043010753, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.324056, + 12.479399169921875, + -0.04687500000000004, + -0.5765884652981428, + 0.5811827956989247, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.344112, + 12.517093994140625, + -0.04791666666666671, + -0.5765884652981428, + 0.5811827956989247, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.364089, + 12.529658935546875, + -0.04791666666666671, + -0.6011241446725318, + 0.6035190615835777, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.384068, + 12.485681640625, + -0.04791666666666671, + -0.6011241446725318, + 0.6035190615835777, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.404098, + 12.53594140625, + -0.04895833333333338, + -0.6011241446725318, + 0.6035190615835777, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.424094, + 12.479399169921875, + -0.04895833333333338, + -0.6133919843597263, + 0.6158357771260997, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.444115, + 12.479399169921875, + -0.05000000000000005, + -0.6133919843597263, + 0.6158357771260997, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.46405, + 12.529658935546875, + -0.05000000000000005, + -0.6256598240469208, + 0.6281524926686216, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.484094, + 12.485681640625, + -0.05000000000000005, + -0.6256598240469208, + 0.6281524926686216, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.504079, + 12.479399169921875, + -0.05104166666666672, + -0.6256598240469208, + 0.6281524926686216, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.524129, + 12.529658935546875, + -0.05104166666666672, + -0.6379276637341154, + 0.6404692082111436, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.544115, + 12.479399169921875, + -0.05104166666666672, + -0.6379276637341154, + 0.6404692082111436, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.564227, + 12.52337646484375, + -0.05208333333333339, + -0.6379276637341154, + 0.6404692082111436, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.584193, + 12.52337646484375, + -0.05208333333333339, + -0.6501955034213099, + 0.6527859237536657, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.604072, + 12.479399169921875, + -0.05312500000000006, + -0.6501955034213099, + 0.6527859237536657, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.624028, + 12.529658935546875, + -0.05312500000000006, + -0.6624633431085044, + 0.6651026392961877, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.644079, + 12.479399169921875, + -0.05312500000000006, + -0.6624633431085044, + 0.6651026392961877, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.664087, + 12.479399169921875, + -0.05416666666666673, + -0.6624633431085044, + 0.6651026392961877, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.684093, + 12.529658935546875, + -0.05416666666666673, + -0.674731182795699, + 0.6774193548387096, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.704095, + 12.479399169921875, + -0.0552083333333334, + -0.674731182795699, + 0.6774193548387096, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.724133, + 12.466834228515625, + -0.0552083333333334, + -0.6869990224828935, + 0.6897360703812316, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.744096, + 12.52337646484375, + -0.0552083333333334, + -0.6869990224828935, + 0.6897360703812316, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.764148, + 12.485681640625, + -0.05625000000000007, + -0.6869990224828935, + 0.6897360703812316, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.784034, + 12.529658935546875, + -0.05625000000000007, + -0.699266862170088, + 0.7020527859237536, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.80416, + 12.529658935546875, + -0.05729166666666674, + -0.699266862170088, + 0.7020527859237536, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.8241, + 12.479399169921875, + -0.05729166666666674, + -0.7115347018572825, + 0.7143695014662756, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.844066, + 12.517093994140625, + -0.05729166666666674, + -0.7115347018572825, + 0.7143695014662756, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.864074, + 12.47311669921875, + -0.05833333333333341, + -0.7115347018572825, + 0.7143695014662756, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.884391, + 12.4605517578125, + -0.05833333333333341, + -0.723802541544477, + 0.7266862170087977, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.904083, + 12.517093994140625, + -0.05937500000000008, + -0.723802541544477, + 0.7266862170087977, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.92408, + 12.47311669921875, + -0.05937500000000008, + -0.7360703812316717, + 0.7390029325513197, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.94406, + 12.47311669921875, + -0.05937500000000008, + -0.7360703812316717, + 0.7390029325513197, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.964142, + 12.529658935546875, + -0.06041666666666675, + -0.7360703812316717, + 0.7390029325513197, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1078.984113, + 12.4605517578125, + -0.06041666666666675, + -0.7483382209188661, + 0.7513196480938417, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.004288, + 12.517093994140625, + -0.06041666666666675, + -0.7483382209188661, + 0.7513196480938417, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.024359, + 12.47311669921875, + -0.06145833333333342, + -0.7483382209188661, + 0.7513196480938417, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.044042, + 12.479399169921875, + -0.06145833333333342, + -0.7606060606060606, + 0.7636363636363637, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.064041, + 12.517093994140625, + -0.06250000000000008, + -0.7606060606060606, + 0.7636363636363637, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.08408, + 12.47311669921875, + -0.06250000000000008, + -0.7728739002932552, + 0.7759530791788857, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.104136, + 12.47311669921875, + -0.06250000000000008, + -0.7728739002932552, + 0.7759530791788857, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.124123, + 12.517093994140625, + -0.06354166666666675, + -0.7728739002932552, + 0.7759530791788857, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.144102, + 12.479399169921875, + -0.06354166666666675, + -0.7974095796676443, + 0.8005865102639296, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.164226, + 12.491964111328125, + -0.06458333333333341, + -0.7974095796676443, + 0.8005865102639296, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.184101, + 12.52337646484375, + -0.06458333333333341, + -0.8096774193548387, + 0.8129032258064516, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.204076, + 12.479399169921875, + -0.06458333333333341, + -0.8096774193548387, + 0.8129032258064516, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.224067, + 12.52337646484375, + -0.06562500000000007, + -0.8096774193548387, + 0.8129032258064516, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.24406, + 12.47311669921875, + -0.06562500000000007, + -0.8219452590420332, + 0.8252199413489736, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.264043, + 12.47311669921875, + -0.06666666666666674, + -0.8219452590420332, + 0.8252199413489736, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.284069, + 12.52337646484375, + -0.06666666666666674, + -0.8342130987292278, + 0.8375366568914955, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.304062, + 12.47311669921875, + -0.06666666666666674, + -0.8342130987292278, + 0.8375366568914955, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.324107, + 12.466834228515625, + -0.0677083333333334, + -0.8342130987292278, + 0.8375366568914955, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.34407, + 12.53594140625, + -0.0677083333333334, + -0.8464809384164222, + 0.8498533724340175, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.364108, + 12.479399169921875, + -0.06875000000000006, + -0.8464809384164222, + 0.8498533724340175, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.384078, + 12.466834228515625, + -0.06875000000000006, + -0.8587487781036168, + 0.8621700879765395, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.404048, + 12.52337646484375, + -0.06875000000000006, + -0.8587487781036168, + 0.8621700879765395, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.424109, + 12.47311669921875, + -0.06979166666666672, + -0.8587487781036168, + 0.8621700879765395, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.444065, + 12.517093994140625, + -0.06979166666666672, + -0.8710166177908113, + 0.8744868035190615, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.464055, + 12.466834228515625, + -0.06979166666666672, + -0.8710166177908113, + 0.8744868035190615, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.484089, + 12.47311669921875, + -0.07083333333333339, + -0.8710166177908113, + 0.8744868035190615, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.50407, + 12.517093994140625, + -0.07083333333333339, + -0.8832844574780059, + 0.8868035190615835, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.524109, + 12.466834228515625, + -0.07187500000000005, + -0.8832844574780059, + 0.8868035190615835, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.544108, + 12.454269287109375, + -0.07187500000000005, + -0.8955522971652006, + 0.8991202346041056, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.56421, + 12.5108115234375, + -0.07187500000000005, + -0.8955522971652006, + 0.8991202346041056, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.584104, + 12.4605517578125, + -0.07291666666666671, + -0.8955522971652006, + 0.8991202346041056, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.604061, + 12.4605517578125, + -0.07291666666666671, + -0.907820136852395, + 0.9114369501466276, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.624213, + 12.517093994140625, + -0.07395833333333338, + -0.907820136852395, + 0.9114369501466276, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.644085, + 12.466834228515625, + -0.07395833333333338, + -0.9200879765395895, + 0.9237536656891496, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.664321, + 12.52337646484375, + -0.07395833333333338, + -0.9200879765395895, + 0.9237536656891496, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.684337, + 12.47311669921875, + -0.07500000000000004, + -0.9200879765395895, + 0.9237536656891496, + 105.49122310125705, + -57.64888541870381, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.704195, + 12.4605517578125, + -0.07500000000000004, + -0.9323558162267841, + 0.9360703812316715, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1079.724043, + 12.5108115234375, + -0.0760416666666667, + -0.9323558162267841, + 0.9360703812316715, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1079.744078, + 12.4605517578125, + -0.0760416666666667, + -0.9446236559139786, + 0.9483870967741935, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1079.76408, + 12.44798681640625, + -0.0760416666666667, + -0.9446236559139786, + 0.9483870967741935, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1079.784125, + 12.5108115234375, + -0.07708333333333336, + -0.9446236559139786, + 0.9483870967741935, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1079.804209, + 12.4605517578125, + -0.07708333333333336, + -0.9568914956011731, + 0.9607038123167155, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.824084, + 12.454269287109375, + -0.07812500000000003, + -0.9568914956011731, + 0.9607038123167155, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.844112, + 12.517093994140625, + -0.07812500000000003, + -0.9691593352883676, + 0.9730205278592375, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.864069, + 12.4605517578125, + -0.07812500000000003, + -0.9691593352883676, + 0.9730205278592375, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.884057, + 12.504529052734375, + -0.07916666666666669, + -0.9691593352883676, + 0.9730205278592375, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.90435, + 12.466834228515625, + -0.07916666666666669, + -0.9814271749755621, + 0.9853372434017595, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.92416, + 12.441704345703124, + -0.07916666666666669, + -0.9814271749755621, + 0.9853372434017595, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.944079, + 12.5108115234375, + -0.08020833333333335, + -0.9814271749755621, + 0.9853372434017595, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.964074, + 12.466834228515625, + -0.08020833333333335, + -1.0059628543499513, + 1.0099706744868036, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1079.984102, + 12.454269287109375, + -0.08125000000000002, + -1.0059628543499513, + 1.0099706744868036, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.004111, + 12.5108115234375, + -0.08125000000000002, + -1.0182306940371457, + 1.0222873900293254, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.024058, + 12.4605517578125, + -0.08125000000000002, + -1.0182306940371457, + 1.0222873900293254, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.044045, + 12.454269287109375, + -0.08229166666666668, + -1.0182306940371457, + 1.0222873900293254, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.064071, + 12.517093994140625, + -0.08229166666666668, + -1.0304985337243402, + 1.0346041055718473, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.084076, + 12.466834228515625, + -0.08333333333333334, + -1.0304985337243402, + 1.0346041055718473, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.104071, + 12.504529052734375, + -0.08333333333333334, + -1.0427663734115347, + 1.0469208211143695, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.124096, + 12.4605517578125, + -0.08333333333333334, + -1.0427663734115347, + 1.0469208211143695, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.144113, + 12.4605517578125, + -0.084375, + -1.0427663734115347, + 1.0469208211143695, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.164106, + 12.49824658203125, + -0.084375, + -1.0550342130987291, + 1.0592375366568914, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.184091, + 12.44798681640625, + -0.08541666666666667, + -1.0550342130987291, + 1.0592375366568914, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.20418, + 12.466834228515625, + -0.08541666666666667, + -1.0673020527859238, + 1.0715542521994135, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.224261, + 12.504529052734375, + -0.08541666666666667, + -1.0673020527859238, + 1.0715542521994135, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.244076, + 12.4605517578125, + -0.08645833333333333, + -1.0673020527859238, + 1.0715542521994135, + 105.49122310125705, + -57.64795030401552, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.264065, + 12.441704345703124, + -0.08645833333333333, + -1.0795698924731185, + 1.0838709677419356, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.284158, + 12.491964111328125, + -0.0875, + -1.0795698924731185, + 1.0838709677419356, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.304291, + 12.44798681640625, + -0.0875, + -1.091837732160313, + 1.0961876832844575, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.324072, + 12.491964111328125, + -0.0875, + -1.091837732160313, + 1.0961876832844575, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.344098, + 12.44798681640625, + -0.08854166666666666, + -1.091837732160313, + 1.0961876832844575, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.364099, + 12.44798681640625, + -0.08854166666666666, + -1.1041055718475075, + 1.1085043988269796, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.38408, + 12.5108115234375, + -0.08854166666666666, + -1.1041055718475075, + 1.1085043988269796, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.404105, + 12.454269287109375, + -0.08958333333333332, + -1.1041055718475075, + 1.1085043988269796, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.4241, + 12.44798681640625, + -0.08958333333333332, + -1.116373411534702, + 1.1208211143695015, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.444066, + 12.504529052734375, + -0.09062499999999998, + -1.116373411534702, + 1.1208211143695015, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.464056, + 12.429139404296874, + -0.09062499999999998, + -1.1286412512218964, + 1.1331378299120234, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.484046, + 12.44798681640625, + -0.09062499999999998, + -1.1286412512218964, + 1.1331378299120234, + 105.49122310125705, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.50406, + 12.504529052734375, + -0.09166666666666665, + -1.1286412512218964, + 1.1331378299120234, + 105.49028798656875, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.524115, + 12.441704345703124, + -0.09166666666666665, + -1.140909090909091, + 1.1454545454545455, + 105.49028798656875, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.544106, + 12.5108115234375, + -0.09270833333333331, + -1.140909090909091, + 1.1454545454545455, + 105.49028798656875, + -57.64701518932722, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.564108, + 12.44798681640625, + -0.09270833333333331, + -1.1531769305962856, + 1.1577712609970674, + 105.49028798656875, + -57.64701518932722, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1080.584065, + 12.429139404296874, + -0.09270833333333331, + -1.1531769305962856, + 1.1577712609970674, + 105.49028798656875, + -57.64701518932722, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1080.604086, + 12.491964111328125, + -0.09374999999999997, + -1.1531769305962856, + 1.1577712609970674, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.624089, + 12.435421875, + -0.09374999999999997, + -1.16544477028348, + 1.1700879765395895, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.644053, + 12.435421875, + -0.09479166666666664, + -1.16544477028348, + 1.1700879765395895, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.664256, + 12.485681640625, + -0.09479166666666664, + -1.1777126099706745, + 1.1824046920821114, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.684064, + 12.44798681640625, + -0.09479166666666664, + -1.1777126099706745, + 1.1824046920821114, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.704081, + 12.429139404296874, + -0.0958333333333333, + -1.1777126099706745, + 1.1824046920821114, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.724053, + 12.491964111328125, + -0.0958333333333333, + -1.2022482893450637, + 1.2070381231671554, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.744088, + 12.42285693359375, + -0.09687499999999996, + -1.2022482893450637, + 1.2070381231671554, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.764037, + 12.491964111328125, + -0.09687499999999996, + -1.2145161290322581, + 1.2193548387096773, + 105.49028798656875, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.784194, + 12.441704345703124, + -0.09687499999999996, + -1.2145161290322581, + 1.2193548387096773, + 105.48935287188046, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.804081, + 12.441704345703124, + -0.09791666666666662, + -1.2145161290322581, + 1.2193548387096773, + 105.48935287188046, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.82407, + 12.49824658203125, + -0.09791666666666662, + -1.2267839687194526, + 1.2316715542521994, + 105.48935287188046, + -57.646080074638924, + 0.0, + 0.0, + 0.0 + ], + [ + 1080.844027, + 12.44798681640625, + -0.09791666666666662, + -1.2267839687194526, + 1.2316715542521994, + 105.48935287188046, + -57.646080074638924, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1080.864051, + 12.441704345703124, + -0.09895833333333329, + -1.2267839687194526, + 1.2316715542521994, + 105.48935287188046, + -57.646080074638924, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1080.884087, + 12.485681640625, + -0.09895833333333329, + -1.239051808406647, + 1.2439882697947213, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.904082, + 12.42285693359375, + -0.09999999999999995, + -1.239051808406647, + 1.2439882697947213, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.924064, + 12.485681640625, + -0.09999999999999995, + -1.2513196480938416, + 1.2513196480938416, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.944062, + 12.491964111328125, + -0.09999999999999995, + -1.2513196480938416, + 1.2513196480938416, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.964027, + 12.429139404296874, + -0.10104166666666661, + -1.2513196480938416, + 1.2513196480938416, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1080.984076, + 12.479399169921875, + -0.10104166666666661, + -1.2635874877810362, + 1.2635874877810362, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.004115, + 12.42285693359375, + -0.10208333333333328, + -1.2635874877810362, + 1.2635874877810362, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.024057, + 12.435421875, + -0.10208333333333328, + -1.2758553274682307, + 1.2758553274682307, + 105.48935287188046, + -57.64514495995063, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.044104, + 12.466834228515625, + -0.10208333333333328, + -1.2758553274682307, + 1.2758553274682307, + 105.48841775719215, + -57.64514495995063, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.06407, + 12.429139404296874, + -0.10312499999999994, + -1.2758553274682307, + 1.2758553274682307, + 105.48841775719215, + -57.64514495995063, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.084096, + 12.416574462890624, + -0.10312499999999994, + -1.2881231671554254, + 1.2932551319648093, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.104076, + 12.479399169921875, + -0.1041666666666666, + -1.2881231671554254, + 1.2932551319648093, + 105.48841775719215, + -57.64420984526233, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1081.124072, + 12.435421875, + -0.1041666666666666, + -1.3003910068426199, + 1.3055718475073315, + 105.48841775719215, + -57.64420984526233, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1081.144082, + 12.485681640625, + -0.1041666666666666, + -1.3003910068426199, + 1.3055718475073315, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.16411, + 12.491964111328125, + -0.10520833333333326, + -1.3003910068426199, + 1.3055718475073315, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.184068, + 12.435421875, + -0.10520833333333326, + -1.3126588465298143, + 1.3178885630498534, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.204069, + 12.479399169921875, + -0.10624999999999993, + -1.3126588465298143, + 1.3178885630498534, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.224122, + 12.44798681640625, + -0.10624999999999993, + -1.3249266862170088, + 1.3302052785923755, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.244098, + 12.435421875, + -0.10624999999999993, + -1.3249266862170088, + 1.3249266862170088, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.264122, + 12.485681640625, + -0.10729166666666659, + -1.3249266862170088, + 1.3249266862170088, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.284106, + 12.441704345703124, + -0.10729166666666659, + -1.3318670576735092, + 1.3371945259042035, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.304109, + 12.454269287109375, + -0.10833333333333325, + -1.3318670576735092, + 1.3371945259042035, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.324083, + 12.479399169921875, + -0.10833333333333325, + -1.3440860215053763, + 1.349462365591398, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.344075, + 12.435421875, + -0.10833333333333325, + -1.3440860215053763, + 1.349462365591398, + 105.48841775719215, + -57.64420984526233, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.364167, + 12.479399169921875, + -0.10937499999999992, + -1.3440860215053763, + 1.349462365591398, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.384071, + 12.47311669921875, + -0.10937499999999992, + -1.3563049853372433, + 1.3617302052785925, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.40405, + 12.416574462890624, + -0.10937499999999992, + -1.3563049853372433, + 1.3617302052785925, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.424084, + 12.47311669921875, + -0.11041666666666658, + -1.3563049853372433, + 1.3617302052785925, + 105.48748264250386, + -57.64327473057404, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1081.444059, + 12.416574462890624, + -0.11041666666666658, + -1.3685239491691104, + 1.373998044965787, + 105.48748264250386, + -57.64327473057404, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1081.464109, + 12.42285693359375, + -0.11145833333333324, + -1.3685239491691104, + 1.373998044965787, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.484102, + 12.466834228515625, + -0.11145833333333324, + -1.3929618768328444, + 1.398533724340176, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.504064, + 12.416574462890624, + -0.11145833333333324, + -1.3929618768328444, + 1.398533724340176, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.524113, + 12.42285693359375, + -0.1124999999999999, + -1.3929618768328444, + 1.398533724340176, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.544269, + 12.466834228515625, + -0.1124999999999999, + -1.4051808406647115, + 1.4108015640273706, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.56409, + 12.441704345703124, + -0.11354166666666657, + -1.4051808406647115, + 1.4108015640273706, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.584104, + 12.466834228515625, + -0.11354166666666657, + -1.4173998044965785, + 1.423069403714565, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.604093, + 12.466834228515625, + -0.11354166666666657, + -1.4173998044965785, + 1.423069403714565, + 105.48748264250386, + -57.64327473057404, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.624055, + 12.4102919921875, + -0.11458333333333323, + -1.4173998044965785, + 1.423069403714565, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.644054, + 12.466834228515625, + -0.11458333333333323, + -1.4296187683284456, + 1.4353372434017595, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.664109, + 12.429139404296874, + -0.1156249999999999, + -1.4296187683284456, + 1.4353372434017595, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.684058, + 12.4102919921875, + -0.1156249999999999, + -1.4418377321603126, + 1.447605083088954, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.704085, + 12.466834228515625, + -0.1156249999999999, + -1.4418377321603126, + 1.447605083088954, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.724082, + 12.404009521484374, + -0.11666666666666656, + -1.4418377321603126, + 1.447605083088954, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.744146, + 12.4102919921875, + -0.11666666666666656, + -1.4540566959921797, + 1.4598729227761487, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.764028, + 12.4605517578125, + -0.11666666666666656, + -1.4540566959921797, + 1.4598729227761487, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.784077, + 12.416574462890624, + -0.11770833333333322, + -1.4540566959921797, + 1.4598729227761487, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.804077, + 12.454269287109375, + -0.11770833333333322, + -1.466275659824047, + 1.4721407624633434, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.824105, + 12.4605517578125, + -0.11874999999999988, + -1.466275659824047, + 1.4721407624633434, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.844054, + 12.4102919921875, + -0.11874999999999988, + -1.478494623655914, + 1.4844086021505378, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.86405, + 12.454269287109375, + -0.11874999999999988, + -1.478494623655914, + 1.4844086021505378, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.884087, + 12.39772705078125, + -0.11979166666666655, + -1.478494623655914, + 1.4844086021505378, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.904053, + 12.404009521484374, + -0.11979166666666655, + -1.490713587487781, + 1.4966764418377323, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.92403, + 12.454269287109375, + -0.12083333333333321, + -1.48475073313783, + 1.4966764418377323, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.944043, + 12.391444580078124, + -0.12083333333333321, + -1.4969208211143696, + 1.5089442815249268, + 105.48748264250386, + -57.642339615885746, + 0.0, + 0.0, + 0.0 + ], + [ + 1081.964093, + 12.39772705078125, + -0.12083333333333321, + -1.4969208211143696, + 1.5089442815249268, + 105.48748264250386, + -57.64140450119745, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1081.984108, + 12.4605517578125, + -0.12187499999999987, + -1.4969208211143696, + 1.5089442815249268, + 105.48748264250386, + -57.64140450119745, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.004088, + 12.4102919921875, + -0.12187499999999987, + -1.5090909090909093, + 1.5212121212121212, + 105.48748264250386, + -57.64140450119745, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.024107, + 12.466834228515625, + -0.12291666666666654, + -1.5090909090909093, + 1.5212121212121212, + 105.48748264250386, + -57.64140450119745, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.044042, + 12.44798681640625, + -0.12291666666666654, + -1.5212609970674489, + 1.533479960899316, + 105.48748264250386, + -57.64140450119745, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.064095, + 12.404009521484374, + -0.12291666666666654, + -1.5212609970674489, + 1.533479960899316, + 105.48748264250386, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.084102, + 12.454269287109375, + -0.1239583333333332, + -1.5212609970674489, + 1.533479960899316, + 105.48654752781557, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.104305, + 12.404009521484374, + -0.1239583333333332, + -1.5334310850439885, + 1.5457478005865104, + 105.48654752781557, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.124066, + 12.4102919921875, + -0.12499999999999986, + -1.5334310850439885, + 1.5457478005865104, + 105.48654752781557, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.144059, + 12.466834228515625, + -0.12499999999999986, + -1.545601173020528, + 1.5580156402737049, + 105.48654752781557, + -57.64140450119745, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1082.164034, + 12.391444580078124, + -0.12499999999999986, + -1.545601173020528, + 1.5580156402737049, + 105.48654752781557, + -57.64140450119745, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1082.184113, + 12.4102919921875, + -0.12604166666666652, + -1.545601173020528, + 1.5580156402737049, + 105.48654752781557, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.204095, + 12.44798681640625, + -0.12604166666666652, + -1.5577712609970675, + 1.5702834799608993, + 105.48654752781557, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.224067, + 12.39772705078125, + -0.1270833333333332, + -1.5577712609970675, + 1.5702834799608993, + 105.48654752781557, + -57.64140450119745, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.244194, + 12.454269287109375, + -0.1270833333333332, + -1.5821114369501468, + 1.5948191593352885, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.264057, + 12.39772705078125, + -0.1270833333333332, + -1.5821114369501468, + 1.5948191593352885, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.284213, + 12.39772705078125, + -0.12812499999999985, + -1.5821114369501468, + 1.5948191593352885, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.304079, + 12.441704345703124, + -0.12812499999999985, + -1.5942815249266864, + 1.607086999022483, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.324041, + 12.4102919921875, + -0.12812499999999985, + -1.5942815249266864, + 1.607086999022483, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.344113, + 12.404009521484374, + -0.1291666666666665, + -1.5942815249266864, + 1.607086999022483, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.36422, + 12.44798681640625, + -0.1291666666666665, + -1.6064516129032258, + 1.6193548387096774, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.384276, + 12.4102919921875, + -0.13020833333333318, + -1.6064516129032258, + 1.6193548387096774, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.404103, + 12.404009521484374, + -0.13020833333333318, + -1.6186217008797654, + 1.631622678396872, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.424087, + 12.454269287109375, + -0.13020833333333318, + -1.6186217008797654, + 1.631622678396872, + 105.48654752781557, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.444158, + 12.404009521484374, + -0.13124999999999984, + -1.6186217008797654, + 1.631622678396872, + 105.48561241312727, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.464076, + 12.435421875, + -0.13124999999999984, + -1.630791788856305, + 1.6438905180840664, + 105.48561241312727, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.484106, + 12.39772705078125, + -0.1322916666666665, + -1.630791788856305, + 1.6438905180840664, + 105.48561241312727, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.504074, + 12.385162109374999, + -0.1322916666666665, + -1.6429618768328447, + 1.656158357771261, + 105.48561241312727, + -57.64046938650915, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1082.524066, + 12.429139404296874, + -0.1322916666666665, + -1.6429618768328447, + 1.656158357771261, + 105.48561241312727, + -57.64046938650915, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1082.544048, + 12.391444580078124, + -0.13333333333333316, + -1.6429618768328447, + 1.656158357771261, + 105.48561241312727, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.564104, + 12.378879638671874, + -0.13333333333333316, + -1.6551319648093843, + 1.6684261974584556, + 105.48561241312727, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.584116, + 12.42285693359375, + -0.13437499999999983, + -1.6551319648093843, + 1.6684261974584556, + 105.48561241312727, + -57.64046938650915, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.604079, + 12.385162109374999, + -0.13437499999999983, + -1.6673020527859237, + 1.68069403714565, + 105.48561241312727, + -57.63953427182086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.624095, + 12.366314697265624, + -0.13437499999999983, + -1.6673020527859237, + 1.68069403714565, + 105.48561241312727, + -57.63953427182086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.644031, + 12.416574462890624, + -0.1354166666666665, + -1.6673020527859237, + 1.68069403714565, + 105.48561241312727, + -57.63953427182086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.664659, + 12.378879638671874, + -0.1354166666666665, + -1.6794721407624633, + 1.6929618768328445, + 105.48561241312727, + -57.63953427182086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.684103, + 12.429139404296874, + -0.13645833333333315, + -1.6794721407624633, + 1.6929618768328445, + 105.48561241312727, + -57.63953427182086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.704059, + 12.385162109374999, + -0.13645833333333315, + -1.691642228739003, + 1.7052297165200392, + 105.48467729843898, + -57.63953427182086, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.724156, + 12.378879638671874, + -0.13645833333333315, + -1.691642228739003, + 1.7052297165200392, + 105.48467729843898, + -57.63953427182086, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.745895, + 12.42285693359375, + -0.13749999999999982, + -1.691642228739003, + 1.7052297165200392, + 105.48467729843898, + -57.63953427182086, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.764126, + 12.372597167968749, + -0.13749999999999982, + -1.7038123167155426, + 1.7174975562072337, + 105.48467729843898, + -57.63953427182086, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.784157, + 12.372597167968749, + -0.13749999999999982, + -1.7038123167155426, + 1.7174975562072337, + 105.48467729843898, + -57.63953427182086, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1082.804119, + 12.42285693359375, + -0.13854166666666648, + -1.7038123167155426, + 1.7174975562072337, + 105.48467729843898, + -57.63953427182086, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.824076, + 12.360032226562499, + -0.13854166666666648, + -1.7159824046920822, + 1.7297653958944281, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.844115, + 12.366314697265624, + -0.13958333333333314, + -1.7159824046920822, + 1.722873900293255, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.864123, + 12.42285693359375, + -0.13958333333333314, + -1.7281524926686216, + 1.735092864125122, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.884186, + 12.385162109374999, + -0.13958333333333314, + -1.7281524926686216, + 1.735092864125122, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.90411, + 12.429139404296874, + -0.1406249999999998, + -1.7281524926686216, + 1.735092864125122, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1082.924075, + 12.378879638671874, + -0.1406249999999998, + -1.7403225806451612, + 1.747311827956989, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.944121, + 12.366314697265624, + -0.14166666666666647, + -1.7403225806451612, + 1.747311827956989, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.964101, + 12.416574462890624, + -0.14166666666666647, + -1.7524926686217008, + 1.759530791788856, + 105.48467729843898, + -57.63859915713256, + 0.0, + 0.0, + 0.0 + ], + [ + 1082.984061, + 12.366314697265624, + -0.14166666666666647, + -1.7524926686217008, + 1.759530791788856, + 105.48374218375068, + -57.63859915713256, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.004058, + 12.360032226562499, + -0.14270833333333313, + -1.7524926686217008, + 1.759530791788856, + 105.48374218375068, + -57.63859915713256, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.02423, + 12.4102919921875, + -0.14270833333333313, + -1.7646627565982407, + 1.7717497556207236, + 105.48374218375068, + -57.63859915713256, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.044097, + 12.372597167968749, + -0.1437499999999998, + -1.7646627565982407, + 1.7717497556207236, + 105.48374218375068, + -57.63859915713256, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1083.064107, + 12.360032226562499, + -0.1437499999999998, + -1.78900293255132, + 1.7961876832844577, + 105.48374218375068, + -57.63766404244427, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1083.084105, + 12.4102919921875, + -0.1437499999999998, + -1.78900293255132, + 1.7961876832844577, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.104089, + 12.378879638671874, + -0.14479166666666646, + -1.78900293255132, + 1.7961876832844577, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.12406, + 12.4102919921875, + -0.14479166666666646, + -1.8011730205278595, + 1.8084066471163247, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.144037, + 12.353749755859374, + -0.14583333333333312, + -1.8011730205278595, + 1.8084066471163247, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.164065, + 12.372597167968749, + -0.14583333333333312, + -1.8133431085043992, + 1.8206256109481918, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.184116, + 12.42285693359375, + -0.14583333333333312, + -1.8133431085043992, + 1.8206256109481918, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.204107, + 12.366314697265624, + -0.14687499999999978, + -1.8133431085043992, + 1.8206256109481918, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.224103, + 12.372597167968749, + -0.14687499999999978, + -1.8255131964809386, + 1.8328445747800588, + 105.48374218375068, + -57.63766404244427, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.244141, + 12.416574462890624, + -0.14687499999999978, + -1.8255131964809386, + 1.8328445747800588, + 105.48374218375068, + -57.636728927755975, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.264085, + 12.372597167968749, + -0.14791666666666645, + -1.8255131964809386, + 1.8328445747800588, + 105.48280706906239, + -57.636728927755975, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.284085, + 12.385162109374999, + -0.14791666666666645, + -1.8376832844574782, + 1.8450635386119258, + 105.48280706906239, + -57.636728927755975, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.304083, + 12.416574462890624, + -0.1489583333333331, + -1.8376832844574782, + 1.8450635386119258, + 105.48280706906239, + -57.636728927755975, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.324114, + 12.360032226562499, + -0.1489583333333331, + -1.8498533724340178, + 1.8498533724340178, + 105.48280706906239, + -57.636728927755975, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1083.344074, + 12.42285693359375, + -0.1489583333333331, + -1.8498533724340178, + 1.8498533724340178, + 105.48280706906239, + -57.636728927755975, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1083.364033, + 12.360032226562499, + -0.14999999999999977, + -1.8498533724340178, + 1.8498533724340178, + 105.48280706906239, + -57.63579381306768, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.384121, + 12.366314697265624, + -0.14999999999999977, + -1.8620234604105574, + 1.8620234604105574, + 105.48280706906239, + -57.63579381306768, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.404154, + 12.4102919921875, + -0.15104166666666644, + -1.8620234604105574, + 1.8620234604105574, + 105.48187195437409, + -57.63579381306768, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.424103, + 12.353749755859374, + -0.15104166666666644, + -1.874193548387097, + 1.874193548387097, + 105.48187195437409, + -57.63579381306768, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.444071, + 12.353749755859374, + -0.15104166666666644, + -1.874193548387097, + 1.874193548387097, + 105.48187195437409, + -57.63579381306768, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.464116, + 12.39772705078125, + -0.1520833333333331, + -1.874193548387097, + 1.874193548387097, + 105.48187195437409, + -57.63485869837938, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1083.484035, + 12.360032226562499, + -0.1520833333333331, + -1.8863636363636367, + 1.8863636363636367, + 105.48187195437409, + -57.63485869837938, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1083.504177, + 12.404009521484374, + -0.15312499999999976, + -1.8863636363636367, + 1.8863636363636367, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.5244, + 12.404009521484374, + -0.15312499999999976, + -1.898533724340176, + 1.898533724340176, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.544061, + 12.353749755859374, + -0.15312499999999976, + -1.898533724340176, + 1.898533724340176, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.564174, + 12.416574462890624, + -0.15416666666666642, + -1.898533724340176, + 1.898533724340176, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.584078, + 12.360032226562499, + -0.15416666666666642, + -1.9107038123167157, + 1.9107038123167157, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.604158, + 12.366314697265624, + -0.1552083333333331, + -1.9107038123167157, + 1.9107038123167157, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.624027, + 12.4102919921875, + -0.1552083333333331, + -1.9228739002932553, + 1.9228739002932553, + 105.48187195437409, + -57.63485869837938, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.644064, + 12.347467285156249, + -0.1552083333333331, + -1.9228739002932553, + 1.9228739002932553, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.664111, + 12.341184814453124, + -0.15624999999999975, + -1.9228739002932553, + 1.9228739002932553, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.684036, + 12.404009521484374, + -0.15624999999999975, + -1.9272727272727272, + 1.935043988269795, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.704078, + 12.334902343749999, + -0.15624999999999975, + -1.9272727272727272, + 1.935043988269795, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.72408, + 12.391444580078124, + -0.1572916666666664, + -1.9272727272727272, + 1.935043988269795, + 105.4809368396858, + -57.633923583691086, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1083.744107, + 12.404009521484374, + -0.1572916666666664, + -1.9393939393939394, + 1.9472140762463346, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.764064, + 12.328619873046875, + -0.15833333333333308, + -1.9393939393939394, + 1.9472140762463346, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.784058, + 12.378879638671874, + -0.15833333333333308, + -1.9515151515151516, + 1.959384164222874, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.804096, + 12.334902343749999, + -0.15833333333333308, + -1.9515151515151516, + 1.959384164222874, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.824075, + 12.32233740234375, + -0.15937499999999974, + -1.9515151515151516, + 1.959384164222874, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.844068, + 12.378879638671874, + -0.15937499999999974, + -1.9757575757575758, + 1.9837243401759532, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.864092, + 12.334902343749999, + -0.1604166666666664, + -1.9757575757575758, + 1.9837243401759532, + 105.4809368396858, + -57.633923583691086, + 0.0, + 0.0, + 0.0 + ], + [ + 1083.884081, + 12.334902343749999, + -0.1604166666666664, + -1.9878787878787878, + 1.9958944281524928, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.904081, + 12.372597167968749, + -0.1604166666666664, + -1.9878787878787878, + 1.9958944281524928, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.924039, + 12.334902343749999, + -0.16145833333333307, + -1.9878787878787878, + 1.9958944281524928, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.944069, + 12.378879638671874, + -0.16145833333333307, + -2.0, + 2.0080645161290325, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1083.964068, + 12.39772705078125, + -0.16249999999999973, + -2.0, + 2.0080645161290325, + 105.4800017249975, + -57.63298846900279, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1083.984072, + 12.341184814453124, + -0.16249999999999973, + -2.012121212121212, + 2.020234604105572, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.004027, + 12.385162109374999, + -0.16249999999999973, + -2.012121212121212, + 2.020234604105572, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.024069, + 12.334902343749999, + -0.1635416666666664, + -2.012121212121212, + 2.020234604105572, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.044059, + 12.334902343749999, + -0.1635416666666664, + -2.0242424242424244, + 2.0324046920821117, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.06407, + 12.391444580078124, + -0.16458333333333305, + -2.0242424242424244, + 2.0324046920821117, + 105.4800017249975, + -57.63298846900279, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.084097, + 12.341184814453124, + -0.16458333333333305, + -2.036363636363636, + 2.044574780058651, + 105.4800017249975, + -57.6320533543145, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.104377, + 12.316054931640625, + -0.16458333333333305, + -2.036363636363636, + 2.044574780058651, + 105.4800017249975, + -57.6320533543145, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.124101, + 12.385162109374999, + -0.16562499999999972, + -2.036363636363636, + 2.044574780058651, + 105.4800017249975, + -57.6320533543145, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.144098, + 12.328619873046875, + -0.16562499999999972, + -2.0484848484848484, + 2.0567448680351905, + 105.4800017249975, + -57.6320533543145, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.164308, + 12.378879638671874, + -0.16562499999999972, + -2.0484848484848484, + 2.0567448680351905, + 105.4790666103092, + -57.6320533543145, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.184076, + 12.385162109374999, + -0.16666666666666638, + -2.0484848484848484, + 2.0567448680351905, + 105.4790666103092, + -57.6320533543145, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.204068, + 12.328619873046875, + -0.16666666666666638, + -2.0606060606060606, + 2.06891495601173, + 105.4790666103092, + -57.6320533543145, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.224047, + 12.378879638671874, + -0.16770833333333304, + -2.0606060606060606, + 2.06891495601173, + 105.4790666103092, + -57.6320533543145, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1084.244309, + 12.32233740234375, + -0.16770833333333304, + -2.0727272727272728, + 2.0810850439882698, + 105.4790666103092, + -57.631118239626204, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1084.264113, + 12.328619873046875, + -0.16770833333333304, + -2.0727272727272728, + 2.0810850439882698, + 105.4790666103092, + -57.631118239626204, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.284107, + 12.378879638671874, + -0.1687499999999997, + -2.0727272727272728, + 2.0810850439882698, + 105.4790666103092, + -57.631118239626204, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.304077, + 12.32233740234375, + -0.1687499999999997, + -2.084848484848485, + 2.0932551319648094, + 105.4790666103092, + -57.631118239626204, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.32412, + 12.334902343749999, + -0.16979166666666637, + -2.084848484848485, + 2.0932551319648094, + 105.4790666103092, + -57.631118239626204, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.344044, + 12.372597167968749, + -0.16979166666666637, + -2.0969696969696967, + 2.105425219941349, + 105.4790666103092, + -57.631118239626204, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.364085, + 12.334902343749999, + -0.16979166666666637, + -2.0969696969696967, + 2.105425219941349, + 105.47813149562091, + -57.631118239626204, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.384174, + 12.385162109374999, + -0.17083333333333303, + -2.0969696969696967, + 2.105425219941349, + 105.47813149562091, + -57.631118239626204, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.404056, + 12.385162109374999, + -0.17083333333333303, + -2.109090909090909, + 2.1175953079178886, + 105.47813149562091, + -57.631118239626204, + 0.0, + 0.0, + 0.0 + ], + [ + 1084.424071, + 12.334902343749999, + -0.1718749999999997, + -2.109090909090909, + 2.1175953079178886, + 105.47813149562091, + -57.63018312493791, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1084.444105, + 12.391444580078124, + -0.1718749999999997, + -2.121212121212121, + 2.1297653958944283, + 105.47813149562091, + -57.63018312493791, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1084.464076, + 12.328619873046875, + -0.1718749999999997, + -2.121212121212121, + 2.1297653958944283, + 105.47813149562091, + -57.63018312493791, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.484094, + 12.32233740234375, + -0.17291666666666636, + -2.121212121212121, + 2.1297653958944283, + 105.47813149562091, + -57.63018312493791, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.504186, + 12.385162109374999, + -0.17291666666666636, + -2.1333333333333337, + 2.141935483870968, + 105.47813149562091, + -57.63018312493791, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.524134, + 12.32233740234375, + -0.17395833333333302, + -2.1333333333333337, + 2.141935483870968, + 105.47719638093261, + -57.62924801024961, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.544077, + 12.334902343749999, + -0.17395833333333302, + -2.1454545454545455, + 2.1541055718475075, + 105.47719638093261, + -57.62924801024961, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.564076, + 12.378879638671874, + -0.17395833333333302, + -2.1454545454545455, + 2.1541055718475075, + 105.47719638093261, + -57.628312895561315, + 0.0, + 0.018702293765901736, + 0.0 + ], + [ + 1084.584086, + 12.32233740234375, + -0.17499999999999968, + -2.1454545454545455, + 2.1541055718475075, + 105.47719638093261, + -57.627377780873026, + -0.009351146882950868, + 0.02805344064885261, + 0.0 + ], + [ + 1084.604092, + 12.378879638671874, + -0.17499999999999968, + -2.16969696969697, + 2.1784457478005868, + 105.47626126624432, + -57.627377780873026, + -0.009351146882950868, + 0.02805344064885261, + 0.0 + ], + [ + 1084.624103, + 12.32233740234375, + -0.17499999999999968, + -2.16969696969697, + 2.1784457478005868, + 105.47532615155603, + -57.627377780873026, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1084.644102, + 12.32233740234375, + -0.17604166666666635, + -2.16969696969697, + 2.1784457478005868, + 105.47532615155603, + -57.62644266618473, + -0.009351146882950868, + 0.02805344064885261, + 0.0 + ], + [ + 1084.664068, + 12.360032226562499, + -0.17604166666666635, + -2.181818181818182, + 2.1906158357771264, + 105.47439103686773, + -57.62550755149643, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1084.684126, + 12.3097724609375, + -0.177083333333333, + -2.181818181818182, + 2.1906158357771264, + 105.47345592217944, + -57.62457243680814, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1084.704026, + 12.29720751953125, + -0.177083333333333, + -2.1939393939393943, + 2.202785923753666, + 105.47345592217944, + -57.62457243680814, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1084.724059, + 12.341184814453124, + -0.177083333333333, + -2.1939393939393943, + 2.202785923753666, + 105.47252080749114, + -57.62363732211984, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1084.744045, + 12.3097724609375, + -0.17812499999999967, + -2.1939393939393943, + 2.202785923753666, + 105.47252080749114, + -57.622702207431544, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1084.764178, + 12.316054931640625, + -0.17812499999999967, + -2.206060606060606, + 2.206060606060606, + 105.47158569280285, + -57.622702207431544, + -0.02805344064885261, + 0.02805344064885261, + 0.0 + ], + [ + 1084.784148, + 12.372597167968749, + -0.17916666666666634, + -2.206060606060606, + 2.206060606060606, + 105.47158569280285, + -57.621767092743255, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1084.804067, + 12.29720751953125, + -0.17916666666666634, + -2.2181818181818183, + 2.2181818181818183, + 105.47158569280285, + -57.621767092743255, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1084.824077, + 12.347467285156249, + -0.17916666666666634, + -2.2181818181818183, + 2.2181818181818183, + 105.47065057811456, + -57.621767092743255, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1084.844026, + 12.290925048828125, + -0.180208333333333, + -2.2181818181818183, + 2.2181818181818183, + 105.47065057811456, + -57.621767092743255, + -0.018702293765901736, + 0.009351146882950868, + 0.0 + ], + [ + 1084.864035, + 12.284642578125, + -0.180208333333333, + -2.2303030303030305, + 2.2303030303030305, + 105.47065057811456, + -57.621767092743255, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1084.88408, + 12.341184814453124, + -0.18124999999999966, + -2.2303030303030305, + 2.2303030303030305, + 105.47065057811456, + -57.621767092743255, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1084.904283, + 12.316054931640625, + -0.18124999999999966, + -2.2424242424242427, + 2.2424242424242427, + 105.47065057811456, + -57.62083197805496, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1084.924135, + 12.284642578125, + -0.18124999999999966, + -2.2424242424242427, + 2.2514662756598245, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.944101, + 12.341184814453124, + -0.18229166666666632, + -2.2424242424242427, + 2.2514662756598245, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.964098, + 12.284642578125, + -0.18229166666666632, + -2.254545454545455, + 2.263636363636364, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1084.984065, + 12.278360107421875, + -0.18229166666666632, + -2.254545454545455, + 2.263636363636364, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.00412, + 12.316054931640625, + -0.183333333333333, + -2.254545454545455, + 2.263636363636364, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.024042, + 12.265795166015625, + -0.183333333333333, + -2.2666666666666666, + 2.2758064516129033, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.044118, + 12.3097724609375, + -0.18437499999999965, + -2.2666666666666666, + 2.2758064516129033, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.064059, + 12.278360107421875, + -0.18437499999999965, + -2.278787878787879, + 2.287976539589443, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.08404, + 12.265795166015625, + -0.18437499999999965, + -2.278787878787879, + 2.278787878787879, + 105.47065057811456, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.104103, + 12.32233740234375, + -0.1854166666666663, + -2.278787878787879, + 2.278787878787879, + 105.46971546342625, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.124047, + 12.284642578125, + -0.1854166666666663, + -2.290909090909091, + 2.290909090909091, + 105.46971546342625, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.144063, + 12.27207763671875, + -0.18645833333333298, + -2.290909090909091, + 2.290909090909091, + 105.46971546342625, + -57.62083197805496, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.16406, + 12.328619873046875, + -0.18645833333333298, + -2.303030303030303, + 2.303030303030303, + 105.46971546342625, + -57.61989686336666, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1085.184031, + 12.284642578125, + -0.18645833333333298, + -2.303030303030303, + 2.303030303030303, + 105.46971546342625, + -57.61989686336666, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1085.204079, + 12.290925048828125, + -0.18749999999999964, + -2.303030303030303, + 2.303030303030303, + 105.46971546342625, + -57.61989686336666, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.224067, + 12.328619873046875, + -0.18749999999999964, + -2.3151515151515154, + 2.3151515151515154, + 105.46971546342625, + -57.61989686336666, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.244059, + 12.27207763671875, + -0.1885416666666663, + -2.3151515151515154, + 2.3058162267839686, + 105.46878034873797, + -57.61989686336666, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.264082, + 12.347467285156249, + -0.1885416666666663, + -2.327272727272727, + 2.3178885630498534, + 105.46878034873797, + -57.61989686336666, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.284205, + 12.278360107421875, + -0.1885416666666663, + -2.3178885630498534, + 2.3178885630498534, + 105.46878034873797, + -57.61989686336666, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.304031, + 12.284642578125, + -0.18958333333333297, + -2.3178885630498534, + 2.3178885630498534, + 105.46878034873797, + -57.618961748678366, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1085.324099, + 12.328619873046875, + -0.18958333333333297, + -2.329960899315738, + 2.329960899315738, + 105.46878034873797, + -57.618961748678366, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1085.344096, + 12.278360107421875, + -0.18958333333333297, + -2.329960899315738, + 2.329960899315738, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.364038, + 12.284642578125, + -0.19062499999999963, + -2.329960899315738, + 2.329960899315738, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.384123, + 12.328619873046875, + -0.19062499999999963, + -2.3541055718475072, + 2.3541055718475072, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.404119, + 12.284642578125, + -0.1916666666666663, + -2.3541055718475072, + 2.3541055718475072, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.424116, + 12.27207763671875, + -0.1916666666666663, + -2.366177908113392, + 2.366177908113392, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.444148, + 12.3097724609375, + -0.1916666666666663, + -2.366177908113392, + 2.366177908113392, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.464092, + 12.278360107421875, + -0.19270833333333295, + -2.366177908113392, + 2.366177908113392, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.484088, + 12.341184814453124, + -0.19270833333333295, + -2.3782502443792763, + 2.3782502443792763, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.504084, + 12.278360107421875, + -0.19374999999999962, + -2.3782502443792763, + 2.3782502443792763, + 105.46878034873797, + -57.618961748678366, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.524109, + 12.278360107421875, + -0.19374999999999962, + -2.390322580645161, + 2.390322580645161, + 105.46878034873797, + -57.61802663399007, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.544077, + 12.32233740234375, + -0.19374999999999962, + -2.390322580645161, + 2.390322580645161, + 105.46878034873797, + -57.61802663399007, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.564071, + 12.278360107421875, + -0.19479166666666628, + -2.390322580645161, + 2.390322580645161, + 105.46878034873797, + -57.61802663399007, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.584246, + 12.265795166015625, + -0.19479166666666628, + -2.402394916911046, + 2.402394916911046, + 105.46878034873797, + -57.61802663399007, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.604106, + 12.334902343749999, + -0.19583333333333294, + -2.402394916911046, + 2.402394916911046, + 105.46878034873797, + -57.61802663399007, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.624085, + 12.284642578125, + -0.19583333333333294, + -2.4144672531769302, + 2.4144672531769302, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.644091, + 12.334902343749999, + -0.19583333333333294, + -2.4144672531769302, + 2.4144672531769302, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.664105, + 12.328619873046875, + -0.1968749999999996, + -2.4144672531769302, + 2.4144672531769302, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.684066, + 12.278360107421875, + -0.1968749999999996, + -2.426539589442815, + 2.426539589442815, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.704114, + 12.328619873046875, + -0.1968749999999996, + -2.426539589442815, + 2.426539589442815, + 105.46784523404966, + -57.61802663399007, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1085.72419, + 12.27207763671875, + -0.19791666666666627, + -2.426539589442815, + 2.4363636363636365, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.744054, + 12.27207763671875, + -0.19791666666666627, + -2.4386119257087, + 2.4484848484848483, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.76407, + 12.32233740234375, + -0.19895833333333293, + -2.4386119257087, + 2.4484848484848483, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.784062, + 12.24694775390625, + -0.19895833333333293, + -2.4506842619745846, + 2.4606060606060605, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.804108, + 12.253230224609375, + -0.19895833333333293, + -2.4506842619745846, + 2.4606060606060605, + 105.46784523404966, + -57.61802663399007, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.824141, + 12.3097724609375, + -0.1999999999999996, + -2.4506842619745846, + 2.4606060606060605, + 105.46784523404966, + -57.61709151930177, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.844055, + 12.24694775390625, + -0.1999999999999996, + -2.462756598240469, + 2.4727272727272727, + 105.46784523404966, + -57.61709151930177, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.864094, + 12.290925048828125, + -0.20104166666666626, + -2.462756598240469, + 2.4727272727272727, + 105.46784523404966, + -57.61709151930177, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.884073, + 12.29720751953125, + -0.20104166666666626, + -2.4748289345063537, + 2.484848484848485, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.904071, + 12.24694775390625, + -0.20104166666666626, + -2.4748289345063537, + 2.484848484848485, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1085.924072, + 12.284642578125, + -0.20208333333333292, + -2.4748289345063537, + 2.484848484848485, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1085.944042, + 12.2343828125, + -0.20208333333333292, + -2.4869012707722384, + 2.496969696969697, + 105.46691011936137, + -57.61709151930177, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1085.964093, + 12.24694775390625, + -0.20312499999999958, + -2.4869012707722384, + 2.496969696969697, + 105.46691011936137, + -57.61709151930177, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1085.984074, + 12.284642578125, + -0.20312499999999958, + -2.4989736070381228, + 2.509090909090909, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.004119, + 12.228100341796875, + -0.20312499999999958, + -2.4989736070381228, + 2.509090909090909, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.024096, + 12.2343828125, + -0.20416666666666625, + -2.4989736070381228, + 2.509090909090909, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.044362, + 12.32233740234375, + -0.20416666666666625, + -2.5110459433040075, + 2.5110459433040075, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.064095, + 12.2595126953125, + -0.2052083333333329, + -2.5110459433040075, + 2.5110459433040075, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.084087, + 12.3097724609375, + -0.2052083333333329, + -2.5231182795698928, + 2.5231182795698928, + 105.46691011936137, + -57.61709151930177, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.104072, + 12.278360107421875, + -0.2052083333333329, + -2.5231182795698928, + 2.5231182795698928, + 105.46691011936137, + -57.616156404613484, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.124129, + 12.228100341796875, + -0.20624999999999957, + -2.5231182795698928, + 2.5231182795698928, + 105.46691011936137, + -57.616156404613484, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.14407, + 12.29720751953125, + -0.20624999999999957, + -2.535190615835777, + 2.535190615835777, + 105.46691011936137, + -57.616156404613484, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.164051, + 12.228100341796875, + -0.20729166666666624, + -2.535190615835777, + 2.535190615835777, + 105.46691011936137, + -57.616156404613484, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.184107, + 12.22181787109375, + -0.20729166666666624, + -2.5593352883675466, + 2.5593352883675466, + 105.46691011936137, + -57.616156404613484, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.204091, + 12.27207763671875, + -0.20729166666666624, + -2.5593352883675466, + 2.5593352883675466, + 105.46597500467307, + -57.616156404613484, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.224129, + 12.2343828125, + -0.2083333333333329, + -2.5593352883675466, + 2.5593352883675466, + 105.46597500467307, + -57.616156404613484, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.244029, + 12.22181787109375, + -0.2083333333333329, + -2.571407624633431, + 2.571407624633431, + 105.46597500467307, + -57.616156404613484, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.264118, + 12.284642578125, + -0.2083333333333329, + -2.571407624633431, + 2.571407624633431, + 105.46597500467307, + -57.616156404613484, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1086.284069, + 12.2343828125, + -0.20937499999999956, + -2.571407624633431, + 2.571407624633431, + 105.46597500467307, + -57.616156404613484, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1086.304125, + 12.284642578125, + -0.20937499999999956, + -2.5834799608993158, + 2.5834799608993158, + 105.46597500467307, + -57.616156404613484, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.324113, + 12.2343828125, + -0.21041666666666622, + -2.5834799608993158, + 2.5834799608993158, + 105.46597500467307, + -57.61522128992519, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.34423, + 12.22181787109375, + -0.21041666666666622, + -2.5955522971652005, + 2.5955522971652005, + 105.46597500467307, + -57.61522128992519, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.364082, + 12.284642578125, + -0.21041666666666622, + -2.5955522971652005, + 2.5955522971652005, + 105.46597500467307, + -57.61522128992519, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.38407, + 12.228100341796875, + -0.2114583333333329, + -2.5955522971652005, + 2.5955522971652005, + 105.46503988998478, + -57.61522128992519, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.404056, + 12.240665283203125, + -0.2114583333333329, + -2.607624633431085, + 2.607624633431085, + 105.46503988998478, + -57.61522128992519, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.4241, + 12.284642578125, + -0.21249999999999955, + -2.607624633431085, + 2.607624633431085, + 105.46503988998478, + -57.61522128992519, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.444076, + 12.2343828125, + -0.21249999999999955, + -2.6196969696969696, + 2.6196969696969696, + 105.46503988998478, + -57.61522128992519, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1086.464081, + 12.2343828125, + -0.21249999999999955, + -2.6196969696969696, + 2.6196969696969696, + 105.46503988998478, + -57.61522128992519, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1086.484057, + 12.29720751953125, + -0.2135416666666662, + -2.6196969696969696, + 2.6196969696969696, + 105.46503988998478, + -57.61428617523689, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.504241, + 12.228100341796875, + -0.2135416666666662, + -2.6317693059628544, + 2.6317693059628544, + 105.46503988998478, + -57.61428617523689, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.524104, + 12.278360107421875, + -0.21458333333333288, + -2.6317693059628544, + 2.6317693059628544, + 105.46503988998478, + -57.61428617523689, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.544303, + 12.2343828125, + -0.21458333333333288, + -2.643841642228739, + 2.643841642228739, + 105.46503988998478, + -57.61428617523689, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.564084, + 12.240665283203125, + -0.21458333333333288, + -2.643841642228739, + 2.643841642228739, + 105.46410477529649, + -57.61428617523689, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.58409, + 12.278360107421875, + -0.21562499999999954, + -2.643841642228739, + 2.643841642228739, + 105.46410477529649, + -57.61428617523689, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.604116, + 12.228100341796875, + -0.21562499999999954, + -2.6559139784946235, + 2.6559139784946235, + 105.46410477529649, + -57.61428617523689, + 0.0, + 0.0, + 0.0 + ], + [ + 1086.624064, + 12.2343828125, + -0.2166666666666662, + -2.6559139784946235, + 2.6559139784946235, + 105.46410477529649, + -57.61428617523689, + -0.009351146882950868, + 0.0, + 0.0 + ], + [ + 1086.644144, + 12.284642578125, + -0.2166666666666662, + -2.6679863147605083, + 2.6679863147605083, + 105.46410477529649, + -57.613351060548595, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1086.664064, + 12.240665283203125, + -0.2166666666666662, + -2.6679863147605083, + 2.6679863147605083, + 105.46410477529649, + -57.613351060548595, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.684106, + 12.240665283203125, + -0.21770833333333287, + -2.6679863147605083, + 2.657184750733138, + 105.46316966060819, + -57.613351060548595, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.704302, + 12.278360107421875, + -0.21770833333333287, + -2.680058651026393, + 2.669208211143695, + 105.46316966060819, + -57.613351060548595, + 0.0, + 0.009351146882950868, + 0.0 + ], + [ + 1086.724058, + 12.228100341796875, + -0.21770833333333287, + -2.669208211143695, + 2.669208211143695, + 105.46316966060819, + -57.6124159458603, + 0.0, + 0.018702293765901736, + 0.0 + ], + [ + 1086.744107, + 12.278360107421875, + -0.21874999999999953, + -2.669208211143695, + 2.669208211143695, + 105.46316966060819, + -57.6124159458603, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1086.764107, + 12.22181787109375, + -0.21874999999999953, + -2.6812316715542526, + 2.6812316715542526, + 105.4622345459199, + -57.6124159458603, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1086.784104, + 12.228100341796875, + -0.2197916666666662, + -2.6812316715542526, + 2.6812316715542526, + 105.4622345459199, + -57.6124159458603, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1086.804091, + 12.284642578125, + -0.2197916666666662, + -2.6932551319648095, + 2.6932551319648095, + 105.4622345459199, + -57.611480831172, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1086.824074, + 12.22181787109375, + -0.2197916666666662, + -2.6932551319648095, + 2.6932551319648095, + 105.4622345459199, + -57.611480831172, + -0.009351146882950868, + 0.009351146882950868, + 0.0 + ], + [ + 1086.844073, + 12.253230224609375, + -0.22083333333333285, + -2.6932551319648095, + 2.6823069403714563, + 105.4612994312316, + -57.61054571648371, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1086.86411, + 12.290925048828125, + -0.22083333333333285, + -2.705278592375367, + 2.6942815249266863, + 105.4612994312316, + -57.61054571648371, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1086.884039, + 12.22181787109375, + -0.22187499999999952, + -2.705278592375367, + 2.6942815249266863, + 105.4612994312316, + -57.60961060179542, + -0.009351146882950868, + 0.02805344064885261, + 0.0 + ], + [ + 1086.904074, + 12.22181787109375, + -0.22187499999999952, + -2.7173020527859237, + 2.7062561094819158, + 105.4612994312316, + -57.60961060179542, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1086.924098, + 12.278360107421875, + -0.22187499999999952, + -2.7173020527859237, + 2.7062561094819158, + 105.4603643165433, + -57.60867548710712, + -0.009351146882950868, + 0.02805344064885261, + 0.0 + ], + [ + 1086.944024, + 12.202970458984375, + -0.22291666666666618, + -2.7173020527859237, + 2.7062561094819158, + 105.45942920185502, + -57.60867548710712, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1086.964036, + 12.2595126953125, + -0.22291666666666618, + -2.7413489736070384, + 2.730205278592375, + 105.45942920185502, + -57.60867548710712, + -0.009351146882950868, + 0.018702293765901736, + 0.0 + ], + [ + 1086.985293, + 12.228100341796875, + -0.22395833333333284, + -2.7413489736070384, + 2.730205278592375, + 105.45942920185502, + -57.607740372418824, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.004227, + 12.202970458984375, + -0.22395833333333284, + -2.7533724340175953, + 2.742179863147605, + 105.45942920185502, + -57.607740372418824, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.024127, + 12.228100341796875, + -0.22395833333333284, + -2.7533724340175953, + 2.742179863147605, + 105.45849408716671, + -57.60680525773053, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.044089, + 12.202970458984375, + -0.2249999999999995, + -2.7533724340175953, + 2.742179863147605, + 105.45755897247842, + -57.60680525773053, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.064126, + 12.190405517578125, + -0.2249999999999995, + -2.7653958944281527, + 2.7541544477028346, + 105.45755897247842, + -57.60587014304224, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.084159, + 12.24694775390625, + -0.22604166666666617, + -2.7653958944281527, + 2.7541544477028346, + 105.45662385779012, + -57.60587014304224, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.104112, + 12.190405517578125, + -0.22604166666666617, + -2.7774193548387096, + 2.7661290322580645, + 105.45662385779012, + -57.60493502835394, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.124069, + 12.177840576171874, + -0.22604166666666617, + -2.7774193548387096, + 2.7661290322580645, + 105.45568874310183, + -57.60493502835394, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.144108, + 12.22181787109375, + -0.22708333333333283, + -2.7774193548387096, + 2.7661290322580645, + 105.45568874310183, + -57.603999913665646, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.164109, + 12.177840576171874, + -0.22708333333333283, + -2.789442815249267, + 2.789442815249267, + 105.45568874310183, + -57.603999913665646, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.184075, + 12.22181787109375, + -0.22708333333333283, + -2.789442815249267, + 2.789442815249267, + 105.45475362841353, + -57.60306479897735, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.204068, + 12.2092529296875, + -0.2281249999999995, + -2.778103616813294, + 2.789442815249267, + 105.45475362841353, + -57.60306479897735, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.224162, + 12.177840576171874, + -0.2281249999999995, + -2.790078201368524, + 2.8014662756598243, + 105.45381851372524, + -57.602129684289054, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.244052, + 12.240665283203125, + -0.22916666666666616, + -2.790078201368524, + 2.8014662756598243, + 105.45381851372524, + -57.602129684289054, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.264061, + 12.184123046875, + -0.22916666666666616, + -2.8020527859237534, + 2.813489736070381, + 105.45288339903695, + -57.60119456960076, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.28405, + 12.190405517578125, + -0.22916666666666616, + -2.8020527859237534, + 2.813489736070381, + 105.45288339903695, + -57.60119456960076, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.304061, + 12.240665283203125, + -0.23020833333333282, + -2.8020527859237534, + 2.813489736070381, + 105.45194828434865, + -57.60025945491247, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.32411, + 12.190405517578125, + -0.23020833333333282, + -2.8140273704789833, + 2.8255131964809386, + 105.45101316966036, + -57.60025945491247, + -0.018702293765901736, + 0.018702293765901736, + 0.0 + ], + [ + 1087.344076, + 12.17155810546875, + -0.23124999999999948, + -2.8140273704789833, + 2.8255131964809386, + 105.45101316966036, + -57.59932434022417, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.364078, + 12.215535400390625, + -0.23124999999999948, + -2.826001955034213, + 2.8375366568914955, + 105.45007805497205, + -57.598389225535875, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.384078, + 12.14642822265625, + -0.23124999999999948, + -2.826001955034213, + 2.8375366568914955, + 105.44914294028376, + -57.598389225535875, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.404062, + 12.228100341796875, + -0.23229166666666615, + -2.826001955034213, + 2.8375366568914955, + 105.44914294028376, + -57.59745411084758, + -0.018702293765901736, + 0.02805344064885261, + 0.0 + ], + [ + 1087.424056, + 12.13386328125, + -0.23229166666666615, + -2.8379765395894427, + 2.849560117302053, + 105.44820782559547, + -57.59651899615928, + -0.018702293765901736, + 0.03740458753180347, + 0.0 + ], + [ + 1087.444062, + 12.14642822265625, + -0.2333333333333328, + -2.8379765395894427, + 2.849560117302053, + 105.44727271090717, + -57.5946487667827, + -0.018702293765901736, + 0.04675573441475434, + 0.0 + ], + [ + 1087.4641, + 12.202970458984375, + -0.2333333333333328, + -2.849951124144672, + 2.86158357771261, + 105.44633759621888, + -57.5937136520944, + -0.02805344064885261, + 0.04675573441475434, + 0.0 + ], + [ + 1087.484075, + 12.152710693359374, + -0.2333333333333328, + -2.849951124144672, + 2.849951124144672, + 105.44540248153058, + -57.59184342271781, + -0.02805344064885261, + 0.06545802818065607, + 0.0 + ], + [ + 1087.505482, + 12.17155810546875, + -0.23437499999999947, + -2.849951124144672, + 2.849951124144672, + 105.443532252154, + -57.59090830802951, + -0.03740458753180347, + 0.06545802818065607, + 0.0 + ], + [ + 1087.524081, + 12.215535400390625, + -0.23437499999999947, + -2.861925708699902, + 2.861925708699902, + 105.443532252154, + -57.59090830802951, + -0.03740458753180347, + 0.06545802818065607, + 0.0 + ], + [ + 1087.544072, + 12.165275634765624, + -0.23437499999999947, + -2.861925708699902, + 2.861925708699902, + 105.4407269080891, + -57.587167849276334, + -0.05610688129770522, + 0.07480917506360694, + 0.0 + ], + [ + 1087.564077, + 12.177840576171874, + -0.23541666666666614, + -2.861925708699902, + 2.861925708699902, + 105.43885667871251, + -57.58623273458804, + -0.06545802818065607, + 0.07480917506360694, + 0.0 + ], + [ + 1087.584106, + 12.22181787109375, + -0.23541666666666614, + -2.873900293255132, + 2.873900293255132, + 105.43698644933593, + -57.58436250521145, + -0.06545802818065607, + 0.07480917506360694, + 0.0 + ], + [ + 1087.604106, + 12.177840576171874, + -0.2364583333333328, + -2.873900293255132, + 2.873900293255132, + 105.43511621995934, + -57.583427390523156, + -0.07480917506360694, + 0.07480917506360694, + 0.0 + ], + [ + 1087.624135, + 12.2343828125, + -0.2364583333333328, + -2.885874877810362, + 2.885874877810362, + 105.43418110527104, + -57.58155716114656, + -0.07480917506360694, + 0.07480917506360694, + 0.0 + ], + [ + 1087.644102, + 12.165275634765624, + -0.2364583333333328, + -2.885874877810362, + 2.885874877810362, + 105.43231087589446, + -57.58062204645827, + -0.07480917506360694, + 0.06545802818065607, + 0.0 + ], + [ + 1087.664136, + 12.1589931640625, + -0.23749999999999946, + -2.885874877810362, + 2.885874877810362, + 105.43137576120616, + -57.57968693176997, + -0.07480917506360694, + 0.06545802818065607, + 0.0 + ], + [ + 1087.68409, + 12.22181787109375, + -0.23749999999999946, + -2.8978494623655915, + 2.8978494623655915, + 105.43044064651787, + -57.577816702393385, + -0.07480917506360694, + 0.05610688129770522, + 0.0 + ], + [ + 1087.704068, + 12.165275634765624, + -0.23854166666666612, + -2.8978494623655915, + 2.8978494623655915, + 105.42950553182956, + -57.57688158770509, + -0.06545802818065607, + 0.06545802818065607, + 0.0 + ], + [ + 1087.724203, + 12.152710693359374, + -0.23854166666666612, + -2.921798631476051, + 2.921798631476051, + 105.42857041714127, + -57.57594647301679, + -0.05610688129770522, + 0.05610688129770522, + 0.0 + ], + [ + 1087.744044, + 12.228100341796875, + -0.23854166666666612, + -2.921798631476051, + 2.921798631476051, + 105.42857041714127, + -57.575011358328496, + -0.04675573441475434, + 0.05610688129770522, + 0.0 + ], + [ + 1087.764091, + 12.1589931640625, + -0.2395833333333328, + -2.921798631476051, + 2.921798631476051, + 105.42763530245298, + -57.5740762436402, + -0.04675573441475434, + 0.05610688129770522, + 0.0 + ], + [ + 1087.78407, + 12.215535400390625, + -0.2395833333333328, + -2.933773216031281, + 2.933773216031281, + 105.42670018776468, + -57.57314112895191, + -0.03740458753180347, + 0.04675573441475434, + 0.0 + ], + [ + 1087.804109, + 12.215535400390625, + -0.24062499999999945, + -2.933773216031281, + 2.933773216031281, + 105.42576507307639, + -57.57314112895191, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1087.824151, + 12.152710693359374, + -0.24062499999999945, + -2.9457478005865103, + 2.9457478005865103, + 105.42576507307639, + -57.572206014263614, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1087.844045, + 12.19668798828125, + -0.24062499999999945, + -2.9337243401759534, + 2.9457478005865103, + 105.42482995838809, + -57.57127089957532, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1087.864256, + 12.17155810546875, + -0.2416666666666661, + -2.9337243401759534, + 2.9457478005865103, + 105.42482995838809, + -57.57033578488702, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1087.884126, + 12.140145751953124, + -0.2416666666666661, + -2.9456500488758555, + 2.9577223851417402, + 105.4238948436998, + -57.569400670198725, + -0.02805344064885261, + 0.03740458753180347, + 0.0 + ], + [ + 1087.904065, + 12.177840576171874, + -0.24270833333333278, + -2.9456500488758555, + 2.9577223851417402, + 105.4229597290115, + -57.56846555551043, + -0.02805344064885261, + 0.04675573441475434, + 0.0 + ], + [ + 1087.924086, + 12.13386328125, + -0.24270833333333278, + -2.957575757575758, + 2.9696969696969697, + 105.4220246143232, + -57.56753044082214, + -0.02805344064885261, + 0.04675573441475434, + 0.0 + ], + [ + 1087.944194, + 12.152710693359374, + -0.24270833333333278, + -2.957575757575758, + 2.9696969696969697, + 105.42108949963492, + -57.56659532613384, + -0.02805344064885261, + 0.04675573441475434, + 0.0 + ], + [ + 1087.964342, + 12.190405517578125, + -0.24374999999999944, + -2.957575757575758, + 2.9696969696969697, + 105.42015438494661, + -57.56566021144555, + -0.02805344064885261, + 0.04675573441475434, + 0.0 + ], + [ + 1087.984094, + 12.127580810546874, + -0.24374999999999944, + -2.96950146627566, + 2.9816715542521997, + 105.41921927025832, + -57.563789982068954, + -0.03740458753180347, + 0.05610688129770522, + 0.0 + ], + [ + 1088.004072, + 12.190405517578125, + -0.24374999999999944, + -2.96950146627566, + 2.9816715542521997, + 105.41828415557002, + -57.562854867380665, + -0.03740458753180347, + 0.05610688129770522, + 0.0 + ], + [ + 1088.024117, + 12.19668798828125, + -0.2447916666666661, + -2.96950146627566, + 2.9816715542521997, + 105.41641392619344, + -57.56098463800407, + -0.03740458753180347, + 0.06545802818065607, + 0.0 + ], + [ + 1088.044158, + 12.1589931640625, + -0.2447916666666661, + -2.9814271749755625, + 2.993646138807429, + 105.41547881150514, + -57.560049523315776, + -0.04675573441475434, + 0.06545802818065607, + 0.0 + ], + [ + 1088.064079, + 12.190405517578125, + -0.24583333333333277, + -2.9814271749755625, + 2.993646138807429, + 105.41360858212855, + -57.55911440862748, + -0.05610688129770522, + 0.06545802818065607, + 0.0 + ], + [ + 1088.084059, + 12.108733398437499, + -0.24583333333333277, + -2.9933528836754646, + 3.005620723362659, + 105.41173835275195, + -57.55817929393918, + -0.05610688129770522, + 0.05610688129770522, + 0.0 + ], + [ + 1088.104081, + 12.108733398437499, + -0.24583333333333277, + -2.9933528836754646, + 3.005620723362659, + 105.41080323806366, + -57.557244179250894, + -0.06545802818065607, + 0.05610688129770522, + 0.0 + ], + [ + 1088.124119, + 12.14642822265625, + -0.24687499999999943, + -2.9933528836754646, + 2.9933528836754646, + 105.40893300868707, + -57.5553739498743, + -0.06545802818065607, + 0.05610688129770522, + 0.0 + ], + [ + 1088.144102, + 12.071038574218749, + -0.24687499999999943, + -3.0052785923753667, + 3.0052785923753667, + 105.40799789399878, + -57.55350372049771, + -0.06545802818065607, + 0.06545802818065607, + 0.0 + ], + [ + 1088.164084, + 12.064756103515625, + -0.2479166666666661, + -3.0052785923753667, + 3.0052785923753667, + 105.40706277931048, + -57.55163349112112, + -0.06545802818065607, + 0.07480917506360694, + 0.0 + ], + [ + 1088.184225, + 12.17155810546875, + -0.2479166666666661, + -3.017204301075269, + 3.017204301075269, + 105.4051925499339, + -57.54976326174453, + -0.06545802818065607, + 0.08416032194655781, + 0.0 + ], + [ + 1088.20407, + 12.071038574218749, + -0.2479166666666661, + -3.017204301075269, + 3.017204301075269, + 105.40332232055731, + -57.54789303236794, + -0.06545802818065607, + 0.09351146882950868, + 0.0 + ], + [ + 1088.224057, + 12.127580810546874, + -0.24895833333333275, + -3.017204301075269, + 3.017204301075269, + 105.40145209118072, + -57.54602280299135, + -0.06545802818065607, + 0.09351146882950868, + 0.0 + ], + [ + 1088.244114, + 12.127580810546874, + -0.24895833333333275, + -3.029130009775171, + 3.029130009775171, + 105.39958186180412, + -57.54415257361476, + -0.06545802818065607, + 0.09351146882950868, + 0.0 + ], + [ + 1088.264156, + 12.083603515624999, + -0.24999999999999942, + -3.029130009775171, + 3.029130009775171, + 105.39677651773924, + -57.54134722954988, + -0.07480917506360694, + 0.10286261571245955, + 0.0 + ], + [ + 1088.284069, + 12.140145751953124, + -0.24999999999999942, + -3.0410557184750737, + 3.028592375366569, + 105.39397117367436, + -57.539477000173285, + -0.08416032194655781, + 0.10286261571245955, + 0.0 + ], + [ + 1088.304087, + 12.089885986328124, + -0.24999999999999942, + -3.0410557184750737, + 3.028592375366569, + 105.39210094429777, + -57.536671656108396, + -0.09351146882950868, + 0.11221376259541044, + 0.0 + ], + [ + 1088.324236, + 12.102450927734374, + -0.2510416666666661, + -3.0410557184750737, + 3.028592375366569, + 105.39023071492117, + -57.53480142673181, + -0.10286261571245955, + 0.11221376259541044, + 0.0 + ], + [ + 1088.344096, + 12.13386328125, + -0.2510416666666661, + -3.052981427174976, + 3.0404692082111437, + 105.38742537085629, + -57.53199608266692, + -0.11221376259541044, + 0.1215649094783613, + 0.0 + ], + [ + 1088.364059, + 12.077321044921874, + -0.2510416666666661, + -3.052981427174976, + 3.0404692082111437, + 105.3855551414797, + -57.530125853290336, + -0.11221376259541044, + 0.11221376259541044, + 0.0 + ], + [ + 1088.384075, + 12.096168457031249, + -0.25208333333333277, + -3.052981427174976, + 3.0404692082111437, + 105.3836849121031, + -57.52825562391374, + -0.10286261571245955, + 0.11221376259541044, + 0.0 + ], + [ + 1088.40405, + 12.140145751953124, + -0.25208333333333277, + -3.0649071358748783, + 3.0523460410557184, + 105.38274979741482, + -57.52638539453715, + -0.10286261571245955, + 0.10286261571245955, + 0.0 + ], + [ + 1088.42407, + 12.108733398437499, + -0.25312499999999943, + -3.0649071358748783, + 3.0523460410557184, + 105.38087956803822, + -57.524515165160565, + -0.09351146882950868, + 0.10286261571245955, + 0.0 + ], + [ + 1088.444071, + 12.152710693359374, + -0.25312499999999943, + -3.0768328445747803, + 3.089442815249267, + 105.37900933866163, + -57.52264493578397, + -0.09351146882950868, + 0.09351146882950868, + 0.0 + ], + [ + 1088.464245, + 12.13386328125, + -0.25312499999999943, + -3.0768328445747803, + 3.089442815249267, + 105.37807422397334, + -57.521709821095676, + -0.08416032194655781, + 0.08416032194655781, + 0.0 + ], + [ + 1088.484064, + 12.102450927734374, + -0.2541666666666661, + -3.0768328445747803, + 3.089442815249267, + 105.37620399459675, + -57.52077470640738, + -0.07480917506360694, + 0.07480917506360694, + 0.0 + ], + [ + 1088.504099, + 12.127580810546874, + -0.2541666666666661, + -3.100684261974585, + 3.113391984359726, + 105.37526887990845, + -57.518904477030794, + -0.07480917506360694, + 0.07480917506360694, + 0.0 + ], + [ + 1088.52417, + 12.064756103515625, + -0.25520833333333276, + -3.100684261974585, + 3.113391984359726, + 105.37339865053187, + -57.5170342476542, + -0.06545802818065607, + 0.07480917506360694, + 0.0 + ], + [ + 1088.544219, + 12.077321044921874, + -0.25520833333333276, + -3.112609970674487, + 3.125366568914956, + 105.37152842115528, + -57.51516401827761, + -0.06545802818065607, + 0.07480917506360694, + 0.0 + ], + [ + 1088.56407, + 12.140145751953124, + -0.25520833333333276, + -3.112609970674487, + 3.125366568914956, + 105.37059330646697, + -57.513293788901024, + -0.06545802818065607, + 0.08416032194655781, + 0.0 + ], + [ + 1088.584087, + 12.108733398437499, + -0.2562499999999994, + -3.112609970674487, + 3.125366568914956, + 105.36872307709038, + -57.510488444836135, + -0.07480917506360694, + 0.10286261571245955, + 0.0 + ], + [ + 1088.604245, + 12.064756103515625, + -0.2562499999999994, + -3.1245356793743895, + 3.1117302052785925, + 105.3659177330255, + -57.50861821545955, + -0.07480917506360694, + 0.10286261571245955, + 0.0 + ], + [ + 1088.624104, + 12.14642822265625, + -0.2572916666666661, + -3.1245356793743895, + 3.1117302052785925, + 105.36311238896062, + -57.50581287139466, + -0.08416032194655781, + 0.11221376259541044, + 0.0 + ], + [ + 1088.645693, + 12.108733398437499, + -0.2572916666666661, + -3.1364613880742915, + 3.123607038123167, + 105.36030704489573, + -57.50300752732978, + -0.09351146882950868, + 0.1215649094783613, + 0.0 + ], + [ + 1088.664077, + 12.14642822265625, + -0.2572916666666661, + -3.1364613880742915, + 3.123607038123167, + 105.36030704489573, + -57.50300752732978, + -0.09351146882950868, + 0.1215649094783613, + 0.0 + ], + [ + 1088.684057, + 12.140145751953124, + -0.25833333333333275, + -3.1364613880742915, + 3.123607038123167, + 105.35376124207767, + -57.49646172451171, + -0.1215649094783613, + 0.14026720324426303, + 0.0 + ], + [ + 1088.704099, + 12.077321044921874, + -0.25833333333333275, + -3.1483870967741936, + 3.1354838709677417, + 105.35002078332448, + -57.49272126575853, + -0.14026720324426303, + 0.1496183501272139, + 0.0 + ], + [ + 1088.724434, + 12.089885986328124, + -0.2593749999999994, + -3.1483870967741936, + 3.1354838709677417, + 105.345345209883, + -57.48898080700535, + -0.1496183501272139, + 0.16832064389311563, + 0.0 + ], + [ + 1088.74415, + 12.052191162109375, + -0.2593749999999994, + -3.160312805474096, + 3.147360703812317, + 105.34160475112984, + -57.48898080700535, + -0.16832064389311563, + 0.16832064389311563, + 0.0 + ], + [ + 1088.764117, + 12.064756103515625, + -0.2593749999999994, + -3.160312805474096, + 3.1344086021505375, + 105.33692917768835, + -57.48524034825217, + -0.1776717907760665, + 0.18702293765901737, + 0.0 + ], + [ + 1088.784114, + 12.108733398437499, + -0.2604166666666661, + -3.160312805474096, + 3.1344086021505375, + 105.33225360424687, + -57.480564774810695, + -0.18702293765901737, + 0.19637408454196825, + 0.0 + ], + [ + 1088.804075, + 12.064756103515625, + -0.2604166666666661, + -3.1462365591397847, + 3.1462365591397847, + 105.3275780308054, + -57.46840828386286, + -0.19637408454196825, + 0.2431298189567226, + 0.0 + ], + [ + 1088.824088, + 12.077321044921874, + -0.2604166666666661, + -3.1462365591397847, + 3.1462365591397847, + 105.32196734267563, + -57.46186248104479, + -0.21507637830786996, + 0.27118325960557516, + 0.0 + ], + [ + 1088.844063, + 12.14642822265625, + -0.26145833333333274, + -3.1462365591397847, + 3.1462365591397847, + 105.31542153985757, + -57.45531667822673, + -0.22442752519082088, + 0.2992367002544278, + 0.0 + ], + [ + 1088.864049, + 12.0584736328125, + -0.26145833333333274, + -3.158064516129032, + 3.158064516129032, + 105.30794062235121, + -57.445965531343774, + -0.25248096583967344, + 0.34599243466918217, + 0.0 + ], + [ + 1088.884043, + 12.121298339843749, + -0.2624999999999994, + -3.158064516129032, + 3.158064516129032, + 105.30045970484484, + -57.436614384460825, + -0.27118325960557516, + 0.3833970222009856, + 0.0 + ], + [ + 1088.904035, + 12.115015869140624, + -0.2624999999999994, + -3.169892473118279, + 3.169892473118279, + 105.2920436726502, + -57.42539300820128, + -0.2992367002544278, + 0.43015275661573993, + 0.0 + ], + [ + 1088.92409, + 12.0584736328125, + -0.2624999999999994, + -3.169892473118279, + 3.169892473118279, + 105.28362764045553, + -57.413236517253445, + -0.32729014090328035, + 0.4862596379134452, + 0.0 + ], + [ + 1088.944078, + 12.13386328125, + -0.26354166666666606, + -3.169892473118279, + 3.169892473118279, + 105.27521160826088, + -57.4020151409939, + -0.355343581552133, + 0.5330153723281995, + 0.0 + ], + [ + 1088.9641, + 12.077321044921874, + -0.26354166666666606, + -3.181720430107527, + 3.181720430107527, + 105.26492534668964, + -57.38798842066948, + -0.3833970222009856, + 0.5797711067429538, + 0.0 + ], + [ + 1088.984092, + 12.0584736328125, + -0.2645833333333327, + -3.181720430107527, + 3.181720430107527, + 105.2537039704301, + -57.374896815033345, + -0.4114504628498382, + 0.6171756942747574, + 0.0 + ], + [ + 1089.004065, + 12.096168457031249, + -0.2645833333333327, + -3.193548387096774, + 3.193548387096774, + 105.24154747948225, + -57.359934980020626, + -0.43950390349869084, + 0.6545802818065607, + 0.0 + ], + [ + 1089.024285, + 12.083603515624999, + -0.2645833333333327, + -3.193548387096774, + 3.193548387096774, + 105.22752075915783, + -57.34403803031961, + -0.4769084910304943, + 0.6919848693383643, + 0.0 + ], + [ + 1089.044075, + 12.04590869140625, + -0.2656249999999994, + -3.193548387096774, + 3.193548387096774, + 105.21255892414511, + -57.32907619530689, + -0.5236642254452486, + 0.7293894568701677, + 0.0 + ], + [ + 1089.064052, + 12.102450927734374, + -0.2656249999999994, + -3.2053763440860212, + 3.2053763440860212, + 105.19759708913239, + -57.31130901622928, + -0.5797711067429538, + 0.7667940444019712, + 0.0 + ], + [ + 1089.084051, + 12.077321044921874, + -0.26666666666666605, + -3.2053763440860212, + 3.2053763440860212, + 105.18076502474307, + -57.29447695183997, + -0.6358779880406591, + 0.8041986319337747, + 0.0 + ], + [ + 1089.104114, + 12.108733398437499, + -0.26666666666666605, + -3.2172043010752684, + 3.2172043010752684, + 105.16299784566547, + -57.27858000213895, + -0.6919848693383643, + 0.8135497788167255, + 0.0 + ], + [ + 1089.124068, + 12.089885986328124, + -0.26666666666666605, + -3.2172043010752684, + 3.2172043010752684, + 105.14429555189956, + -57.262683052437936, + -0.7480917506360695, + 0.8135497788167255, + 0.0 + ], + [ + 1089.144041, + 12.03334375, + -0.2677083333333327, + -3.2172043010752684, + 3.2172043010752684, + 105.12465814344537, + -57.244915873360334, + -0.7948474850508238, + 0.8416032194655781, + 0.0 + ], + [ + 1089.164042, + 12.071038574218749, + -0.2677083333333327, + -3.2290322580645157, + 3.2290322580645157, + 105.10502073499117, + -57.22527846490613, + -0.8416032194655781, + 0.8696566601144308, + 0.0 + ], + [ + 1089.184124, + 12.052191162109375, + -0.2677083333333327, + -3.2290322580645157, + 3.2290322580645157, + 105.08444821184868, + -57.203770827075346, + -0.8883589538803326, + 0.9070612476462342, + 0.0 + ], + [ + 1089.204169, + 12.03334375, + -0.2687499999999994, + -3.2290322580645157, + 3.2290322580645157, + 105.06387568870619, + -57.18132807455627, + -0.9351146882950868, + 0.9725192758268904, + 0.0 + ], + [ + 1089.224077, + 12.096168457031249, + -0.2687499999999994, + -3.2408602150537633, + 3.2408602150537633, + 105.0433031655637, + -57.158885322037186, + -0.9725192758268904, + 1.0379773040075464, + 0.0 + ], + [ + 1089.244105, + 12.02077880859375, + -0.26979166666666604, + -3.2408602150537633, + 3.2408602150537633, + 105.02086041304462, + -57.1364425695181, + -1.000572716475743, + 1.0847330384223006, + 0.0 + ], + [ + 1089.26407, + 12.027061279296875, + -0.26979166666666604, + -3.2526881720430105, + 3.2526881720430105, + 104.99935277521382, + -57.11119447293414, + -1.0192750102416446, + 1.131488772837055, + 0.0 + ], + [ + 1089.284054, + 12.064756103515625, + -0.26979166666666604, + -3.2526881720430105, + 3.2526881720430105, + 104.97784513738304, + -57.08781660572676, + -1.0379773040075464, + 1.1595422134859077, + 0.0 + ], + [ + 1089.304097, + 12.014496337890625, + -0.2708333333333327, + -3.2526881720430105, + 3.2526881720430105, + 104.95353215548737, + -57.0606982797662, + -1.0566795977734482, + 1.215649094783613, + 0.0 + ], + [ + 1089.324126, + 12.03334375, + -0.2708333333333327, + -3.276344086021505, + 3.276344086021505, + 104.93015428828, + -57.03170972442905, + -1.0753818915393498, + 1.2717559760813182, + 0.0 + ], + [ + 1089.344023, + 12.014496337890625, + -0.2708333333333327, + -3.276344086021505, + 3.276344086021505, + 104.9067764210726, + -57.00459139846849, + -1.1034353321882024, + 1.3185117104960726, + 0.0 + ], + [ + 1089.364077, + 11.97051904296875, + -0.27187499999999937, + -3.276344086021505, + 3.276344086021505, + 104.88152832448864, + -56.97840818719623, + -1.131488772837055, + 1.3278628573790232, + 0.0 + ], + [ + 1089.384067, + 12.027061279296875, + -0.27187499999999937, + -3.288172043010752, + 3.288172043010752, + 104.85440999852808, + -56.95128986123567, + -1.1595422134859077, + 1.3652674449108269, + 0.0 + ], + [ + 1089.404059, + 11.989366455078125, + -0.27291666666666603, + -3.288172043010752, + 3.288172043010752, + 104.82729167256753, + -56.924171535275114, + -1.1969468010177111, + 1.355916298027876, + 0.0 + ], + [ + 1089.424031, + 12.027061279296875, + -0.27291666666666603, + -3.3, + 3.3, + 104.79736800254209, + -56.894247865249675, + -1.2437025354324653, + 1.3746185917937774, + 0.0 + ], + [ + 1089.444101, + 12.03334375, + -0.27291666666666603, + -3.3, + 3.3, + 104.76837944720494, + -56.861518851159346, + -1.2904582698472198, + 1.421374326208532, + 0.0 + ], + [ + 1089.464105, + 12.027061279296875, + -0.2739583333333327, + -3.3, + 3.3, + 104.7375206624912, + -56.82972495175731, + -1.346565151144925, + 1.4868323543891881, + 0.0 + ], + [ + 1089.484052, + 12.039626220703125, + -0.2739583333333327, + -3.311827956989247, + 3.311827956989247, + 104.70853210715406, + -56.79793105235528, + -1.3933208855596793, + 1.5335880888039424, + 0.0 + ], + [ + 1089.504104, + 12.052191162109375, + -0.27499999999999936, + -3.311827956989247, + 3.311827956989247, + 104.67860843712862, + -56.76520203826495, + -1.440076619974434, + 1.5990461169845984, + 0.0 + ], + [ + 1089.524048, + 12.0082138671875, + -0.27499999999999936, + -3.3236559139784942, + 3.3236559139784942, + 104.64774965241487, + -56.734343253551216, + -1.4681300606232863, + 1.6083972638675494, + 0.0 + ], + [ + 1089.544093, + 12.0584736328125, + -0.27499999999999936, + -3.3236559139784942, + 3.3236559139784942, + 104.61595575301284, + -56.70348446883747, + -1.4868323543891881, + 1.5803438232186968, + 0.0 + ], + [ + 1089.564096, + 12.001931396484375, + -0.276041666666666, + -3.3236559139784942, + 3.309921798631476, + 104.58135650954593, + -56.67262568412374, + -1.5148857950380408, + 1.570992676335746, + 0.0 + ], + [ + 1089.584221, + 12.014496337890625, + -0.276041666666666, + -3.3354838709677415, + 3.321700879765396, + 104.5476923807673, + -56.63989667003341, + -1.5429392356868932, + 1.5803438232186968, + 0.0 + ], + [ + 1089.604069, + 12.064756103515625, + -0.2770833333333327, + -3.3354838709677415, + 3.321700879765396, + 104.51402825198868, + -56.608102770631376, + -1.5803438232186968, + 1.570992676335746, + 0.0 + ], + [ + 1089.624067, + 12.014496337890625, + -0.2770833333333327, + -3.3473118279569887, + 3.3334799608993158, + 104.47662366445688, + -56.57069818309957, + -1.6177484107505002, + 1.627099557633451, + 0.0 + ], + [ + 1089.644042, + 12.039626220703125, + -0.2770833333333327, + -3.3473118279569887, + 3.3334799608993158, + 104.44108930630166, + -56.53235848087947, + -1.6645041451652545, + 1.7206110264629597, + 0.0 + ], + [ + 1089.664105, + 12.052191162109375, + -0.27812499999999934, + -3.3473118279569887, + 3.3334799608993158, + 104.40368471876985, + -56.490278319906196, + -1.711259879580009, + 1.8328247890583702, + 0.0 + ], + [ + 1089.684131, + 12.014496337890625, + -0.27812499999999934, + -3.3591397849462363, + 3.3452590420332355, + 104.36815036061465, + -56.45287373237439, + -1.7486644671118123, + 1.8702293765901736, + 0.0 + ], + [ + 1089.704036, + 12.03334375, + -0.27812499999999934, + -3.3591397849462363, + 3.3452590420332355, + 104.33261600245943, + -56.41733937421918, + -1.7767179077606652, + 1.9076339641219773, + 0.0 + ], + [ + 1089.724085, + 12.052191162109375, + -0.279166666666666, + -3.3591397849462363, + 3.3452590420332355, + 104.29427630023933, + -56.37993478668738, + -1.795420201526567, + 1.9076339641219773, + 0.0 + ], + [ + 1089.744112, + 12.027061279296875, + -0.279166666666666, + -3.3709677419354835, + 3.3570381231671553, + 104.25406636864264, + -56.33878974040239, + -1.8141224952924684, + 1.926336257887879, + 0.0 + ], + [ + 1089.764084, + 12.03334375, + -0.28020833333333267, + -3.3709677419354835, + 3.3570381231671553, + 104.21292132235766, + -56.295774464740816, + -1.8515270828242718, + 1.9450385516537807, + 0.0 + ], + [ + 1089.784063, + 12.039626220703125, + -0.28020833333333267, + -3.3827956989247308, + 3.368817204301075, + 104.17177627607268, + -56.249018730326064, + -1.8889316703560755, + 2.038550020483289, + 0.0 + ], + [ + 1089.804598, + 11.939106689453125, + -0.28020833333333267, + -3.3827956989247308, + 3.368817204301075, + 104.12969611509939, + -56.20226299591131, + -1.9356874047708297, + 2.141412636195749, + 0.0 + ], + [ + 1089.824091, + 12.102450927734374, + -0.28124999999999933, + -3.3827956989247308, + 3.368817204301075, + 104.12969611509939, + -56.20226299591131, + -1.9356874047708297, + 2.141412636195749, + 0.0 + ], + [ + 1089.844082, + 12.001931396484375, + -0.28124999999999933, + -3.394623655913978, + 3.380596285434995, + 104.08761595412612, + -56.157377490873145, + -1.982443139185584, + 2.2349241050252573, + 0.0 + ], + [ + 1089.864124, + 12.001931396484375, + -0.282291666666666, + -3.394623655913978, + 3.380596285434995, + 104.00345563217957, + -56.074152283614886, + -2.057252314249191, + 2.206870664376405, + 0.0 + ], + [ + 1089.884103, + 12.052191162109375, + -0.282291666666666, + -3.406451612903225, + 3.406451612903225, + 103.96044035651799, + -56.02739654920013, + -2.075954608015093, + 2.2255729581423065, + 0.0 + ], + [ + 1089.904178, + 11.99564892578125, + -0.282291666666666, + -3.406451612903225, + 3.406451612903225, + 103.91181439272664, + -55.9759652413439, + -2.104008048663945, + 2.272328692557061, + 0.0 + ], + [ + 1089.924077, + 12.0082138671875, + -0.28333333333333266, + -3.406451612903225, + 3.406451612903225, + 103.86692888768847, + -55.924533933487666, + -2.141412636195749, + 2.3190844269718154, + 0.0 + ], + [ + 1089.944097, + 12.077321044921874, + -0.28333333333333266, + -3.4182795698924733, + 3.4182795698924733, + 103.82110826796202, + -55.874037740319736, + -2.1788172237275525, + 2.403244748918373, + 0.0 + ], + [ + 1089.964063, + 12.02077880859375, + -0.28333333333333266, + -3.4182795698924733, + 3.4182795698924733, + 103.77341741885897, + -55.82634689121669, + -2.2255729581423065, + 2.4780539239819803, + 0.0 + ], + [ + 1089.984108, + 12.108733398437499, + -0.2843749999999993, + -3.4182795698924733, + 3.4182795698924733, + 103.72011588162614, + -55.77491558336045, + -2.281679839440012, + 2.5154585115137835, + 0.0 + ], + [ + 1090.004099, + 12.04590869140625, + -0.2843749999999993, + -3.4301075268817205, + 3.4301075268817205, + 103.6714899178348, + -55.727224734257405, + -2.337786720737717, + 2.4874050708649307, + 0.0 + ], + [ + 1090.024058, + 12.027061279296875, + -0.2843749999999993, + -3.4301075268817205, + 3.4301075268817205, + 103.62192883935516, + -55.67205296764799, + -2.3845424551524714, + 2.5248096583967343, + 0.0 + ], + [ + 1090.044077, + 12.096168457031249, + -0.285416666666666, + -3.4301075268817205, + 3.4301075268817205, + 103.56862730212235, + -55.61220562759711, + -2.431298189567226, + 2.5996188334603416, + 0.0 + ], + [ + 1090.064091, + 12.02077880859375, + -0.285416666666666, + -3.441935483870968, + 3.441935483870968, + 103.51439065020124, + -55.56077431974088, + -2.4780539239819803, + 2.6557257147580464, + 0.0 + ], + [ + 1090.084123, + 12.02077880859375, + -0.28645833333333265, + -3.427712609970675, + 3.441935483870968, + 103.462959342345, + -55.506537667819764, + -2.5248096583967343, + 2.69313030228985, + 0.0 + ], + [ + 1090.104148, + 12.071038574218749, + -0.28645833333333265, + -3.4512707722385145, + 3.4655913978494626, + 103.4068524610473, + -55.4420147543274, + -2.5715653928114888, + 2.814695211768212, + 0.0 + ], + [ + 1090.124099, + 12.03334375, + -0.28645833333333265, + -3.4512707722385145, + 3.4655913978494626, + 103.34887535037299, + -55.386842987718, + -2.6183211272262428, + 2.861450946182966, + 0.0 + ], + [ + 1090.14406, + 12.02077880859375, + -0.2874999999999993, + -3.4512707722385145, + 3.4655913978494626, + 103.29463869845189, + -55.33073610642029, + -2.6650768616409977, + 2.833397505534113, + 0.0 + ], + [ + 1090.164156, + 12.064756103515625, + -0.2874999999999993, + -3.4630498533724343, + 3.47741935483871, + 103.23853181715418, + -55.26995365168111, + -2.711832596055752, + 2.9175578274806706, + 0.0 + ], + [ + 1090.18409, + 11.976801513671875, + -0.2874999999999993, + -3.4630498533724343, + 3.47741935483871, + 103.17961959179159, + -55.21291165569511, + -2.758588330470506, + 2.926908974363622, + 0.0 + ], + [ + 1090.204102, + 12.0584736328125, + -0.288541666666666, + -3.4630498533724343, + 3.47741935483871, + 103.1197722517407, + -55.15025897157934, + -2.7959929180023098, + 2.9549624150124743, + 0.0 + ], + [ + 1090.22406, + 11.97051904296875, + -0.288541666666666, + -3.474828934506354, + 3.489247311827957, + 103.05618445293663, + -55.0810604846455, + -2.842748652417064, + 3.048473883841983, + 0.0 + ], + [ + 1090.244125, + 11.99564892578125, + -0.28958333333333264, + -3.474828934506354, + 3.489247311827957, + 102.99820734226235, + -55.02121314459462, + -2.8988555337147695, + 3.095229618256737, + 0.0 + ], + [ + 1090.264117, + 12.052191162109375, + -0.28958333333333264, + -3.4866080156402743, + 3.5010752688172047, + 102.93836000221145, + -54.95949557516714, + -2.945611268129524, + 3.1045807651396884, + 0.0 + ], + [ + 1090.284099, + 12.001931396484375, + -0.28958333333333264, + -3.4866080156402743, + 3.5010752688172047, + 102.87570731809568, + -54.8912322029216, + -2.9830158556613275, + 3.2261456746180492, + 0.0 + ], + [ + 1090.304102, + 11.97051904296875, + -0.2906249999999993, + -3.4866080156402743, + 3.5010752688172047, + 102.81492486335651, + -54.822033715987764, + -3.01106929631018, + 3.272901409032804, + 0.0 + ], + [ + 1090.324085, + 12.02077880859375, + -0.2906249999999993, + -3.498387096774194, + 3.512903225806452, + 102.75133706455244, + -54.75657568780711, + -3.0297715900760815, + 3.2448479683839517, + 0.0 + ], + [ + 1090.344067, + 12.001931396484375, + -0.2906249999999993, + -3.498387096774194, + 3.512903225806452, + 102.68681415106008, + -54.69766346244452, + -3.048473883841983, + 3.2354968215010005, + 0.0 + ], + [ + 1090.364091, + 11.976801513671875, + -0.29166666666666596, + -3.498387096774194, + 3.498387096774194, + 102.62322635225601, + -54.63127031957556, + -3.076527324490836, + 3.272901409032804, + 0.0 + ], + [ + 1090.384088, + 12.001931396484375, + -0.29166666666666596, + -3.510166177908114, + 3.510166177908114, + 102.55683320938707, + -54.55833137388855, + -3.1045807651396884, + 3.329008290330509, + 0.0 + ], + [ + 1090.404475, + 12.027061279296875, + -0.2927083333333326, + -3.510166177908114, + 3.510166177908114, + 102.49137518120641, + -54.48539242820153, + -3.1606876464373936, + 3.3664128778623126, + 0.0 + ], + [ + 1090.424061, + 12.03334375, + -0.2927083333333326, + -3.5219452590420337, + 3.5219452590420337, + 102.49137518120641, + -54.48539242820153, + -3.1606876464373936, + 3.3664128778623126, + 0.0 + ], + [ + 1090.444031, + 11.9579541015625, + -0.2927083333333326, + -3.5219452590420337, + 3.5219452590420337, + 102.36139423953338, + -54.350735913087036, + -3.216794527735099, + 3.478626640457723, + 0.0 + ], + [ + 1090.464077, + 11.93282421875, + -0.2937499999999993, + -3.5219452590420337, + 3.5219452590420337, + 102.28939040853467, + -54.279667196776614, + -3.254199115266902, + 3.5160312279895267, + 0.0 + ], + [ + 1090.484064, + 12.001931396484375, + -0.2937499999999993, + -3.5337243401759535, + 3.5337243401759535, + 102.22299726566571, + -54.202987792336415, + -3.2916037027987057, + 3.5534358155213304, + 0.0 + ], + [ + 1090.50428, + 12.0082138671875, + -0.29479166666666595, + -3.5337243401759535, + 3.5337243401759535, + 102.15566900810846, + -54.13285419071428, + -3.3196571434475586, + 3.5347335217554283, + 0.0 + ], + [ + 1090.524062, + 11.989366455078125, + -0.29479166666666595, + -3.5455034213098733, + 3.5455034213098733, + 102.08179494773316, + -54.05710990096238, + -3.3570617309793613, + 3.637596137467888, + 0.0 + ], + [ + 1090.544084, + 12.027061279296875, + -0.29479166666666595, + -3.5455034213098733, + 3.5455034213098733, + 102.00792088735784, + -53.98043049652218, + -3.4038174653941162, + 3.7030541656485436, + 0.0 + ], + [ + 1090.564063, + 11.93282421875, + -0.2958333333333326, + -3.560215053763441, + 3.5455034213098733, + 101.9396575151123, + -53.90749155083517, + -3.4692754935747723, + 3.721756459414446, + 0.0 + ], + [ + 1090.584073, + 11.964236572265625, + -0.2958333333333326, + -3.5720430107526884, + 3.557282502443793, + 101.87045902817847, + -53.82987703170667, + -3.4973289342236247, + 3.7311076062973965, + 0.0 + ], + [ + 1090.604119, + 12.0082138671875, + -0.2968749999999993, + -3.5720430107526884, + 3.557282502443793, + 101.79471473842656, + -53.75319762726648, + -3.525382374872477, + 3.7965656344780525, + 0.0 + ], + [ + 1090.624078, + 11.99564892578125, + -0.2968749999999993, + -3.5838709677419356, + 3.569061583577713, + 101.71990556336296, + -53.6727777640731, + -3.5534358155213304, + 3.843321368892807, + 0.0 + ], + [ + 1090.64404, + 12.02077880859375, + -0.2968749999999993, + -3.5838709677419356, + 3.569061583577713, + 101.64509638829935, + -53.5970334743212, + -3.6001915499360844, + 3.8339702220098557, + 0.0 + ], + [ + 1090.664044, + 11.97051904296875, + -0.29791666666666594, + -3.5838709677419356, + 3.569061583577713, + 101.57028721323574, + -53.51193803768634, + -3.6282449905849368, + 3.964886278371168, + 0.0 + ], + [ + 1090.684117, + 11.983083984375, + -0.29791666666666594, + -3.595698924731183, + 3.595698924731183, + 101.48706200597748, + -53.43245328918126, + -3.675000724999691, + 3.974237425254119, + 0.0 + ], + [ + 1090.704068, + 12.027061279296875, + -0.29791666666666594, + -3.595698924731183, + 3.595698924731183, + 101.41038260153728, + -53.34642273785811, + -3.7404587531803473, + 4.0677488940836275, + 0.0 + ], + [ + 1090.724051, + 11.989366455078125, + -0.2989583333333326, + -3.5808406647116326, + 3.595698924731183, + 101.33463831178538, + -53.26693798935303, + -3.7965656344780525, + 4.049046600317726, + 0.0 + ], + [ + 1090.744092, + 11.97051904296875, + -0.2989583333333326, + -3.592619745845553, + 3.60752688172043, + 101.25328333390371, + -53.17903720865329, + -3.843321368892807, + 4.179962656679038, + 0.0 + ], + [ + 1090.764069, + 12.04590869140625, + -0.29999999999999927, + -3.592619745845553, + 3.60752688172043, + 101.17005812664544, + -53.098617345459914, + -3.8807259564246106, + 4.133206922264284, + 0.0 + ], + [ + 1090.784113, + 11.976801513671875, + -0.29999999999999927, + -3.6043988269794727, + 3.6193548387096777, + 101.08963826345207, + -53.00510587663041, + -3.9368328377223154, + 4.264122978625596, + 0.0 + ], + [ + 1090.804045, + 11.989366455078125, + -0.29999999999999927, + -3.6043988269794727, + 3.6193548387096777, + 101.0073481708821, + -52.92281578406044, + -3.9835885721370703, + 4.236069537976743, + 0.0 + ], + [ + 1090.824201, + 12.027061279296875, + -0.30104166666666593, + -3.6043988269794727, + 3.6193548387096777, + 100.92131761955895, + -52.83210965929582, + -4.0209931596688735, + 4.357634447455105, + 0.0 + ], + [ + 1090.844104, + 12.02077880859375, + -0.30104166666666593, + -3.6161779081133925, + 3.6161779081133925, + 100.83996264167727, + -52.747014222660965, + -4.0677488940836275, + 4.320229859923302, + 0.0 + ], + [ + 1090.864121, + 12.04590869140625, + -0.3020833333333326, + -3.6161779081133925, + 3.6161779081133925, + 100.75767254910731, + -52.65443786851975, + -4.105153481615432, + 4.441794769401662, + 0.0 + ], + [ + 1090.884077, + 12.03334375, + -0.3020833333333326, + -3.639736070381232, + 3.639736070381232, + 100.67257711247247, + -52.570277546573195, + -4.133206922264284, + 4.366985594338056, + 0.0 + ], + [ + 1090.904091, + 12.02077880859375, + -0.3020833333333326, + -3.639736070381232, + 3.639736070381232, + 100.58561144646102, + -52.47489584836709, + -4.151909216030186, + 4.469848210050515, + 0.0 + ], + [ + 1090.924116, + 12.04590869140625, + -0.30312499999999926, + -3.639736070381232, + 3.639736070381232, + 100.50332135389105, + -52.38605995297906, + -4.170611509796087, + 4.469848210050515, + 0.0 + ], + [ + 1090.944132, + 12.001931396484375, + -0.30312499999999926, + -3.651515151515152, + 3.651515151515152, + 100.4172908025679, + -52.29441871352614, + -4.189313803561989, + 4.52595509134822, + 0.0 + ], + [ + 1090.964061, + 12.014496337890625, + -0.3041666666666659, + -3.651515151515152, + 3.651515151515152, + 100.33313048062135, + -52.2065179328264, + -4.20801609732789, + 4.479199356933466, + 0.0 + ], + [ + 1090.984074, + 12.0584736328125, + -0.3041666666666659, + -3.6632942326490716, + 3.6632942326490716, + 100.24803504398649, + -52.10552554649053, + -4.226718391093793, + 4.638168853943631, + 0.0 + ], + [ + 1091.004514, + 11.9579541015625, + -0.3041666666666659, + -3.6632942326490716, + 3.6632942326490716, + 100.16200449266334, + -52.0176247657908, + -4.236069537976743, + 4.572710825762974, + 0.0 + ], + [ + 1091.024074, + 12.0082138671875, + -0.3052083333333326, + -3.6632942326490716, + 3.6632942326490716, + 100.16200449266334, + -52.0176247657908, + -4.236069537976743, + 4.572710825762974, + 0.0 + ], + [ + 1091.044255, + 12.03334375, + -0.3052083333333326, + -3.6750733137829914, + 3.6750733137829914, + 99.98994339001705, + -51.824991140002005, + -4.254771831742645, + 4.6942757352413365, + 0.0 + ], + [ + 1091.064109, + 12.0082138671875, + -0.30624999999999925, + -3.6750733137829914, + 3.6750733137829914, + 99.9020426093173, + -51.733349900549086, + -4.264122978625596, + 4.722329175890189, + 0.0 + ], + [ + 1091.084092, + 12.071038574218749, + -0.30624999999999925, + -3.686852394916911, + 3.686852394916911, + 99.81227159924099, + -51.63142239952492, + -4.282825272391498, + 4.73168032277314, + 0.0 + ], + [ + 1091.104078, + 11.99564892578125, + -0.30624999999999925, + -3.686852394916911, + 3.686852394916911, + 99.72437081854125, + -51.53791093069542, + -4.31087871304035, + 4.797138350953796, + 0.0 + ], + [ + 1091.124062, + 12.001931396484375, + -0.3072916666666659, + -3.686852394916911, + 3.686852394916911, + 99.6364700378415, + -51.43691854435955, + -4.348283300572154, + 4.84389408536855, + 0.0 + ], + [ + 1091.14412, + 12.04590869140625, + -0.3072916666666659, + -3.698631476050831, + 3.698631476050831, + 99.5420234543237, + -51.344342190218335, + -4.385687888103957, + 4.806489497836746, + 0.0 + ], + [ + 1091.164154, + 12.014496337890625, + -0.3072916666666659, + -3.698631476050831, + 3.698631476050831, + 99.44944710018248, + -51.23867423044099, + -4.432443622518712, + 4.956107847963961, + 0.0 + ], + [ + 1091.184056, + 11.989366455078125, + -0.30833333333333257, + -3.698631476050831, + 3.698631476050831, + 99.35593563135298, + -51.14329253223489, + -4.488550503816417, + 4.881298672900353, + 0.0 + ], + [ + 1091.204116, + 12.04590869140625, + -0.30833333333333257, + -3.710410557184751, + 3.710410557184751, + 99.26055393314688, + -51.03855968714584, + -4.544657385114122, + 4.993512435495764, + 0.0 + ], + [ + 1091.224125, + 11.97051904296875, + -0.30937499999999923, + -3.710410557184751, + 3.710410557184751, + 99.16797757900567, + -50.94130775956315, + -4.591413119528877, + 4.956107847963961, + 0.0 + ], + [ + 1091.244267, + 12.014496337890625, + -0.30937499999999923, + -3.722189638318671, + 3.722189638318671, + 99.07633633955275, + -50.845926061357055, + -4.638168853943631, + 4.993512435495764, + 0.0 + ], + [ + 1091.264457, + 12.052191162109375, + -0.30937499999999923, + -3.722189638318671, + 3.722189638318671, + 98.97908441197006, + -50.73932298689141, + -4.666222294592483, + 4.993512435495764, + 0.0 + ], + [ + 1091.284215, + 12.014496337890625, + -0.3104166666666659, + -3.722189638318671, + 3.722189638318671, + 98.97908441197006, + -50.73932298689141, + -4.666222294592483, + 4.993512435495764, + 0.0 + ], + [ + 1091.304065, + 12.04590869140625, + -0.3104166666666659, + -3.733968719452591, + 3.733968719452591, + 98.88557294314055, + -50.640200829932134, + -4.675573441475434, + 5.021565876144617, + 0.0 + ], + [ + 1091.324108, + 11.983083984375, + -0.31145833333333256, + -3.733968719452591, + 3.733968719452591, + 98.68919885859859, + -50.43167025444233, + -4.703626882124286, + 5.096375051208223, + 0.0 + ], + [ + 1091.344067, + 11.983083984375, + -0.31145833333333256, + -3.7457478005865106, + 3.7457478005865106, + 98.59662250445737, + -50.33067786810646, + -4.7410314696560905, + 5.152481932505929, + 0.0 + ], + [ + 1091.364122, + 12.03334375, + -0.31145833333333256, + -3.7457478005865106, + 3.7457478005865106, + 98.4956301181215, + -50.21659387613446, + -4.769084910304943, + 5.227291107569535, + 0.0 + ], + [ + 1091.384112, + 11.97051904296875, + -0.3124999999999992, + -3.7457478005865106, + 3.7457478005865106, + 98.3983781905388, + -50.11560148979859, + -4.815840644719697, + 5.255344548218388, + 0.0 + ], + [ + 1091.404144, + 11.976801513671875, + -0.3124999999999992, + -3.7575268817204304, + 3.7575268817204304, + 98.30112626295612, + -50.00806330064466, + -4.853245232251501, + 5.292749135750192, + 0.0 + ], + [ + 1091.424292, + 12.052191162109375, + -0.3124999999999992, + -3.7575268817204304, + 3.7575268817204304, + 98.19639341786707, + -49.89491442336095, + -4.881298672900353, + 5.3675583108137985, + 0.0 + ], + [ + 1091.44407, + 11.976801513671875, + -0.3135416666666659, + -3.7575268817204304, + 3.7575268817204304, + 98.0963361462195, + -49.79205180764849, + -4.9187032604321566, + 5.376909457696749, + 0.0 + ], + [ + 1091.464039, + 11.9579541015625, + -0.3135416666666659, + -3.76930596285435, + 3.76930596285435, + 97.99066818644215, + -49.673292242235014, + -4.956107847963961, + 5.433016338994454, + 0.0 + ], + [ + 1091.484032, + 11.989366455078125, + -0.31458333333333255, + -3.76930596285435, + 3.76930596285435, + 97.8850002266648, + -49.56481893839278, + -5.021565876144617, + 5.507825514058061, + 0.0 + ], + [ + 1091.504063, + 11.9579541015625, + -0.31458333333333255, + -3.78108504398827, + 3.78108504398827, + 97.78400784032894, + -49.45728074923885, + -5.077672757442322, + 5.507825514058061, + 0.0 + ], + [ + 1091.524078, + 12.001931396484375, + -0.31458333333333255, + -3.78108504398827, + 3.78108504398827, + 97.676469651175, + -49.337586069137075, + -5.124428491857076, + 5.582634689121669, + 0.0 + ], + [ + 1091.544072, + 11.964236572265625, + -0.3156249999999992, + -3.78108504398827, + 3.78108504398827, + 97.57173680608595, + -49.230982994671436, + -5.161833079388879, + 5.610688129770521, + 0.0 + ], + [ + 1091.564078, + 11.92025927734375, + -0.3156249999999992, + -3.7928641251221897, + 3.7928641251221897, + 97.4670039609969, + -49.115963888011144, + -5.199237666920683, + 5.582634689121669, + 0.0 + ], + [ + 1091.584022, + 12.001931396484375, + -0.3166666666666659, + -3.7928641251221897, + 3.7928641251221897, + 97.35572531308979, + -49.00000966666255, + -5.227291107569535, + 5.648092717302324, + 0.0 + ], + [ + 1091.604111, + 11.964236572265625, + -0.3166666666666659, + -3.8046432062561095, + 3.8046432062561095, + 97.24725200924756, + -48.89060124813203, + -5.2740468419842905, + 5.666795011068226, + 0.0 + ], + [ + 1091.6241, + 11.983083984375, + -0.3166666666666659, + -3.8046432062561095, + 3.8046432062561095, + 97.13597336134045, + -48.77277679740685, + -5.3208025763990445, + 5.6387415704193735, + 0.0 + ], + [ + 1091.644155, + 11.983083984375, + -0.31770833333333254, + -3.8046432062561095, + 3.8046432062561095, + 97.02375959874503, + -48.65495234668166, + -5.3862606045797, + 5.760306479897736, + 0.0 + ], + [ + 1091.664103, + 11.92025927734375, + -0.31770833333333254, + -3.8282013685239495, + 3.8282013685239495, + 96.9162214095911, + -48.54367369877455, + -5.442367485877405, + 5.704199598600029, + 0.0 + ], + [ + 1091.684137, + 11.99564892578125, + -0.3187499999999992, + -3.8282013685239495, + 3.8282013685239495, + 96.8002671882425, + -48.42678436273766, + -5.489123220292161, + 5.732253039248882, + 0.0 + ], + [ + 1091.704096, + 12.0082138671875, + -0.3187499999999992, + -3.8399804496578693, + 3.8399804496578693, + 96.6880534256471, + -48.31083014138907, + -5.526527807823963, + 5.797711067429539, + 0.0 + ], + [ + 1091.724058, + 11.939106689453125, + -0.3187499999999992, + -3.8399804496578693, + 3.8399804496578693, + 96.57209920429851, + -48.190200346599006, + -5.563932395355766, + 5.825764508078391, + 0.0 + ], + [ + 1091.744041, + 11.983083984375, + -0.31979166666666586, + -3.8399804496578693, + 3.8399804496578693, + 96.4580152123265, + -48.06957055180894, + -5.60133698288757, + 5.853817948727244, + 0.0 + ], + [ + 1091.764106, + 11.951671630859375, + -0.31979166666666586, + -3.851759530791789, + 3.851759530791789, + 96.3439312203545, + -47.94707052764228, + -5.6387415704193735, + 5.975382858205604, + 0.0 + ], + [ + 1091.784123, + 11.951671630859375, + -0.3208333333333325, + -3.851759530791789, + 3.851759530791789, + 96.22797699900592, + -47.83205142098199, + -5.676146157951178, + 5.937978270673802, + 0.0 + ], + [ + 1091.804129, + 11.983083984375, + -0.3208333333333325, + -3.863538611925709, + 3.8475073313782993, + 96.1157632364105, + -47.83205142098199, + -5.704199598600029, + 5.937978270673802, + 0.0 + ], + [ + 1091.82406, + 11.951671630859375, + -0.3208333333333325, + -3.863538611925709, + 3.8475073313782993, + 95.99606855630873, + -47.58424602858379, + -5.722901892365932, + 6.059543180152163, + 0.0 + ], + [ + 1091.844068, + 11.97051904296875, + -0.3218749999999992, + -3.863538611925709, + 3.8475073313782993, + 95.88291967902502, + -47.46174600441714, + -5.732253039248882, + 6.078245473918065, + 0.0 + ], + [ + 1091.86408, + 12.014496337890625, + -0.3218749999999992, + -3.8753176930596287, + 3.8592375366568916, + 95.76603034298815, + -47.332700177432415, + -5.741604186131833, + 6.14370350209872, + 0.0 + ], + [ + 1091.884108, + 11.964236572265625, + -0.32291666666666585, + -3.8753176930596287, + 3.8592375366568916, + 95.64820589226296, + -47.20552457982428, + -5.760306479897736, + 6.274619558460033, + 0.0 + ], + [ + 1091.904117, + 11.983083984375, + -0.32291666666666585, + -3.8870967741935485, + 3.870967741935484, + 95.53225167091436, + -47.079284096904445, + -5.779008773663636, + 6.24656611781118, + 0.0 + ], + [ + 1091.924071, + 12.02077880859375, + -0.32291666666666585, + -3.8870967741935485, + 3.870967741935484, + 95.40788141737112, + -46.958654302114375, + -5.80706221431249, + 6.265268411577082, + 0.0 + ], + [ + 1091.944109, + 11.97051904296875, + -0.3239583333333325, + -3.8870967741935485, + 3.870967741935484, + 95.29099208133424, + -46.82680313106477, + -5.853817948727244, + 6.34942873352364, + 0.0 + ], + [ + 1091.964064, + 12.0082138671875, + -0.3239583333333325, + -3.8988758553274683, + 3.8988758553274683, + 95.16662182779099, + -46.70149776283323, + -5.900573683141998, + 6.321375292874787, + 0.0 + ], + [ + 1091.984119, + 11.964236572265625, + -0.3239583333333325, + -3.8988758553274683, + 3.8988758553274683, + 95.04692714768922, + -46.57058170647191, + -5.947329417556753, + 6.368131027289542, + 0.0 + ], + [ + 1092.004136, + 11.976801513671875, + -0.3249999999999992, + -3.8988758553274683, + 3.8988758553274683, + 94.92255689414597, + -46.445276338240376, + -5.994085151971507, + 6.34942873352364, + 0.0 + ], + [ + 1092.024043, + 12.014496337890625, + -0.3249999999999992, + -3.910654936461388, + 3.910654936461388, + 94.8037973287325, + -46.30968470843759, + -6.031489739503311, + 6.480344789884952, + 0.0 + ], + [ + 1092.044065, + 11.97051904296875, + -0.32604166666666584, + -3.910654936461388, + 3.910654936461388, + 94.67568661643607, + -46.1740930786348, + -6.068894327035114, + 6.527100524299706, + 0.0 + ], + [ + 1092.064099, + 11.97051904296875, + -0.32604166666666584, + -3.922434017595308, + 3.922434017595308, + 94.55131636289282, + -46.033825875390534, + -6.096947767683966, + 6.658016580661018, + 0.0 + ], + [ + 1092.084041, + 12.03334375, + -0.32604166666666584, + -3.922434017595308, + 3.922434017595308, + 94.42788122403788, + -45.903844933717515, + -6.1343523552157695, + 6.658016580661018, + 0.0 + ], + [ + 1092.104062, + 11.9579541015625, + -0.3270833333333325, + -3.922434017595308, + 3.922434017595308, + 94.29603005298826, + -45.77012353329132, + -6.190459236513474, + 6.751528049490528, + 0.0 + ], + [ + 1092.124073, + 12.0584736328125, + -0.3270833333333325, + -3.9342130987292276, + 3.9178885630498534, + 94.16604911131525, + -45.629856330047055, + -6.23721497092823, + 6.8076349307882325, + 0.0 + ], + [ + 1092.144066, + 12.02077880859375, + -0.32812499999999917, + -3.9342130987292276, + 3.9178885630498534, + 94.03513305495393, + -45.48678378273791, + -6.302672999108886, + 6.882444105851839, + 0.0 + ], + [ + 1092.164067, + 11.976801513671875, + -0.32812499999999917, + -3.945992179863148, + 3.929618768328446, + 93.90608722796921, + -45.346516579493645, + -6.368131027289542, + 6.882444105851839, + 0.0 + ], + [ + 1092.184101, + 12.001931396484375, + -0.32812499999999917, + -3.945992179863148, + 3.929618768328446, + 93.77143071285472, + -45.210924949690856, + -6.442940202353148, + 6.919848693383642, + 0.0 + ], + [ + 1092.204065, + 11.976801513671875, + -0.32916666666666583, + -3.945992179863148, + 3.929618768328446, + 93.63864442711682, + -45.078138663952956, + -6.4896959367679035, + 6.910497546500692, + 0.0 + ], + [ + 1092.224057, + 11.93282421875, + -0.32916666666666583, + -3.9577712609970677, + 3.941348973607038, + 93.50024745324914, + -44.93506611664381, + -6.545802818065608, + 6.9385509871495445, + 0.0 + ], + [ + 1092.244048, + 12.02077880859375, + -0.3302083333333325, + -3.9577712609970677, + 3.941348973607038, + 93.36839628219954, + -44.79573402808784, + -6.601909699363313, + 6.901146399617741, + 0.0 + ], + [ + 1092.264117, + 11.951671630859375, + -0.3302083333333325, + -3.9695503421309875, + 3.9530791788856305, + 93.22719396426697, + -44.6517263660904, + -6.658016580661018, + 6.947902134032495, + 0.0 + ], + [ + 1092.284093, + 11.94538916015625, + -0.3302083333333325, + -3.9695503421309875, + 3.9530791788856305, + 93.09253744915249, + -44.51706985097591, + -6.714123461958723, + 6.947902134032495, + 0.0 + ], + [ + 1092.304125, + 11.976801513671875, + -0.33124999999999916, + -3.9695503421309875, + 3.9530791788856305, + 92.94946490184334, + -44.36932173022528, + -6.770230343256429, + 7.088169337276758, + 0.0 + ], + [ + 1092.324064, + 11.964236572265625, + -0.33124999999999916, + -3.9813294232649072, + 3.964809384164223, + 92.81387327204055, + -44.232794985734195, + -6.826337224554134, + 7.032062455979053, + 0.0 + ], + [ + 1092.344117, + 12.001931396484375, + -0.3322916666666658, + -3.9813294232649072, + 3.964809384164223, + 92.67547629817288, + -44.0813064062304, + -6.863741812085937, + 7.144276218574463, + 0.0 + ], + [ + 1092.36409, + 11.97051904296875, + -0.3322916666666658, + -3.993108504398827, + 3.9765395894428153, + 92.54081978305838, + -43.931688056103184, + -6.8917952527347905, + 7.2097342467551195, + 0.0 + ], + [ + 1092.384081, + 11.97051904296875, + -0.3322916666666658, + -3.993108504398827, + 3.9765395894428153, + 92.39961746512583, + -43.78955062348233, + -6.8917952527347905, + 7.275192274935776, + 0.0 + ], + [ + 1092.404111, + 11.989366455078125, + -0.3333333333333325, + -3.993108504398827, + 3.9765395894428153, + 92.25935026188156, + -43.64741319086147, + -6.901146399617741, + 7.2097342467551195, + 0.0 + ], + [ + 1092.424108, + 11.939106689453125, + -0.3333333333333325, + -4.004887585532747, + 3.9882697947214076, + 92.11440748519583, + -43.494989496669376, + -6.910497546500692, + 7.378054890648236, + 0.0 + ], + [ + 1092.444133, + 11.926541748046875, + -0.3333333333333325, + -4.004887585532747, + 3.971652003910068, + 91.97601051132816, + -43.34350091716557, + -6.9385509871495445, + 7.378054890648236, + 0.0 + ], + [ + 1092.464107, + 12.0082138671875, + -0.33437499999999915, + -4.004887585532747, + 3.971652003910068, + 91.83013261995411, + -43.19575279641494, + -6.9853067215642985, + 7.350001449999382, + 0.0 + ], + [ + 1092.484095, + 11.951671630859375, + -0.33437499999999915, + -4.028445747800586, + 3.995014662756598, + 91.68799518733327, + -43.041458872846256, + -7.041413602862004, + 7.4809175063606945, + 0.0 + ], + [ + 1092.504055, + 11.939106689453125, + -0.3354166666666658, + -4.028445747800586, + 3.995014662756598, + 91.54118218127094, + -42.893710752095636, + -7.088169337276758, + 7.5370243876584, + 0.0 + ], + [ + 1092.524056, + 12.001931396484375, + -0.3354166666666658, + -4.040224828934506, + 4.006695992179862, + 91.3981096339618, + -42.74502751665671, + -7.134925071691512, + 7.490268653243646, + 0.0 + ], + [ + 1092.544044, + 11.926541748046875, + -0.3354166666666658, + -4.040224828934506, + 4.006695992179862, + 91.25223174258775, + -42.59727939590609, + -7.1629785123403655, + 7.462215212594793, + 0.0 + ], + [ + 1092.564066, + 11.983083984375, + -0.33645833333333247, + -4.040224828934506, + 4.006695992179862, + 91.10635385121373, + -42.44485570171399, + -7.191031952989217, + 7.518322093892499, + 0.0 + ], + [ + 1092.584081, + 11.99564892578125, + -0.33645833333333247, + -4.052003910068426, + 4.018377321603127, + 90.96141107452799, + -42.293367122210185, + -7.21908539363807, + 7.4809175063606945, + 0.0 + ], + [ + 1092.604058, + 11.913976806640624, + -0.33749999999999913, + -4.052003910068426, + 4.035190615835777, + 90.80992249502418, + -42.13439762520002, + -7.247138834286924, + 7.583780122073155, + 0.0 + ], + [ + 1092.624065, + 11.983083984375, + -0.33749999999999913, + -4.063782991202346, + 4.0469208211143695, + 90.66497971833844, + -41.974493013501565, + -7.284543421818727, + 7.705345031551516, + 0.0 + ], + [ + 1092.644068, + 11.926541748046875, + -0.33749999999999913, + -4.0469208211143695, + 4.0469208211143695, + 90.51349113883464, + -41.82113420462117, + -7.312596862467579, + 7.761451912849221, + 0.0 + ], + [ + 1092.664104, + 11.93282421875, + -0.3385416666666658, + -4.0469208211143695, + 4.0469208211143695, + 90.3685483621489, + -41.65748913416953, + -7.350001449999382, + 7.873665675444631, + 0.0 + ], + [ + 1092.684063, + 11.9579541015625, + -0.3385416666666658, + -4.058651026392962, + 4.058651026392962, + 90.21986512670998, + -41.50319521060084, + -7.359352596882333, + 7.892367969210533, + 0.0 + ], + [ + 1092.704055, + 11.93282421875, + -0.33958333333333246, + -4.058651026392962, + 4.058651026392962, + 90.07118189127107, + -41.340485254837496, + -7.387406037531186, + 7.939123703625287, + 0.0 + ], + [ + 1092.724094, + 11.92025927734375, + -0.33958333333333246, + -4.070381231671554, + 4.070381231671554, + 89.91782308239067, + -41.18993179002199, + -7.415459478180039, + 7.85496338167873, + 0.0 + ], + [ + 1092.744066, + 11.964236572265625, + -0.33958333333333246, + -4.070381231671554, + 4.070381231671554, + 89.76352915882198, + -41.034702751765, + -7.452864065711841, + 7.86431452856168, + 0.0 + ], + [ + 1092.764111, + 11.92025927734375, + -0.3406249999999991, + -4.070381231671554, + 4.053421309872922, + 89.60549477650011, + -40.88040882819631, + -7.499619800126597, + 7.761451912849221, + 0.0 + ], + [ + 1092.784174, + 11.99564892578125, + -0.3406249999999991, + -4.0821114369501466, + 4.065102639296187, + 89.45307108230801, + -40.72143933118615, + -7.565077828307253, + 7.817558794146926, + 0.0 + ], + [ + 1092.804061, + 11.92025927734375, + -0.3406249999999991, + -4.0821114369501466, + 4.065102639296187, + 89.29784204405102, + -40.56434006355257, + -7.621184709604957, + 7.761451912849221, + 0.0 + ], + [ + 1092.824063, + 11.901411865234374, + -0.3416666666666658, + -4.0821114369501466, + 4.065102639296187, + 89.14167789110574, + -40.40817591060729, + -7.677291590902663, + 7.808207647263975, + 0.0 + ], + [ + 1092.844108, + 11.97051904296875, + -0.3416666666666658, + -4.093841642228739, + 4.076783968719452, + 88.99018931160194, + -40.241725496090766, + -7.714696178434467, + 7.939123703625287, + 0.0 + ], + [ + 1092.86415, + 11.913976806640624, + -0.34270833333333245, + -4.093841642228739, + 4.076783968719452, + 88.83028469990349, + -40.079950655015715, + -7.742749619083319, + 7.995230584922992, + 0.0 + ], + [ + 1092.884121, + 11.9076943359375, + -0.34270833333333245, + -4.105571847507331, + 4.088465298142717, + 88.67879612039968, + -39.91817581394067, + -7.742749619083319, + 8.032635172454796, + 0.0 + ], + [ + 1092.90411, + 11.976801513671875, + -0.34270833333333245, + -4.105571847507331, + 4.088465298142717, + 88.52076173807781, + -39.7592063169305, + -7.75210076596627, + 8.060688613103649, + 0.0 + ], + [ + 1092.924177, + 11.93282421875, + -0.3437499999999991, + -4.105571847507331, + 4.105571847507331, + 88.36459758513253, + -39.59182078772568, + -7.75210076596627, + 8.163551228816107, + 0.0 + ], + [ + 1092.944087, + 11.926541748046875, + -0.3437499999999991, + -4.117302052785924, + 4.117302052785924, + 88.20656320281066, + -39.430981061338926, + -7.770803059732172, + 8.098093200635452, + 0.0 + ], + [ + 1092.964078, + 11.964236572265625, + -0.3447916666666658, + -4.117302052785924, + 4.117302052785924, + 88.05039904986538, + -39.26827110557558, + -7.789505353498073, + 8.144848935050206, + 0.0 + ], + [ + 1092.98418, + 11.9076943359375, + -0.3447916666666658, + -4.129032258064516, + 4.129032258064516, + 87.8923646675435, + -39.106496264500535, + -7.808207647263975, + 8.126146641284304, + 0.0 + ], + [ + 1093.004068, + 11.976801513671875, + -0.3447916666666658, + -4.129032258064516, + 4.129032258064516, + 87.73058982646846, + -38.944721423425484, + -7.836261087912828, + 8.144848935050206, + 0.0 + ], + [ + 1093.024128, + 11.951671630859375, + -0.34583333333333244, + -4.129032258064516, + 4.129032258064516, + 87.56787987070511, + -38.77733589422066, + -7.86431452856168, + 8.154200081933157, + 0.0 + ], + [ + 1093.044024, + 11.94538916015625, + -0.34583333333333244, + -4.140762463343108, + 4.140762463343108, + 87.40610502963007, + -38.611820594392434, + -7.911070262976435, + 8.20095581634791, + 0.0 + ], + [ + 1093.064067, + 11.976801513671875, + -0.3468749999999991, + -4.140762463343108, + 4.140762463343108, + 87.23778438573694, + -38.43882437705784, + -7.967177144274141, + 8.28511613829447, + 0.0 + ], + [ + 1093.084122, + 11.93282421875, + -0.3468749999999991, + -4.152492668621701, + 4.169794721407625, + 87.0778797740385, + -38.27143884785302, + -8.041986319337747, + 8.331871872709224, + 0.0 + ], + [ + 1093.104297, + 11.926541748046875, + -0.3468749999999991, + -4.152492668621701, + 4.169794721407625, + 86.90862401545708, + -38.09657240114184, + -8.116795494401355, + 8.481490222836438, + 0.0 + ], + [ + 1093.124251, + 11.97051904296875, + -0.34791666666666576, + -4.152492668621701, + 4.169794721407625, + 86.74404383031714, + -37.918900610365775, + -8.191604669464962, + 8.50019251660234, + 0.0 + ], + [ + 1093.144066, + 11.94538916015625, + -0.34791666666666576, + -4.164222873900293, + 4.181573802541545, + 86.58133387455379, + -37.74683950771948, + -8.238360403879716, + 8.565650544782995, + 0.0 + ], + [ + 1093.164089, + 11.939106689453125, + -0.3489583333333324, + -4.164222873900293, + 4.181573802541545, + 86.41207811597239, + -37.58506466664443, + -8.257062697645617, + 8.537597104134143, + 0.0 + ], + [ + 1093.184076, + 11.976801513671875, + -0.3489583333333324, + -4.1759530791788855, + 4.193352883675465, + 86.24749793083245, + -37.417679137439606, + -8.266413844528568, + 8.556299397900045, + 0.0 + ], + [ + 1093.204077, + 11.94538916015625, + -0.3489583333333324, + -4.1759530791788855, + 4.193352883675465, + 86.07917728693934, + -37.23907223197524, + -8.266413844528568, + 8.575001691665946, + 0.0 + ], + [ + 1093.224096, + 11.9579541015625, + -0.3499999999999991, + -4.1759530791788855, + 4.193352883675465, + 85.90431084022815, + -37.070751588082125, + -8.29446728517742, + 8.575001691665946, + 0.0 + ], + [ + 1093.244197, + 11.926541748046875, + -0.3499999999999991, + -4.19941348973607, + 4.216911045943305, + 85.73131462289356, + -36.89775537074754, + -8.350574166475125, + 8.575001691665946, + 0.0 + ], + [ + 1093.264063, + 11.951671630859375, + -0.3499999999999991, + -4.19941348973607, + 4.216911045943305, + 85.55831840555898, + -36.89775537074754, + -8.425383341538733, + 8.575001691665946, + 0.0 + ], + [ + 1093.284087, + 12.001931396484375, + -0.35104166666666575, + -4.19941348973607, + 4.216911045943305, + 85.38625730291268, + -36.54989270670176, + -8.50954366348529, + 8.687215454261356, + 0.0 + ], + [ + 1093.304078, + 11.951671630859375, + -0.35104166666666575, + -4.211143695014663, + 4.228690127077225, + 85.21139085620149, + -36.37035068654911, + -8.584352838548897, + 8.677864307378405, + 0.0 + ], + [ + 1093.324297, + 11.93282421875, + -0.3520833333333324, + -4.211143695014663, + 4.228690127077225, + 85.03652440949031, + -36.19267889577304, + -8.631108572963651, + 8.771375776207915, + 0.0 + ], + [ + 1093.344168, + 11.989366455078125, + -0.3520833333333324, + -4.222873900293255, + 4.240469208211144, + 84.86446330684402, + -36.01313687562038, + -8.649810866729554, + 8.83683380438857, + 0.0 + ], + [ + 1093.364125, + 11.92025927734375, + -0.3520833333333324, + -4.222873900293255, + 4.240469208211144, + 84.68866174544453, + -35.82798416733796, + -8.668513160495454, + 8.93034527321808, + 0.0 + ], + [ + 1093.384077, + 11.9076943359375, + -0.3531249999999991, + -4.222873900293255, + 4.240469208211144, + 84.51098995466847, + -35.643766573743825, + -8.677864307378405, + 9.04255903581349, + 0.0 + ], + [ + 1093.404105, + 11.989366455078125, + -0.3531249999999991, + -4.234604105571847, + 4.234604105571847, + 84.33799373733389, + -35.463289438902876, + -8.70591774802726, + 9.079963623345293, + 0.0 + ], + [ + 1093.424135, + 11.93282421875, + -0.35416666666666574, + -4.234604105571847, + 4.234604105571847, + 84.16032194655781, + -35.280942074685335, + -8.733971188676112, + 9.117368210877096, + 0.0 + ], + [ + 1093.444213, + 11.989366455078125, + -0.35416666666666574, + -4.24633431085044, + 4.24633431085044, + 83.98265015578176, + -35.10046493984438, + -8.762024629324964, + 9.136070504643, + 0.0 + ], + [ + 1093.464097, + 11.89512939453125, + -0.35416666666666574, + -4.24633431085044, + 4.24633431085044, + 83.80684859438227, + -34.91437711687366, + -8.780726923090866, + 9.136070504643, + 0.0 + ], + [ + 1093.484111, + 11.913976806640624, + -0.3552083333333324, + -4.24633431085044, + 4.24633431085044, + 83.62917680360621, + -34.73109463796782, + -8.799429216856767, + 9.145421651525949, + 0.0 + ], + [ + 1093.504072, + 11.97051904296875, + -0.3552083333333324, + -4.258064516129032, + 4.258064516129032, + 83.44682943938867, + -34.53939612686733, + -8.82748265750562, + 9.238933120355458, + 0.0 + ], + [ + 1093.524059, + 11.901411865234374, + -0.35624999999999907, + -4.258064516129032, + 4.258064516129032, + 83.2691576486126, + -34.34769761576683, + -8.855536098154474, + 9.332444589184966, + 0.0 + ], + [ + 1093.544063, + 11.9076943359375, + -0.35624999999999907, + -4.269794721407624, + 4.269794721407624, + 83.08774539908335, + -34.153193760601454, + -8.892940685686275, + 9.47271179242923, + 0.0 + ], + [ + 1093.564079, + 11.983083984375, + -0.35624999999999907, + -4.269794721407624, + 4.252003910068426, + 82.91007360830729, + -33.95868990543608, + -8.93034527321808, + 9.556872114375787, + 0.0 + ], + [ + 1093.584063, + 11.926541748046875, + -0.35729166666666573, + -4.269794721407624, + 4.252003910068426, + 82.7342720469078, + -33.77540742653024, + -8.949047566983982, + 9.547520967492837, + 0.0 + ], + [ + 1093.604026, + 11.93282421875, + -0.35729166666666573, + -4.281524926686217, + 4.263685239491691, + 82.55473002675515, + -33.58183868605316, + -8.949047566983982, + 9.575574408141689, + 0.0 + ], + [ + 1093.624026, + 11.97051904296875, + -0.3583333333333324, + -4.281524926686217, + 4.263685239491691, + 82.37612312129079, + -33.39014017495266, + -8.93034527321808, + 9.556872114375787, + 0.0 + ], + [ + 1093.644083, + 11.9076943359375, + -0.3583333333333324, + -4.293255131964809, + 4.275366568914956, + 82.19284064238495, + -33.19002563165752, + -8.92099412633513, + 9.528818673726935, + 0.0 + ], + [ + 1093.664064, + 11.983083984375, + -0.3583333333333324, + -4.293255131964809, + 4.275366568914956, + 82.00768793410252, + -33.005808038063385, + -8.93034527321808, + 9.519467526843984, + 0.0 + ], + [ + 1093.684121, + 11.9076943359375, + -0.35937499999999906, + -4.293255131964809, + 4.275366568914956, + 81.8234703405084, + -32.80943395352142, + -8.967749860749883, + 9.659734730088248, + 0.0 + ], + [ + 1093.704055, + 11.901411865234374, + -0.35937499999999906, + -4.3049853372434015, + 4.287047898338221, + 81.63551228816108, + -32.613994983667745, + -9.033207888930539, + 9.678437023854148, + 0.0 + ], + [ + 1093.724102, + 11.926541748046875, + -0.3604166666666657, + -4.3049853372434015, + 4.287047898338221, + 81.44942446519036, + -32.41481555506089, + -9.126719357760049, + 9.771948492683658, + 0.0 + ], + [ + 1093.744089, + 11.913976806640624, + -0.3604166666666657, + -4.316715542521994, + 4.298729227761486, + 81.26146641284305, + -32.218441470518925, + -9.201528532823655, + 9.809353080215462, + 0.0 + ], + [ + 1093.764056, + 11.926541748046875, + -0.3604166666666657, + -4.316715542521994, + 4.298729227761486, + 81.07818393393721, + -32.02206738597695, + -9.26698656100431, + 9.856108814630215, + 0.0 + ], + [ + 1093.784214, + 11.97051904296875, + -0.3614583333333324, + -4.316715542521994, + 4.298729227761486, + 80.89583656971966, + -31.82101772799351, + -9.295040001653163, + 9.893513402162018, + 0.0 + ], + [ + 1093.804273, + 11.9076943359375, + -0.3614583333333324, + -4.328445747800586, + 4.310410557184751, + 80.70694340268406, + -31.62464364345154, + -9.285688854770212, + 9.884162255279067, + 0.0 + ], + [ + 1093.824076, + 11.913976806640624, + -0.3614583333333324, + -4.328445747800586, + 4.310410557184751, + 80.52179069440163, + -31.420788641403213, + -9.276337707887262, + 9.940269136576774, + 0.0 + ], + [ + 1093.844194, + 11.964236572265625, + -0.36249999999999905, + -4.328445747800586, + 4.310410557184751, + 80.3366379861192, + -31.22347944217295, + -9.26698656100431, + 9.968322577225626, + 0.0 + ], + [ + 1093.86415, + 11.882564453125, + -0.36249999999999905, + -4.340175953079179, + 4.322091886608016, + 80.14867993377189, + -31.022429784189505, + -9.276337707887262, + 9.987024870991528, + 0.0 + ], + [ + 1093.884097, + 11.951671630859375, + -0.3635416666666657, + -4.340175953079179, + 4.340175953079179, + 79.95978676673629, + -30.825120584959244, + -9.285688854770212, + 9.958971430342675, + 0.0 + ], + [ + 1093.904078, + 11.913976806640624, + -0.3635416666666657, + -4.351906158357771, + 4.351906158357771, + 79.77182871438897, + -30.62033046822262, + -9.323093442302016, + 10.052482899172183, + 0.0 + ], + [ + 1093.924158, + 11.901411865234374, + -0.3635416666666657, + -4.351906158357771, + 4.351906158357771, + 79.58013020328848, + -30.419280810239176, + -9.360498029833819, + 10.01507831164038, + 0.0 + ], + [ + 1093.944103, + 11.939106689453125, + -0.36458333333333237, + -4.351906158357771, + 4.351906158357771, + 79.38749657749969, + -30.209815120061076, + -9.407253764248573, + 10.136643221118742, + 0.0 + ], + [ + 1093.964127, + 11.863717041015624, + -0.36458333333333237, + -4.363636363636363, + 4.363636363636363, + 79.19392783702261, + -30.003154773947863, + -9.454009498663329, + 10.202101249299398, + 0.0 + ], + [ + 1093.984144, + 11.926541748046875, + -0.36562499999999903, + -4.363636363636363, + 4.363636363636363, + 79.00129421123383, + -29.793689083769763, + -9.500765233078083, + 10.314315011894807, + 0.0 + ], + [ + 1094.004109, + 11.9579541015625, + -0.36562499999999903, + -4.387096774193548, + 4.387096774193548, + 78.81333615888651, + -29.590769196409727, + -9.528818673726935, + 10.304963865011858, + 0.0 + ], + [ + 1094.024072, + 11.9076943359375, + -0.36562499999999903, + -4.387096774193548, + 4.387096774193548, + 78.6253781065392, + -29.3869141943614, + -9.538169820609886, + 10.314315011894807, + 0.0 + ], + [ + 1094.044102, + 11.92025927734375, + -0.3666666666666657, + -4.387096774193548, + 4.387096774193548, + 78.42993913668552, + -29.17931873355989, + -9.547520967492837, + 10.286261571245955, + 0.0 + ], + [ + 1094.064054, + 11.976801513671875, + -0.3666666666666657, + -4.39882697947214, + 4.39882697947214, + 78.23169482276697, + -28.96985304338179, + -9.566223261258738, + 10.304963865011858, + 0.0 + ], + [ + 1094.084091, + 11.939106689453125, + -0.3666666666666657, + -4.39882697947214, + 4.39882697947214, + 78.0343856235367, + -28.761322467891986, + -9.603627848790543, + 10.314315011894807, + 0.0 + ], + [ + 1094.104075, + 12.014496337890625, + -0.36770833333333236, + -4.39882697947214, + 4.39882697947214, + 77.83520619492985, + -28.55092166302559, + -9.659734730088248, + 10.389124186958414, + 0.0 + ], + [ + 1094.124087, + 11.901411865234374, + -0.36770833333333236, + -4.410557184750733, + 4.410557184750733, + 77.63883211038788, + -28.343326202224084, + -9.734543905151854, + 10.44523106825612, + 0.0 + ], + [ + 1094.144023, + 11.9076943359375, + -0.368749999999999, + -4.410557184750733, + 4.410557184750733, + 77.44339314053421, + -28.12544447985133, + -9.80000193333251, + 10.55744483085153, + 0.0 + ], + [ + 1094.164124, + 11.964236572265625, + -0.368749999999999, + -4.422287390029325, + 4.422287390029325, + 77.24514882661565, + -27.912238330920047, + -9.837406520864313, + 10.585498271500384, + 0.0 + ], + [ + 1094.184076, + 11.888846923828124, + -0.368749999999999, + -4.422287390029325, + 4.422287390029325, + 77.05158008613857, + -27.699967296677062, + -9.856108814630215, + 10.613551712149237, + 0.0 + ], + [ + 1094.204076, + 11.926541748046875, + -0.3697916666666657, + -4.422287390029325, + 4.422287390029325, + 76.85427088690831, + -27.488631377122374, + -9.846757667747264, + 10.613551712149237, + 0.0 + ], + [ + 1094.224082, + 11.976801513671875, + -0.3697916666666657, + -4.4340175953079175, + 4.4340175953079175, + 76.66257237580781, + -27.27823057225598, + -9.818704227098412, + 10.641605152798089, + 0.0 + ], + [ + 1094.244101, + 11.913976806640624, + -0.37083333333333235, + -4.4340175953079175, + 4.4340175953079175, + 76.46432806188925, + -27.065959538012994, + -9.80000193333251, + 10.594849418383333, + 0.0 + ], + [ + 1094.264079, + 11.9076943359375, + -0.37083333333333235, + -4.44574780058651, + 4.44574780058651, + 76.26140817452922, + -26.848077815640238, + -9.781299639566608, + 10.641605152798089, + 0.0 + ], + [ + 1094.284063, + 11.99564892578125, + -0.37083333333333235, + -4.44574780058651, + 4.44574780058651, + 76.06129363123407, + -26.633001437332368, + -9.790650786449559, + 10.66030744656399, + 0.0 + ], + [ + 1094.304101, + 11.92025927734375, + -0.371874999999999, + -4.44574780058651, + 4.44574780058651, + 75.85837374387404, + -26.41605482964791, + -9.828055373981362, + 10.735116621627597, + 0.0 + ], + [ + 1094.324062, + 11.964236572265625, + -0.371874999999999, + -4.457478005865102, + 4.457478005865102, + 75.65638897120229, + -26.196302877898564, + -9.893513402162018, + 10.828628090457107, + 0.0 + ], + [ + 1094.344084, + 11.939106689453125, + -0.3729166666666657, + -4.457478005865102, + 4.457478005865102, + 75.45720954259545, + -25.975615811460923, + -9.968322577225626, + 10.894086118637762, + 0.0 + ], + [ + 1094.364101, + 11.94538916015625, + -0.3729166666666657, + -4.469208211143695, + 4.469208211143695, + 75.2580301139886, + -25.759604318464756, + -10.024429458523333, + 10.88473497175481, + 0.0 + ], + [ + 1094.384032, + 11.983083984375, + -0.3729166666666657, + -4.469208211143695, + 4.469208211143695, + 75.05885068538174, + -25.549203513598364, + -10.061834046055134, + 10.85668153110596, + 0.0 + ], + [ + 1094.404098, + 11.94538916015625, + -0.37395833333333234, + -4.469208211143695, + 4.469208211143695, + 74.85406056864511, + -25.33132179122561, + -10.071185192938085, + 10.847330384223008, + 0.0 + ], + [ + 1094.424126, + 11.901411865234374, + -0.37395833333333234, + -4.480938416422287, + 4.480938416422287, + 74.6464651078436, + -25.110634724787968, + -10.071185192938085, + 10.847330384223008, + 0.0 + ], + [ + 1094.44414, + 11.964236572265625, + -0.374999999999999, + -4.480938416422287, + 4.480938416422287, + 74.44261010579527, + -24.8946232317918, + -10.080536339821036, + 10.819276943574154, + 0.0 + ], + [ + 1094.464038, + 11.94538916015625, + -0.374999999999999, + -4.492668621700879, + 4.492668621700879, + 74.23127418624058, + -24.682352197548816, + -10.136643221118742, + 10.763170062276451, + 0.0 + ], + [ + 1094.484136, + 11.913976806640624, + -0.374999999999999, + -4.492668621700879, + 4.492668621700879, + 74.0190031519976, + -24.466340704552653, + -10.2208035430653, + 10.837979237340056, + 0.0 + ], + [ + 1094.504116, + 11.951671630859375, + -0.37604166666666566, + -4.492668621700879, + 4.492668621700879, + 73.80673211775462, + -24.243783408738423, + -10.304963865011858, + 10.88473497175481, + 0.0 + ], + [ + 1094.52409, + 11.92025927734375, + -0.37604166666666566, + -4.504398826979472, + 4.448093841642229, + 73.59820154226482, + -24.027771915742257, + -10.398475333841366, + 10.828628090457107, + 0.0 + ], + [ + 1094.54409, + 11.989366455078125, + -0.37604166666666566, + -4.504398826979472, + 4.448093841642229, + 73.3906060814633, + -23.8098901933695, + -10.45458221513907, + 10.828628090457107, + 0.0 + ], + [ + 1094.564138, + 11.926541748046875, + -0.3770833333333323, + -4.504398826979472, + 4.448093841642229, + 73.18488085003838, + -23.59668404443822, + -10.482635655787924, + 10.87538382487186, + 0.0 + ], + [ + 1094.584146, + 11.92025927734375, + -0.3770833333333323, + -4.516129032258064, + 4.459677419354839, + 72.97635027454858, + -23.375996978000583, + -10.473284508904971, + 10.894086118637762, + 0.0 + ], + [ + 1094.604056, + 11.94538916015625, + -0.378124999999999, + -4.516129032258064, + 4.459677419354839, + 72.76781969905878, + -23.156245026251234, + -10.45458221513907, + 10.866032677988908, + 0.0 + ], + [ + 1094.624047, + 11.92025927734375, + -0.378124999999999, + -4.527859237536656, + 4.471260997067449, + 72.5546135501275, + -22.94210376263166, + -10.426528774490219, + 10.847330384223008, + 0.0 + ], + [ + 1094.644062, + 11.93282421875, + -0.378124999999999, + -4.527859237536656, + 4.471260997067449, + 72.3460829746377, + -22.716741122752545, + -10.426528774490219, + 10.940841853052516, + 0.0 + ], + [ + 1094.664026, + 11.94538916015625, + -0.37916666666666565, + -4.527859237536656, + 4.471260997067449, + 72.12633102288834, + -22.49137848287343, + -10.45458221513907, + 11.062406762530877, + 0.0 + ], + [ + 1094.684056, + 11.913976806640624, + -0.37916666666666565, + -4.539589442815249, + 4.520674486803519, + 71.91031952989218, + -22.271626531124085, + -10.520040243319727, + 11.053055615647926, + 0.0 + ], + [ + 1094.704104, + 11.94538916015625, + -0.3802083333333323, + -4.539589442815249, + 4.520674486803519, + 71.69898361033749, + -22.054679923439622, + -10.594849418383333, + 11.025002174999074, + 0.0 + ], + [ + 1094.724102, + 11.951671630859375, + -0.3802083333333323, + -4.551319648093841, + 4.532355816226784, + 71.4867125760945, + -21.833992857001984, + -10.66030744656399, + 11.081109056296778, + 0.0 + ], + [ + 1094.744086, + 11.913976806640624, + -0.3802083333333323, + -4.551319648093841, + 4.532355816226784, + 71.27724688591641, + -21.613305790564343, + -10.679009740329892, + 11.043704468764977, + 0.0 + ], + [ + 1094.764049, + 11.964236572265625, + -0.381249999999999, + -4.551319648093841, + 4.532355816226784, + 71.06030027823195, + -21.396359182879884, + -10.679009740329892, + 10.922139559286615, + 0.0 + ], + [ + 1094.784085, + 11.882564453125, + -0.381249999999999, + -4.574780058651026, + 4.555718475073314, + 70.84428878523578, + -21.181282804572014, + -10.66030744656399, + 10.903437265520711, + 0.0 + ], + [ + 1094.804069, + 11.901411865234374, + -0.38229166666666564, + -4.574780058651026, + 4.555718475073314, + 70.6292124069279, + -20.957790394069487, + -10.65095629968104, + 10.978246440584321, + 0.0 + ], + [ + 1094.824033, + 11.9579541015625, + -0.38229166666666564, + -4.586510263929618, + 4.567399804496579, + 70.41226579924346, + -20.738973557008435, + -10.66030744656399, + 10.968895293701369, + 0.0 + ], + [ + 1094.844073, + 11.89512939453125, + -0.38229166666666564, + -4.586510263929618, + 4.586510263929618, + 70.19157873280581, + -20.516416261194205, + -10.707063180978745, + 10.950192999935467, + 0.0 + ], + [ + 1094.864099, + 11.888846923828124, + -0.3833333333333323, + -4.586510263929618, + 4.586510263929618, + 69.97369701043306, + -20.29666430944486, + -10.763170062276451, + 11.006299881233172, + 0.0 + ], + [ + 1094.884061, + 11.92025927734375, + -0.3833333333333323, + -4.598240469208211, + 4.598240469208211, + 69.75768551743688, + -20.07410701363063, + -10.819276943574154, + 11.053055615647926, + 0.0 + ], + [ + 1094.904069, + 11.86999951171875, + -0.38437499999999897, + -4.598240469208211, + 4.598240469208211, + 69.54073890975243, + -19.856225291257875, + -10.866032677988908, + 11.006299881233172, + 0.0 + ], + [ + 1094.924086, + 11.913976806640624, + -0.38437499999999897, + -4.609970674486803, + 4.609970674486803, + 69.32659764613285, + -19.619641275119218, + -10.87538382487186, + 11.081109056296778, + 0.0 + ], + [ + 1094.944064, + 11.92025927734375, + -0.38437499999999897, + -4.609970674486803, + 4.609970674486803, + 69.10965103844839, + -19.400824438058166, + -10.85668153110596, + 11.155918231360387, + 0.0 + ], + [ + 1094.964077, + 11.89512939453125, + -0.38541666666666563, + -4.609970674486803, + 4.609970674486803, + 68.8973800042054, + -19.171721339425872, + -10.828628090457107, + 11.249429700189895, + 0.0 + ], + [ + 1094.985657, + 11.94538916015625, + -0.38541666666666563, + -4.621700879765395, + 4.621700879765395, + 68.68510896996243, + -18.95103427298823, + -10.800574649808253, + 11.230727406423993, + 0.0 + ], + [ + 1095.004057, + 11.89512939453125, + -0.38541666666666563, + -4.621700879765395, + 4.583186705767351, + 68.68510896996243, + -18.95103427298823, + -10.800574649808253, + 11.230727406423993, + 0.0 + ], + [ + 1095.024119, + 11.826022216796874, + -0.3864583333333323, + -4.621700879765395, + 4.583186705767351, + 68.2512157545935, + -18.491892961035344, + -10.744467768510548, + 11.39904805031711, + 0.0 + ], + [ + 1095.044111, + 11.926541748046875, + -0.3864583333333323, + -4.6141251221896376, + 4.594819159335288, + 68.03707449097394, + -18.26746543584452, + -10.744467768510548, + 11.342941169019403, + 0.0 + ], + [ + 1095.064098, + 11.857434570312499, + -0.38749999999999896, + -4.6141251221896376, + 4.594819159335288, + 67.82199811266607, + -18.03368676377075, + -10.735116621627597, + 11.380345756551208, + 0.0 + ], + [ + 1095.08443, + 11.89512939453125, + -0.38749999999999896, + -4.6258064516129025, + 4.606451612903226, + 67.61440265186455, + -17.808324123891634, + -10.725765474744646, + 11.42710149096596, + 0.0 + ], + [ + 1095.104242, + 11.9076943359375, + -0.38749999999999896, + -4.6258064516129025, + 4.606451612903226, + 67.61440265186455, + -17.808324123891634, + -10.725765474744646, + 11.42710149096596, + 0.0 + ], + [ + 1095.124069, + 11.876281982421874, + -0.3885416666666656, + -4.6258064516129025, + 4.606451612903226, + 67.40213161762156, + -17.578285910571044, + -10.707063180978745, + 11.445803784731863, + 0.0 + ], + [ + 1095.144101, + 11.9076943359375, + -0.3885416666666656, + -4.637487781036167, + 4.618084066471163, + 66.97384909038242, + -17.117274369241564, + -10.641605152798089, + 11.492559519146617, + 0.0 + ], + [ + 1095.164054, + 11.926541748046875, + -0.3895833333333323, + -4.637487781036167, + 4.637487781036167, + 66.76531851489261, + -16.889106385297563, + -10.622902859032186, + 11.455154931614814, + 0.0 + ], + [ + 1095.184046, + 11.863717041015624, + -0.3895833333333323, + -4.649169110459432, + 4.649169110459432, + 66.54556656314327, + -16.657197942600384, + -10.622902859032186, + 11.520612959795471, + 0.0 + ], + [ + 1095.204098, + 11.926541748046875, + -0.3895833333333323, + -4.649169110459432, + 4.649169110459432, + 66.32394438201733, + -16.42154904115002, + -10.65095629968104, + 11.576719841093174, + 0.0 + ], + [ + 1095.224074, + 11.857434570312499, + -0.39062499999999895, + -4.649169110459432, + 4.649169110459432, + 66.10699777433287, + -16.188705483764544, + -10.707063180978745, + 11.64217786927383, + 0.0 + ], + [ + 1095.24561, + 11.913976806640624, + -0.39062499999999895, + -4.660850439882697, + 4.660850439882697, + 65.88631070789523, + -15.956797041067363, + -10.7725212091594, + 11.623475575507928, + 0.0 + ], + [ + 1095.264102, + 11.913976806640624, + -0.3916666666666656, + -4.660850439882697, + 4.660850439882697, + 65.88631070789523, + -15.956797041067363, + -10.7725212091594, + 11.623475575507928, + 0.0 + ], + [ + 1095.284121, + 11.863717041015624, + -0.3916666666666656, + -4.672531769305962, + 4.672531769305962, + 65.4542877219029, + -15.487369467543228, + -10.88473497175481, + 11.698284750571537, + 0.0 + ], + [ + 1095.304105, + 11.86999951171875, + -0.3916666666666656, + -4.672531769305962, + 4.672531769305962, + 65.23921134359503, + -15.253590795469457, + -10.894086118637762, + 11.679582456805635, + 0.0 + ], + [ + 1095.324046, + 11.951671630859375, + -0.39270833333333227, + -4.672531769305962, + 4.652981427174976, + 65.02413496528716, + -15.011396091201028, + -10.88473497175481, + 11.773093925635143, + 0.0 + ], + [ + 1095.344113, + 11.857434570312499, + -0.39270833333333227, + -4.684213098729227, + 4.664613880742913, + 64.8053181282261, + -14.773876960374077, + -10.85668153110596, + 11.819849660049897, + 0.0 + ], + [ + 1095.364094, + 11.951671630859375, + -0.39270833333333227, + -4.684213098729227, + 4.664613880742913, + 64.5780852589704, + -14.536357829547125, + -10.837979237340056, + 11.847903100698751, + 0.0 + ], + [ + 1095.384122, + 11.926541748046875, + -0.39374999999999893, + -4.684213098729227, + 4.664613880742913, + 64.35926842190935, + -14.298838698720173, + -10.847330384223008, + 11.885307688230553, + 0.0 + ], + [ + 1095.404069, + 11.863717041015624, + -0.39374999999999893, + -4.695894428152492, + 4.67624633431085, + 64.13858135547171, + -14.065995141334696, + -10.894086118637762, + 11.866605394464653, + 0.0 + ], + [ + 1095.424103, + 11.901411865234374, + -0.3947916666666656, + -4.695894428152492, + 4.67624633431085, + 63.91695917434578, + -13.829411125196039, + -10.959544146818418, + 11.801147366283995, + 0.0 + ], + [ + 1095.444056, + 11.86999951171875, + -0.3947916666666656, + -4.707575757575757, + 4.6878787878787875, + 63.69159653446666, + -13.590956879680792, + -11.025002174999074, + 11.82920080693285, + 0.0 + ], + [ + 1095.464083, + 11.86999951171875, + -0.3947916666666656, + -4.707575757575757, + 4.6878787878787875, + 63.469974353340724, + -13.359983551671906, + -11.07175790941383, + 11.754391631869241, + 0.0 + ], + [ + 1095.484094, + 11.901411865234374, + -0.39583333333333226, + -4.707575757575757, + 4.6878787878787875, + 63.25022240159138, + -13.117788847403478, + -11.109162496945633, + 11.791796219401045, + 0.0 + ], + [ + 1095.50417, + 11.863717041015624, + -0.39583333333333226, + -4.719257086999022, + 4.699511241446725, + 63.02018418827079, + -12.884010175329706, + -11.127864790711532, + 11.838551953815799, + 0.0 + ], + [ + 1095.524239, + 11.882564453125, + -0.3968749999999989, + -4.719257086999022, + 4.699511241446725, + 62.7892108602619, + -12.64929638856764, + -11.165269378243337, + 11.810498513166948, + 0.0 + ], + [ + 1095.544143, + 11.913976806640624, + -0.3968749999999989, + -4.742619745845552, + 4.7227761485826, + 62.55543218818813, + -12.411777257740688, + -11.221376259541042, + 11.801147366283995, + 0.0 + ], + [ + 1095.564366, + 11.851152099609374, + -0.3968749999999989, + -4.742619745845552, + 4.7227761485826, + 62.31510771329629, + -12.174258126913736, + -11.324238875253503, + 11.8572542475817, + 0.0 + ], + [ + 1095.584129, + 11.89512939453125, + -0.3979166666666656, + -4.742619745845552, + 4.7227761485826, + 62.31510771329629, + -12.174258126913736, + -11.324238875253503, + 11.8572542475817, + 0.0 + ], + [ + 1095.604071, + 11.913976806640624, + -0.3979166666666656, + -4.754301075268817, + 4.734408602150538, + 62.08226415591081, + -11.934868766710194, + -11.445803784731863, + 11.847903100698751, + 0.0 + ], + [ + 1095.624077, + 11.838587158203124, + -0.39895833333333225, + -4.754301075268817, + 4.734408602150538, + 61.62125261458134, + -11.450479358173338, + -11.623475575507928, + 11.988170303943013, + 0.0 + ], + [ + 1095.644068, + 11.939106689453125, + -0.39895833333333225, + -4.765982404692082, + 4.746041055718475, + 61.394954860013925, + -11.19706327764537, + -11.651529016156783, + 12.128437507187277, + 0.0 + ], + [ + 1095.664096, + 11.857434570312499, + -0.39895833333333225, + -4.765982404692082, + 4.746041055718475, + 61.164916646693335, + -10.956738802753533, + -11.623475575507928, + 12.175193241602031, + 0.0 + ], + [ + 1095.684308, + 11.882564453125, + -0.3999999999999989, + -4.765982404692082, + 4.746041055718475, + 60.9245921718015, + -10.70612806629045, + -11.586070987976127, + 12.27805585731449, + 0.0 + ], + [ + 1095.704071, + 11.93282421875, + -0.3999999999999989, + -4.777663734115347, + 4.757673509286413, + 60.689878385039435, + -10.455517329827366, + -11.567368694210225, + 12.352865032378098, + 0.0 + ], + [ + 1095.724109, + 11.876281982421874, + -0.4010416666666656, + -4.777663734115347, + 4.757673509286413, + 60.457034827653956, + -10.209582166805758, + -11.586070987976127, + 12.399620766792852, + 0.0 + ], + [ + 1095.744071, + 11.844869628906249, + -0.4010416666666656, + -4.789345063538612, + 4.76930596285435, + 60.22512638495677, + -9.958971430342675, + -11.632826722390881, + 12.380918473026949, + 0.0 + ], + [ + 1095.764056, + 11.93282421875, + -0.4010416666666656, + -4.789345063538612, + 4.76930596285435, + 59.99041259819471, + -9.710230923256182, + -11.670231309922682, + 12.48378108873941, + 0.0 + ], + [ + 1095.784093, + 11.863717041015624, + -0.40208333333333224, + -4.789345063538612, + 4.76930596285435, + 59.76504995831559, + -9.4596201867931, + -11.698284750571537, + 12.47442994185646, + 0.0 + ], + [ + 1095.804109, + 11.888846923828124, + -0.40208333333333224, + -4.801026392961877, + 4.780938416422288, + 59.53688197437159, + -9.214620138459786, + -11.660880163039733, + 12.390269619909901, + 0.0 + ], + [ + 1095.824102, + 11.93282421875, + -0.40208333333333224, + -4.801026392961877, + 4.780938416422288, + 59.30403841698611, + -8.959333828555227, + -11.61412442862498, + 12.511834529388262, + 0.0 + ], + [ + 1095.844102, + 11.876281982421874, + -0.4031249999999989, + -4.801026392961877, + 4.780938416422288, + 59.069324630224045, + -8.710593321468734, + -11.558017547327273, + 12.49313223562236, + 0.0 + ], + [ + 1095.864088, + 11.92025927734375, + -0.4031249999999989, + -4.8127077223851416, + 4.792570869990224, + 58.82712992595562, + -8.46185281438224, + -11.548666400444322, + 12.465078794973508, + 0.0 + ], + [ + 1095.884063, + 11.863717041015624, + -0.40416666666666556, + -4.8127077223851416, + 4.792570869990224, + 58.585870336375486, + -8.207501619165978, + -11.595422134859078, + 12.511834529388262, + 0.0 + ], + [ + 1095.904089, + 11.876281982421874, + -0.40416666666666556, + -4.8243890518084065, + 4.804203323558162, + 58.347416090860236, + -7.958761112079484, + -11.698284750571537, + 12.577292557568917, + 0.0 + ], + [ + 1095.924102, + 11.901411865234374, + -0.40416666666666556, + -4.8243890518084065, + 4.804203323558162, + 58.11363741878647, + -7.7034748021749255, + -11.791796219401045, + 12.549239116920067, + 0.0 + ], + [ + 1095.944059, + 11.851152099609374, + -0.4052083333333322, + -4.8243890518084065, + 4.804203323558162, + 57.88266409077758, + -7.445383148205481, + -11.866605394464653, + 12.652101732632525, + 0.0 + ], + [ + 1095.964076, + 11.851152099609374, + -0.4052083333333322, + -4.8360703812316705, + 4.815835777126099, + 57.64795030401552, + -7.1882266089243325, + -11.866605394464653, + 12.745613201462033, + 0.0 + ], + [ + 1095.984174, + 11.93282421875, + -0.4062499999999989, + -4.8360703812316705, + 4.815835777126099, + 57.41417163194174, + -6.926394496201708, + -11.819849660049897, + 12.811071229642689, + 0.0 + ], + [ + 1096.004065, + 11.863717041015624, + -0.4062499999999989, + -4.8477517106549355, + 4.827468230694037, + 57.18039295986797, + -6.6711081862971495, + -11.754391631869241, + 12.867178110940396, + 0.0 + ], + [ + 1096.024096, + 11.92025927734375, + -0.4062499999999989, + -4.8477517106549355, + 4.827468230694037, + 56.94474405841761, + -6.410211188262821, + -11.707635897454487, + 12.941987286004002, + 0.0 + ], + [ + 1096.044265, + 11.863717041015624, + -0.40729166666666555, + -4.8477517106549355, + 4.827468230694037, + 56.705354698214066, + -6.146508846163606, + -11.698284750571537, + 12.988743020418756, + 0.0 + ], + [ + 1096.064124, + 11.851152099609374, + -0.40729166666666555, + -4.8594330400782, + 4.839100684261974, + 56.46783556738711, + -5.9080546006483585, + -11.735689338103338, + 12.792368935876787, + 0.0 + ], + [ + 1096.08409, + 11.89512939453125, + -0.4083333333333322, + -4.8594330400782, + 4.839100684261974, + 56.23312178062505, + -5.664924781691636, + -11.773093925635143, + 12.614697145100722, + 0.0 + ], + [ + 1096.104062, + 11.863717041015624, + -0.4083333333333322, + -4.871114369501466, + 4.850733137829913, + 55.99653776448639, + -5.537749184083505, + -11.810498513166948, + 11.333590022136452, + 0.0 + ], + [ + 1096.124027, + 11.844869628906249, + -0.4083333333333322, + -4.871114369501466, + 4.830351906158358, + 55.7674346658541, + -5.2721766126077, + -11.801147366283995, + 11.380345756551208, + 0.0 + ], + [ + 1096.144084, + 11.876281982421874, + -0.4093749999999989, + -4.871114369501466, + 4.830351906158358, + 55.526175076273965, + -5.021565876144616, + -11.773093925635143, + 11.249429700189895, + 0.0 + ], + [ + 1096.164124, + 11.826022216796874, + -0.4093749999999989, + -4.882795698924731, + 4.8419354838709685, + 55.2905261748236, + -4.753187960603927, + -11.754391631869241, + 11.558017547327273, + 0.0 + ], + [ + 1096.184218, + 11.832304687499999, + -0.41041666666666554, + -4.882795698924731, + 4.8419354838709685, + 55.049266585243465, + -4.484810045063236, + -11.763742778752192, + 11.810498513166948, + 0.0 + ], + [ + 1096.204066, + 11.89512939453125, + -0.41041666666666554, + -4.894477028347996, + 4.853519061583579, + 54.80146119284527, + -4.219237473587432, + -11.819849660049897, + 13.175765958077774, + 0.0 + ], + [ + 1096.224097, + 11.838587158203124, + -0.41041666666666554, + -4.894477028347996, + 4.853519061583579, + 54.56113671795343, + -3.953664902111627, + -11.904009981996456, + 13.166414811194823, + 0.0 + ], + [ + 1096.244075, + 11.89512939453125, + -0.4114583333333322, + -4.894477028347996, + 4.853519061583579, + 54.312396210866936, + -3.6852869865709375, + -12.006872597708915, + 13.36278889573679, + 0.0 + ], + [ + 1096.264132, + 11.844869628906249, + -0.4114583333333322, + -4.906158357771261, + 4.865102639296189, + 54.071136621286804, + -3.4187793004068374, + -12.100384066538423, + 13.35343774885384, + 0.0 + ], + [ + 1096.284442, + 11.832304687499999, + -0.41249999999999887, + -4.906158357771261, + 4.865102639296189, + 53.826136572953494, + -3.1475960408012624, + -12.15649094783613, + 13.36278889573679, + 0.0 + ], + [ + 1096.304055, + 11.86999951171875, + -0.41249999999999887, + -4.917839687194526, + 4.876686217008799, + 53.826136572953494, + -3.1475960408012624, + -12.15649094783613, + 13.36278889573679, + 0.0 + ], + [ + 1096.324071, + 11.857434570312499, + -0.41249999999999887, + -4.917839687194526, + 4.876686217008799, + 53.337071590975164, + -2.614580668473063, + -12.193895535367933, + 13.428246923917445, + 0.0 + ], + [ + 1096.344356, + 11.819739746093749, + -0.41354166666666553, + -4.917839687194526, + 4.876686217008799, + 53.09394177201844, + -2.3518134410621436, + -12.193895535367933, + 13.34408660197089, + 0.0 + ] + ], + "fast-forward": [ + [ + 1139.024078, + 12.52337646484375, + 0.0, + 0.0, + 0.0, + 26.435692238102106, + 22.417504422498116, + 0.0, + 0.0, + 0.0 + ], + [ + 1139.044105, + 12.52337646484375, + 0.5, + 0.0, + 0.0, + 26.435692238102106, + 22.417504422498116, + 0.0, + 0.0, + 0.0 + ], + [ + 1139.06418, + 11.7569150390625, + 0.5, + 6.293841642228739, + -6.318817204301076, + 26.435692238102106, + 22.417504422498116, + 0.0, + 0.0, + 0.0 + ], + [ + 1139.084092, + 11.480486328125, + 0.5, + 6.293841642228739, + -6.318817204301076, + 26.435692238102106, + 22.417504422498116, + 0.0, + 0.0, + 0.0 + ], + [ + 1139.104097, + 11.292012207031249, + 0.5, + 6.293841642228739, + -6.318817204301076, + 26.4366273527904, + 22.370748688083363, + 0.0, + -0.4675573441475434, + 0.0 + ], + [ + 1139.124033, + 11.298294677734374, + 0.5, + 6.293841642228739, + -6.318817204301076, + 26.444108270296763, + 22.356721967758936, + 0.009351146882950868, + -0.6078245473918065, + 0.0 + ], + [ + 1139.144103, + 11.4302265625, + 0.5, + 6.293841642228739, + -6.318817204301076, + 26.4553296465563, + 22.334279215239853, + 0.05610688129770522, + -0.8416032194655781, + 0.0 + ], + [ + 1139.164058, + 11.342271972656249, + 0.5, + 6.293841642228739, + -5.544574780058651, + 26.469356366880728, + 22.310901348032477, + 0.14026720324426303, + -1.0753818915393498, + 0.0 + ], + [ + 1139.184054, + 11.4050966796875, + 0.5, + 6.293841642228739, + -5.544574780058651, + 26.48618843127004, + 22.28004256331874, + 0.25248096583967344, + -1.3839697386767287, + 0.0 + ], + [ + 1139.204061, + 11.4302265625, + 0.5, + 5.6944281524926685, + -5.544574780058651, + 26.507696069100827, + 22.237027287657167, + 0.4208016097327891, + -1.346565151144925, + 0.0 + ], + [ + 1139.224116, + 11.373684326171874, + 0.5, + 5.6944281524926685, + -5.544574780058651, + 26.536684624437974, + 22.189336438554115, + 0.5891222536259046, + -1.6738552920482055, + 0.0 + ], + [ + 1139.24408, + 11.41766162109375, + 0.5, + 5.6944281524926685, + -5.544574780058651, + 26.571283867904892, + 22.142580704139363, + 0.7948474850508238, + -1.9169851110049279, + 0.0 + ], + [ + 1139.264065, + 11.449073974609375, + 0.5, + 5.6944281524926685, + -5.544574780058651, + 26.61149379950158, + 22.089279166906543, + 1.0192750102416446, + -2.206870664376405, + 0.0 + ], + [ + 1139.284054, + 11.361119384765624, + 0.5, + 5.6944281524926685, + -5.544574780058651, + 26.656379304539747, + 22.030366941543953, + 1.2717559760813182, + -2.4874050708649307, + 0.0 + ], + [ + 1139.304112, + 11.4302265625, + 0.5, + 5.6944281524926685, + -5.544574780058651, + 26.7031350389545, + 21.973324945557952, + 1.5335880888039424, + -2.6370234209921453, + 0.0 + ], + [ + 1139.32408, + 11.4050966796875, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 26.75456634681073, + 21.91254249081877, + 1.795420201526567, + -2.777290624236408, + 0.0 + ], + [ + 1139.344077, + 11.39253173828125, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 26.80973811342014, + 21.848954692014704, + 2.029198873600339, + -2.9362601212465727, + 0.0 + ], + [ + 1139.364278, + 11.436509033203125, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 26.867715224094436, + 21.78069131976916, + 2.2536263987911593, + -3.095229618256737, + 0.0 + ], + [ + 1139.384086, + 11.361119384765624, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 26.932238137586797, + 21.70681725939385, + 2.4500004833331275, + -3.2448479683839517, + 0.0 + ], + [ + 1139.404108, + 11.292012207031249, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 27.001436624520633, + 21.628267625577063, + 2.646374567875096, + -3.4505731998088707, + 0.0 + ], + [ + 1139.424074, + 11.386249267578124, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 27.075310684895946, + 21.542237074253915, + 2.8520997993000146, + -3.7030541656485436, + 0.0 + ], + [ + 1139.444112, + 11.398814208984374, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 27.149184745271256, + 21.45340117886588, + 3.0671761776078847, + -3.9461839846052666, + 0.0 + ], + [ + 1139.464411, + 11.41766162109375, + 0.5, + 5.6944281524926685, + -5.594525904203323, + 27.225864149711455, + 21.363630168789555, + 3.272901409032804, + -4.170611509796087, + 0.0 + ], + [ + 1139.484066, + 11.386249267578124, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.310959586346307, + 21.270118699960044, + 3.4692754935747723, + -4.357634447455105, + 0.0 + ], + [ + 1139.504102, + 11.36740185546875, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.39418479360457, + 21.183153033948603, + 3.646947284350839, + -4.451145916284613, + 0.0 + ], + [ + 1139.524086, + 11.304577148437499, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.483955803680896, + 21.076549959482964, + 3.8246190751269054, + -4.656871147709532, + 0.0 + ], + [ + 1139.544173, + 11.342271972656249, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.577467272510408, + 20.965271311575847, + 3.992939719020021, + -4.881298672900353, + 0.0 + ], + [ + 1139.564103, + 11.323424560546874, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.67752454415798, + 20.84651174616237, + 4.170611509796087, + -5.17118422627183, + 0.0 + ], + [ + 1139.584206, + 11.4050966796875, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.777581815805554, + 20.73429798356696, + 4.366985594338056, + -5.358207163930848, + 0.0 + ], + [ + 1139.604073, + 11.298294677734374, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.88137954620631, + 20.617408647530073, + 4.563359678880024, + -5.657443864185275, + 0.0 + ], + [ + 1139.624101, + 11.317142089843749, + 0.5, + 5.6944281524926685, + -5.644477028347996, + 27.98424216191877, + 20.489297935233648, + 4.7410314696560905, + -5.881871389376096, + 0.0 + ], + [ + 1139.644057, + 11.386249267578124, + 0.5, + 5.6944281524926685, + -5.6195014662756595, + 28.093650580449296, + 20.367733025755285, + 4.909352113549206, + -5.975382858205604, + 0.0 + ], + [ + 1139.664069, + 11.285729736328125, + 0.5, + 5.6944281524926685, + -5.6195014662756595, + 28.206799457733, + 20.231206281264203, + 5.05897046367642, + -6.162405795864623, + 0.0 + ], + [ + 1139.684065, + 11.411379150390625, + 0.5, + 5.719403714565004, + -5.6195014662756595, + 28.32275367908159, + 20.100290224902892, + 5.208588813803634, + -6.340077586640689, + 0.0 + ], + [ + 1139.704107, + 11.398814208984374, + 0.5, + 5.719403714565004, + -5.6195014662756595, + 28.443383473871656, + 19.962828365723514, + 5.3675583108137985, + -6.555153964948559, + 0.0 + ], + [ + 1139.724067, + 11.3548369140625, + 0.5, + 5.719403714565004, + -5.6195014662756595, + 28.565883498038314, + 19.82630162123243, + 5.526527807823963, + -6.620611993129215, + 0.0 + ], + [ + 1139.74406, + 11.386249267578124, + 0.5, + 5.719403714565004, + -5.6195014662756595, + 28.69212398095815, + 19.679488615170104, + 5.704199598600029, + -6.882444105851839, + 0.0 + ], + [ + 1139.764063, + 11.4050966796875, + 0.5, + 5.719403714565004, + -5.6195014662756595, + 28.815559119813102, + 19.53361072379607, + 5.8631690956101945, + -6.975955574681349, + 0.0 + ], + [ + 1139.784065, + 11.3548369140625, + 0.5, + 5.719403714565004, + -5.6195014662756595, + 28.9492805202393, + 19.373706112097608, + 6.02213859262036, + -7.2564899811698735, + 0.0 + ], + [ + 1139.804036, + 11.436509033203125, + 0.5, + 5.719403714565004, + -5.644477028347996, + 29.08019657660061, + 19.216606844464035, + 6.162405795864623, + -7.462215212594793, + 0.0 + ], + [ + 1139.82407, + 11.335989501953124, + 0.5, + 5.719403714565004, + -5.644477028347996, + 29.218593550468285, + 19.053896888700688, + 6.293321852225935, + -7.733398472200368, + 0.0 + ], + [ + 1139.844119, + 11.386249267578124, + 0.5, + 5.744379276637341, + -5.644477028347996, + 29.355120294959367, + 18.89399227700223, + 6.433589055470198, + -7.86431452856168, + 0.0 + ], + [ + 1139.864226, + 11.4050966796875, + 0.5, + 5.744379276637341, + -5.644477028347996, + 29.49912795695681, + 18.73408766530377, + 6.573856258714461, + -7.995230584922992, + 0.0 + ], + [ + 1139.884086, + 11.4050966796875, + 0.5, + 5.744379276637341, + -5.644477028347996, + 29.64126538957766, + 18.57231282422872, + 6.723474608841674, + -8.004581731805944, + 0.0 + ], + [ + 1139.904073, + 11.4050966796875, + 0.5, + 5.744379276637341, + -5.644477028347996, + 29.794624198458056, + 18.4049272950239, + 6.863741812085937, + -8.116795494401355, + 0.0 + ], + [ + 1139.924125, + 11.41766162109375, + 0.5, + 5.744379276637341, + -5.644477028347996, + 29.94611277796186, + 18.231931077689307, + 7.013360162213152, + -8.229009256996765, + 0.0 + ], + [ + 1139.944108, + 11.4050966796875, + 0.5, + 5.744379276637341, + -5.644477028347996, + 30.108822733725205, + 18.05799974566642, + 7.172329659223316, + -8.359925313358076, + 0.0 + ], + [ + 1139.964073, + 11.4302265625, + 0.5, + 5.744379276637341, + -5.669452590420333, + 30.269662460111963, + 17.87752261082547, + 7.368703743765285, + -8.565650544782995, + 0.0 + ], + [ + 1139.984059, + 11.4050966796875, + 0.5, + 5.744379276637341, + -5.669452590420333, + 30.435177759940192, + 17.694240131919635, + 7.574428975190203, + -8.790078069973816, + 0.0 + ], + [ + 1140.004109, + 11.4050966796875, + 0.5, + 5.744379276637341, + -5.669452590420333, + 30.602563289145014, + 17.506282079572323, + 7.780154206615123, + -8.883589538803324, + 0.0 + ], + [ + 1140.024074, + 11.46792138671875, + 0.5, + 5.744379276637341, + -5.669452590420333, + 30.768078588973243, + 17.32767517410796, + 7.976528291157091, + -9.04255903581349, + 0.0 + ], + [ + 1140.044117, + 11.423944091796875, + 0.5, + 5.744379276637341, + -5.669452590420333, + 30.937334347554653, + 17.137846892384058, + 8.126146641284304, + -9.201528532823655, + 0.0 + ], + [ + 1140.064106, + 11.461638916015625, + 0.5, + 5.744379276637341, + -5.669452590420333, + 31.106590106136064, + 16.949888840036746, + 8.238360403879716, + -9.285688854770212, + 0.0 + ], + [ + 1140.084252, + 11.486768798828125, + 0.5, + 5.744379276637341, + -5.669452590420333, + 31.281456552847246, + 16.755384984871366, + 8.322520725826273, + -9.388551470482673, + 0.0 + ], + [ + 1140.104078, + 11.386249267578124, + 0.5, + 5.744379276637341, + -5.669452590420333, + 31.464739031753084, + 16.55714067095281, + 8.41603219465578, + -9.594276701907592, + 0.0 + ], + [ + 1140.12421, + 11.5056162109375, + 0.5, + 5.744379276637341, + -5.644477028347996, + 31.648021510658918, + 16.36263681578743, + 8.528245957251192, + -9.641032436322345, + 0.0 + ], + [ + 1140.144083, + 11.555875976562499, + 0.5, + 5.744379276637341, + -5.644477028347996, + 31.83317421894135, + 16.163457387180575, + 8.687215454261356, + -9.734543905151854, + 0.0 + ], + [ + 1140.164063, + 11.511898681640625, + 0.5, + 5.769354838709678, + -5.644477028347996, + 32.02019715660036, + 15.956797041067363, + 8.855536098154474, + -9.930917989693823, + 0.0 + ], + [ + 1140.184114, + 11.54331103515625, + 0.5, + 5.769354838709678, + -5.644477028347996, + 32.21189566770086, + 15.748266465577558, + 9.033207888930539, + -10.080536339821036, + 0.0 + ], + [ + 1140.204055, + 11.49305126953125, + 0.5, + 5.769354838709678, + -5.644477028347996, + 32.398918605359874, + 15.539735890087753, + 9.182826239057754, + -10.174047808650545, + 0.0 + ], + [ + 1140.224064, + 11.562158447265624, + 0.5, + 5.769354838709678, + -5.644477028347996, + 32.593422460525254, + 15.328399970533063, + 9.304391148536114, + -10.351719599426612, + 0.0 + ], + [ + 1140.24402, + 11.574723388671874, + 0.5, + 5.769354838709678, + -5.644477028347996, + 32.78325074224915, + 15.116128936290078, + 9.388551470482673, + -10.482635655787924, + 0.0 + ], + [ + 1140.264111, + 11.474203857421875, + 0.5, + 5.769354838709678, + -5.644477028347996, + 32.976819482726235, + 14.898247213917324, + 9.444658351780378, + -10.576147124617432, + 0.0 + ], + [ + 1140.284151, + 11.49305126953125, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 33.17319356726821, + 14.683170835609454, + 9.519467526843984, + -10.641605152798089, + 0.0 + ], + [ + 1140.30406, + 11.574723388671874, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 33.37330811056336, + 14.453132622288862, + 9.594276701907592, + -10.753818915393499, + 0.0 + ], + [ + 1140.324102, + 11.54331103515625, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 33.57996845667657, + 14.240861588045878, + 9.697139317620051, + -10.866032677988908, + 0.0 + ], + [ + 1140.344026, + 11.555875976562499, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 33.786628802789785, + 14.017369177543351, + 9.818704227098412, + -10.98759758746727, + 0.0 + ], + [ + 1140.3641, + 11.524463623046875, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 33.99796472234447, + 13.792006537664236, + 9.958971430342675, + -11.081109056296778, + 0.0 + ], + [ + 1140.384073, + 11.51818115234375, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 34.208365527210866, + 13.56477366840853, + 10.10858978046989, + -11.165269378243337, + 0.0 + ], + [ + 1140.4041, + 11.555875976562499, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 34.423441905518736, + 13.336605684464528, + 10.239505836831203, + -11.277483140838747, + 0.0 + ], + [ + 1140.424045, + 11.524463623046875, + 0.5, + 5.769354838709678, + -5.6195014662756595, + 34.638518283826606, + 13.103762127079053, + 10.379773040075463, + -11.370994609668257, + 0.0 + ], + [ + 1140.444094, + 11.499333740234375, + 0.5, + 5.769354838709678, + -5.744379276637341, + 34.85920535026425, + 12.8662429962521, + 10.501337949553825, + -11.511261812912519, + 0.0 + ], + [ + 1140.464112, + 11.599853271484374, + 0.5, + 5.769354838709678, + -5.744379276637341, + 35.080827531390185, + 12.631529209490033, + 10.632254005915138, + -11.586070987976127, + 0.0 + ], + [ + 1140.484068, + 11.5056162109375, + 0.5, + 5.769354838709678, + -5.744379276637341, + 35.30899551533418, + 12.391204734598196, + 10.7725212091594, + -11.763742778752192, + 0.0 + ], + [ + 1140.50409, + 11.51818115234375, + 0.5, + 5.769354838709678, + -5.744379276637341, + 35.53248792583671, + 12.145269571576588, + 10.894086118637762, + -11.913361128879407, + 0.0 + ], + [ + 1140.524109, + 11.568440917968749, + 0.5, + 5.769354838709678, + -5.744379276637341, + 35.758785680404124, + 11.898399293866685, + 11.015651028116123, + -12.053628332123669, + 0.0 + ], + [ + 1140.544068, + 11.524463623046875, + 0.5, + 5.769354838709678, + -5.744379276637341, + 35.99256435247789, + 11.644983213338717, + 11.137215937594485, + -12.221948976016785, + 0.0 + ], + [ + 1140.564114, + 11.51818115234375, + 0.5, + 5.769354838709678, + -5.744379276637341, + 36.22260256579848, + 11.396242706252224, + 11.249429700189895, + -12.343513885495145, + 0.0 + ], + [ + 1140.584099, + 11.524463623046875, + 0.5, + 5.769354838709678, + -5.744379276637341, + 36.454511008495665, + 11.14376174041255, + 11.352292315902355, + -12.465078794973508, + 0.0 + ], + [ + 1140.604089, + 11.511898681640625, + 0.5, + 5.769354838709678, + -5.6944281524926685, + 36.690159909946026, + 10.892215889261172, + 11.436452637848912, + -12.530536823154163, + 0.0 + ], + [ + 1140.624069, + 11.568440917968749, + 0.5, + 5.769354838709678, + -5.6944281524926685, + 36.92206835264321, + 10.636929579356613, + 11.511261812912519, + -12.614697145100722, + 0.0 + ], + [ + 1140.644078, + 11.449073974609375, + 0.5, + 5.794330400782014, + -5.6944281524926685, + 37.155847024716984, + 10.369486778504218, + 11.567368694210225, + -12.624048291983671, + 0.0 + ], + [ + 1140.664037, + 11.474203857421875, + 0.5, + 5.794330400782014, + -5.6944281524926685, + 37.391495926167345, + 10.124486730170906, + 11.604773281742027, + -12.70820861393023, + 0.0 + ], + [ + 1140.684079, + 11.54331103515625, + 0.5, + 5.794330400782014, + -5.6944281524926685, + 37.6290150569943, + 9.866395076201462, + 11.64217786927383, + -12.783017788993838, + 0.0 + ], + [ + 1140.704055, + 11.49305126953125, + 0.5, + 5.794330400782014, + -5.6944281524926685, + 37.872144875951015, + 9.599887390037361, + 11.698284750571537, + -12.932636139121051, + 0.0 + ], + [ + 1140.72406, + 11.54331103515625, + 0.5, + 5.794330400782014, + -5.6944281524926685, + 38.11714492428433, + 9.333379703873263, + 11.782445072518096, + -13.044849901716463, + 0.0 + ], + [ + 1140.744121, + 11.54331103515625, + 0.5, + 5.794330400782014, + -5.6944281524926685, + 38.36214497261764, + 9.065001788332571, + 11.894658835113505, + -13.175765958077774, + 0.0 + ], + [ + 1140.764116, + 11.524463623046875, + 0.5, + 5.794330400782014, + -5.669452590420333, + 38.61369082376902, + 8.792883414038702, + 12.006872597708915, + -13.325384308204988, + 0.0 + ], + [ + 1140.784069, + 11.549593505859374, + 0.5, + 5.794330400782014, + -5.669452590420333, + 38.86336644554381, + 8.520765039744832, + 12.128437507187277, + -13.446949217683349, + 0.0 + ], + [ + 1140.804049, + 11.46792138671875, + 0.5, + 5.794330400782014, + -5.669452590420333, + 39.11023672325371, + 8.244906206697781, + 12.231300122899736, + -13.549811833395808, + 0.0 + ], + [ + 1140.824069, + 11.5056162109375, + 0.5, + 5.794330400782014, + -5.669452590420333, + 39.35430165689873, + 7.966242029585845, + 12.306109297963344, + -13.68072788975712, + 0.0 + ], + [ + 1140.844414, + 11.637548095703124, + 0.5, + 5.794330400782014, + -5.669452590420333, + 39.602107049296926, + 7.687577852473909, + 12.352865032378098, + -13.764888211703678, + 0.0 + ], + [ + 1140.864071, + 11.49305126953125, + 0.5, + 5.794330400782014, + -5.669452590420333, + 39.855523129824896, + 7.399562528479022, + 12.390269619909901, + -13.933208855596796, + 0.0 + ], + [ + 1140.884095, + 11.54331103515625, + 0.5, + 5.794330400782014, + -5.669452590420333, + 40.10987432504116, + 7.119028121990496, + 12.427674207441704, + -14.017369177543353, + 0.0 + ], + [ + 1140.904099, + 11.593570800781249, + 0.5, + 5.794330400782014, + -5.669452590420333, + 40.36422552025742, + 6.839428830190265, + 12.465078794973508, + -14.054773765075154, + 0.0 + ], + [ + 1140.924026, + 11.581005859374999, + 0.5, + 5.794330400782014, + -5.719403714565004, + 40.62418740360346, + 6.556089079636854, + 12.530536823154163, + -14.082827205724008, + 0.0 + ], + [ + 1140.944278, + 11.537028564453125, + 0.5, + 5.794330400782014, + -5.719403714565004, + 40.87947371350802, + 6.271814214395148, + 12.614697145100722, + -14.195040968319418, + 0.0 + ], + [ + 1140.964093, + 11.574723388671874, + 0.5, + 5.794330400782014, + -5.719403714565004, + 41.14130582623064, + 5.984734005088556, + 12.70820861393023, + -14.148285233904666, + 0.0 + ], + [ + 1140.98414, + 11.49305126953125, + 0.5, + 5.794330400782014, + -5.719403714565004, + 41.3965921361352, + 5.686432419522423, + 12.792368935876787, + -14.325957024680731, + 0.0 + ], + [ + 1141.004158, + 11.555875976562499, + 0.5, + 5.794330400782014, + -5.719403714565004, + 41.66497005167589, + 5.377844572385045, + 12.867178110940396, + -14.456873081042044, + 0.0 + ], + [ + 1141.024209, + 11.51818115234375, + 0.5, + 5.794330400782014, + -5.719403714565004, + 41.93428308190487, + 5.1019857393379935, + 12.951338432886953, + -14.559735696754503, + 0.0 + ], + [ + 1141.045045, + 11.537028564453125, + 0.5, + 5.794330400782014, + -5.719403714565004, + 42.20546634151045, + 4.806489497836746, + 13.054201048599412, + -14.63454487181811, + 0.0 + ], + [ + 1141.064082, + 11.64383056640625, + 0.5, + 5.794330400782014, + -5.719403714565004, + 42.20546634151045, + 4.806489497836746, + 13.054201048599412, + -14.63454487181811, + 0.0 + ], + [ + 1141.084074, + 11.587288330078124, + 0.5, + 5.794330400782014, + -5.769354838709678, + 42.749703090098194, + 4.19679472106835, + 13.297330867556134, + -14.877674690774832, + 0.0 + ], + [ + 1141.104047, + 11.568440917968749, + 0.5, + 5.794330400782014, + -5.769354838709678, + 43.02743215252183, + 3.8919473326841514, + 13.418895777034496, + -14.989888453370241, + 0.0 + ], + [ + 1141.124041, + 11.631265625, + 0.5, + 5.81930596285435, + -5.769354838709678, + 43.30235587088059, + 3.596451091182904, + 13.521758392746957, + -15.055346481550897, + 0.0 + ], + [ + 1141.144117, + 11.612418212890624, + 0.5, + 5.81930596285435, + -5.769354838709678, + 43.58195516268082, + 3.302825079058247, + 13.605918714693514, + -15.055346481550897, + 0.0 + ], + [ + 1141.164066, + 11.637548095703124, + 0.5, + 5.81930596285435, + -5.769354838709678, + 43.85407353697469, + 3.004523493492114, + 13.68072788975712, + -14.989888453370241, + 0.0 + ], + [ + 1141.184071, + 11.662677978515624, + 0.5, + 5.81930596285435, + -5.769354838709678, + 44.1364781728398, + 2.690324958224965, + 13.755537064820729, + -14.933781572072537, + 0.0 + ], + [ + 1141.204069, + 11.624983154296874, + 0.5, + 5.81930596285435, + -5.769354838709678, + 44.41981792339322, + 2.403244748918373, + 13.830346239884335, + -14.915079278306635, + 0.0 + ], + [ + 1141.224078, + 11.681525390625, + 0.5, + 5.81930596285435, + -5.769354838709678, + 44.69941721519345, + 2.09933247522247, + 13.905155414947941, + -14.961835012721389, + 0.0 + ], + [ + 1141.24406, + 11.606135742187499, + 0.5, + 5.81930596285435, + -5.744379276637341, + 44.98556230981174, + 1.7916797427733864, + 13.970613443128597, + -15.083399922199751, + 0.0 + ], + [ + 1141.264089, + 11.61870068359375, + 0.5, + 5.81930596285435, + -5.744379276637341, + 45.26890206036516, + 1.4905728131423683, + 14.026720324426304, + -15.148857950380407, + 0.0 + ], + [ + 1141.284072, + 11.662677978515624, + 0.5, + 5.81930596285435, + -5.744379276637341, + 45.56813876061958, + 1.1847903100698751, + 14.101529499489908, + -15.214315978561064, + 0.0 + ], + [ + 1141.304061, + 11.624983154296874, + 0.5, + 5.81930596285435, + -5.744379276637341, + 45.86363500212083, + 0.8790078069973817, + 14.195040968319418, + -15.233018272326966, + 0.0 + ], + [ + 1141.324029, + 11.624983154296874, + 0.5, + 5.81930596285435, + -5.744379276637341, + 46.16100147299867, + 0.5741604186131833, + 14.325957024680731, + -15.251720566092866, + 0.0 + ], + [ + 1141.344066, + 11.687807861328125, + 0.5, + 5.81930596285435, + -5.744379276637341, + 46.45369237043503, + 0.26089699803432925, + 14.475575374807946, + -15.298476300507621, + 0.0 + ], + [ + 1141.364104, + 11.637548095703124, + 0.5, + 5.81930596285435, + -5.744379276637341, + 46.752929070689454, + -0.043950390349869084, + 14.625193724935158, + -15.345232034922375, + 0.0 + ], + [ + 1141.38406, + 11.606135742187499, + 0.5, + 5.81930596285435, + -5.744379276637341, + 47.061516917826836, + -0.355343581552133, + 14.765460928179422, + -15.40133891622008, + 0.0 + ], + [ + 1141.404176, + 11.64383056640625, + 0.5, + 5.81930596285435, + -5.769354838709678, + 47.362623847457854, + -0.6658016580661018, + 14.877674690774832, + -15.438743503751883, + 0.0 + ], + [ + 1141.424096, + 11.599853271484374, + 0.5, + 5.81930596285435, + -5.769354838709678, + 47.66747123584205, + -0.9771948492683658, + 14.97118615960434, + -15.50420153193254, + 0.0 + ], + [ + 1141.444098, + 11.687807861328125, + 0.5, + 5.81930596285435, + -5.769354838709678, + 47.96857816547307, + -1.2885880404706296, + 15.036644187784997, + -15.522903825698442, + 0.0 + ], + [ + 1141.464051, + 11.612418212890624, + 0.5, + 5.81930596285435, + -5.769354838709678, + 48.26594463635091, + -1.5971758876080084, + 15.0740487753168, + -15.51355267881549, + 0.0 + ], + [ + 1141.48408, + 11.593570800781249, + 0.5, + 5.81930596285435, + -5.769354838709678, + 48.565181336605335, + -1.9113744228751575, + 15.092751069082702, + -15.560308413230246, + 0.0 + ], + [ + 1141.504059, + 11.687807861328125, + 0.5, + 5.81930596285435, + -5.769354838709678, + 48.86722338092465, + -2.229313416895487, + 15.0740487753168, + -15.625766441410903, + 0.0 + ], + [ + 1141.524064, + 11.606135742187499, + 0.5, + 5.81930596285435, + -5.769354838709678, + 49.17955168681521, + -2.5481875256041118, + 15.055346481550897, + -15.719277910240411, + 0.0 + ], + [ + 1141.544068, + 11.555875976562499, + 0.5, + 5.81930596285435, + -5.769354838709678, + 49.49562045145895, + -2.867061634312736, + 15.083399922199751, + -15.766033644655163, + 0.0 + ], + [ + 1141.564061, + 11.687807861328125, + 0.5, + 5.81930596285435, + -5.794330400782014, + 49.81262433079098, + -3.186870857709656, + 15.195613684795163, + -15.896949701016476, + 0.0 + ], + [ + 1141.584085, + 11.612418212890624, + 0.5, + 5.81930596285435, + -5.794330400782014, + 50.12495263668154, + -3.5066800811065755, + 15.335880888039423, + -15.962407729197132, + 0.0 + ], + [ + 1141.604091, + 11.574723388671874, + 0.5, + 5.844281524926686, + -5.794330400782014, + 50.441956516013576, + -3.8274244191917903, + 15.50420153193254, + -15.990461169845984, + 0.0 + ], + [ + 1141.624142, + 11.66896044921875, + 0.5, + 5.844281524926686, + -5.794330400782014, + 50.75896039534561, + -4.144428298523825, + 15.644468735176805, + -15.953056582314183, + 0.0 + ], + [ + 1141.64412, + 11.574723388671874, + 0.5, + 5.844281524926686, + -5.794330400782014, + 51.07970473343082, + -4.457691719102679, + 15.747331350889262, + -15.906300847899429, + 0.0 + ], + [ + 1141.6641, + 11.624983154296874, + 0.5, + 5.844281524926686, + -5.794330400782014, + 51.40512464495752, + -4.770020024993238, + 15.812789379069919, + -15.812789379069919, + 0.0 + ], + [ + 1141.68405, + 11.574723388671874, + 0.5, + 5.844281524926686, + -5.794330400782014, + 51.71838806553637, + -5.095439936519928, + 15.868896260367624, + -15.868896260367624, + 0.0 + ], + [ + 1141.704062, + 11.612418212890624, + 0.5, + 5.844281524926686, + -5.794330400782014, + 52.04100263299817, + -5.418989618670028, + 15.915651994782378, + -15.925003141665329, + 0.0 + ], + [ + 1141.724088, + 11.599853271484374, + 0.5, + 5.844281524926686, + -5.794330400782014, + 52.3598767417068, + -5.749085103638194, + 15.953056582314183, + -16.065270344909592, + 0.0 + ], + [ + 1141.744064, + 11.61870068359375, + 0.5, + 5.844281524926686, + -5.794330400782014, + 52.674075276973944, + -6.078245473918065, + 15.962407729197132, + -16.196186401270904, + 0.0 + ], + [ + 1141.764154, + 11.555875976562499, + 0.5, + 5.844281524926686, + -5.794330400782014, + 53.00230053256552, + -6.398989812003279, + 15.971758876080084, + -16.317751310749266, + 0.0 + ], + [ + 1141.78406, + 11.631265625, + 0.5, + 5.844281524926686, + -5.794330400782014, + 53.3305257881571, + -6.730955526348035, + 15.981110022963033, + -16.36450704516402, + 0.0 + ], + [ + 1141.80407, + 11.568440917968749, + 0.5, + 5.844281524926686, + -5.794330400782014, + 53.66249150250185, + -7.058245667251316, + 16.02786575737779, + -16.383209338929923, + 0.0 + ], + [ + 1141.824028, + 11.61870068359375, + 0.5, + 5.844281524926686, + -5.794330400782014, + 53.99258698747002, + -7.3892762669077765, + 16.121377226207297, + -16.392560485812872, + 0.0 + ], + [ + 1141.844067, + 11.637548095703124, + 0.5, + 5.844281524926686, + -5.794330400782014, + 54.3198771283733, + -7.7268526693823025, + 16.24294213568566, + -16.495423101525333, + 0.0 + ], + [ + 1141.864059, + 11.549593505859374, + 0.5, + 5.844281524926686, + -5.794330400782014, + 54.65277795740635, + -8.064429071856829, + 16.35515589828107, + -16.645041451652546, + 0.0 + ], + [ + 1141.884082, + 11.637548095703124, + 0.5, + 5.844281524926686, + -5.794330400782014, + 54.98754901581599, + -8.413226850590897, + 16.45801851399353, + -16.635690304769597, + 0.0 + ], + [ + 1141.904043, + 11.61870068359375, + 0.5, + 5.844281524926686, + -5.794330400782014, + 55.31577427140757, + -8.734906303364406, + 16.523476542174183, + -16.757255214247955, + 0.0 + ], + [ + 1141.924072, + 11.587288330078124, + 0.5, + 5.844281524926686, + -5.794330400782014, + 55.64119418293426, + -9.075288049903818, + 16.542178835940085, + -16.86946897684337, + 0.0 + ], + [ + 1141.944066, + 11.66896044921875, + 0.5, + 5.844281524926686, + -5.794330400782014, + 55.96474386508436, + -9.403513305495393, + 16.532827689057136, + -16.757255214247955, + 0.0 + ], + [ + 1141.96406, + 11.631265625, + 0.5, + 5.844281524926686, + -5.794330400782014, + 56.28642331785787, + -9.745765281411396, + 16.47672080775943, + -16.81336209554566, + 0.0 + ], + [ + 1141.984157, + 11.612418212890624, + 0.5, + 5.844281524926686, + -5.794330400782014, + 56.620259261579214, + -10.081471454509332, + 16.40191163269582, + -16.860117829960416, + 0.0 + ], + [ + 1142.004025, + 11.6563955078125, + 0.5, + 5.844281524926686, + -5.794330400782014, + 56.95128986123567, + -10.38070815476376, + 16.34580475139812, + -16.439316220227628, + 0.0 + ], + [ + 1142.024274, + 11.581005859374999, + 0.5, + 5.844281524926686, + -5.794330400782014, + 57.28138534620384, + -10.648150955616154, + 16.336453604515167, + -15.70992676335746, + 0.0 + ], + [ + 1142.044267, + 11.7066552734375, + 0.5, + 5.844281524926686, + -5.844281524926686, + 57.622702207431544, + -10.99507850497363, + 16.392560485812872, + -15.925003141665329, + 0.0 + ], + [ + 1142.064115, + 11.700372802734375, + 0.5, + 5.844281524926686, + -5.844281524926686, + 57.955603036464595, + -11.348551857149173, + 16.48607195464238, + -16.01851461049484, + 0.0 + ], + [ + 1142.084094, + 11.61870068359375, + 0.5, + 5.844281524926686, + -5.844281524926686, + 58.294114553627416, + -11.711376356207667, + 16.59828571723779, + -16.299049016983364, + 0.0 + ], + [ + 1142.104091, + 11.687807861328125, + 0.5, + 5.844281524926686, + -5.844281524926686, + 58.63075584141365, + -12.065784823071505, + 16.6917971860673, + -16.878820123726317, + 0.0 + ], + [ + 1142.124111, + 11.637548095703124, + 0.5, + 5.844281524926686, + -5.844281524926686, + 58.972072702641356, + -12.418323060558754, + 16.766606361130908, + -17.711072196308947, + 0.0 + ], + [ + 1142.144133, + 11.631265625, + 0.5, + 5.844281524926686, + -5.844281524926686, + 59.31525979324565, + -12.778342215552362, + 16.83206438931156, + -17.832637105787306, + 0.0 + ], + [ + 1142.164071, + 11.74435009765625, + 0.5, + 5.844281524926686, + -5.844281524926686, + 59.65844688384995, + -13.1327506824162, + 16.90687356437517, + -17.87939284020206, + 0.0 + ], + [ + 1142.184075, + 11.681525390625, + 0.5, + 5.844281524926686, + -5.844281524926686, + 59.99976374507766, + -13.494640066786399, + 16.981682739438778, + -17.84198825267026, + 0.0 + ], + [ + 1142.204031, + 11.650113037109374, + 0.5, + 5.844281524926686, + -5.81930596285435, + 60.354172211941496, + -13.860269909909777, + 17.037789620736483, + -17.935499721499767, + 0.0 + ], + [ + 1142.224165, + 11.687807861328125, + 0.5, + 5.844281524926686, + -5.81930596285435, + 60.67959212346818, + -14.222159294279976, + 17.056491914502384, + -18.066415777861078, + 0.0 + ], + [ + 1142.244073, + 11.662677978515624, + 0.5, + 5.869257086999022, + -5.81930596285435, + 61.026519672825664, + -14.577502875832108, + 17.075194208268286, + -17.98225545591452, + 0.0 + ], + [ + 1142.264113, + 11.69409033203125, + 0.5, + 5.869257086999022, + -5.81930596285435, + 61.37718768093632, + -14.946873177708667, + 17.093896502034188, + -18.131873806041735, + 0.0 + ], + [ + 1142.284068, + 11.7066552734375, + 0.5, + 5.869257086999022, + -5.81930596285435, + 61.72037477154062, + -15.311567906143752, + 17.13130108956599, + -18.16927839357354, + 0.0 + ], + [ + 1142.304104, + 11.675242919921875, + 0.5, + 5.869257086999022, + -5.81930596285435, + 62.07104277965127, + -15.689354240214968, + 17.178056823980747, + -18.131873806041735, + 0.0 + ], + [ + 1142.324031, + 11.775762451171875, + 0.5, + 5.869257086999022, + -5.81930596285435, + 62.423581017138524, + -16.037216904260738, + 17.262217145927302, + -18.131873806041735, + 0.0 + ], + [ + 1142.344091, + 11.687807861328125, + 0.5, + 5.869257086999022, + -5.81930596285435, + 62.77798948400236, + -16.40097651800753, + 17.35572861475681, + -18.234736421754192, + 0.0 + ], + [ + 1142.364083, + 11.681525390625, + 0.5, + 5.869257086999022, + -5.81930596285435, + 63.12585214804813, + -16.761930787689433, + 17.43988893670337, + -18.159927246690586, + 0.0 + ], + [ + 1142.384074, + 11.74435009765625, + 0.5, + 5.869257086999022, + -5.81930596285435, + 63.469974353340724, + -17.13130108956599, + 17.486644671118125, + -18.20668298110534, + 0.0 + ], + [ + 1142.404287, + 11.662677978515624, + 0.5, + 5.869257086999022, + -5.81930596285435, + 63.81316144394502, + -17.5100225383255, + 17.486644671118125, + -18.375003624998456, + 0.0 + ], + [ + 1142.424059, + 11.712937744140625, + 0.5, + 5.869257086999022, + -5.81930596285435, + 64.1591538786142, + -17.882198184266947, + 17.44924008358632, + -18.449812800062062, + 0.0 + ], + [ + 1142.444056, + 11.750632568359375, + 0.5, + 5.869257086999022, + -5.81930596285435, + 64.51262723078975, + -18.245957798013734, + 17.402484349171566, + -18.449812800062062, + 0.0 + ], + [ + 1142.464079, + 11.712937744140625, + 0.5, + 5.869257086999022, + -5.81930596285435, + 64.86797081234188, + -18.62935482021472, + 17.35572861475681, + -18.64618688460403, + 0.0 + ], + [ + 1142.484178, + 11.763197509765625, + 0.5, + 5.869257086999022, + -5.81930596285435, + 65.21957393514083, + -19.022102989298656, + 17.365079761639763, + -18.702293765901736, + 0.0 + ], + [ + 1142.504092, + 11.73178515625, + 0.5, + 5.869257086999022, + -5.81930596285435, + 65.56556636981001, + -19.386797717733742, + 17.43053778982042, + -18.767751794082393, + 0.0 + ], + [ + 1142.524107, + 11.69409033203125, + 0.5, + 5.869257086999022, + -5.844281524926686, + 65.91529926323237, + -19.785156574947447, + 17.495995818001077, + -18.842560969146, + 0.0 + ], + [ + 1142.544088, + 11.775762451171875, + 0.5, + 5.869257086999022, + -5.844281524926686, + 66.26970773009621, + -20.16107267964207, + 17.55210269929878, + -18.973477025507314, + 0.0 + ], + [ + 1142.565013, + 11.712937744140625, + 0.5, + 5.869257086999022, + -5.844281524926686, + 66.62692154102494, + -20.51922160525909, + 17.580156139947633, + -18.908018997326657, + 0.0 + ], + [ + 1142.584043, + 11.700372802734375, + 0.5, + 5.869257086999022, + -5.844281524926686, + 66.62692154102494, + -20.51922160525909, + 17.580156139947633, + -18.908018997326657, + 0.0 + ] + ], + "fast-backward": [ + [ + 1163.784072, + 12.466834228515625, + -0.5, + 0.0, + 0.0, + 112.74397262367374, + -66.65778032573867, + 0.0, + 0.0, + 0.0 + ], + [ + 1163.804107, + 11.782044921875, + -0.5, + -6.268866080156403, + 6.318817204301076, + 112.74397262367374, + -66.65778032573867, + 0.0, + 0.0, + 0.0 + ], + [ + 1163.824041, + 11.39253173828125, + -0.5, + -6.268866080156403, + 6.318817204301076, + 112.74397262367374, + -66.65778032573867, + 0.0, + 0.0, + 0.0 + ], + [ + 1163.844064, + 11.298294677734374, + -0.5, + -5.869257086999022, + 6.318817204301076, + 112.74397262367374, + -66.64188337603765, + 0.0, + 0.15896949701016477, + 0.0 + ], + [ + 1163.864065, + 11.248034912109375, + -0.5, + -5.869257086999022, + 6.318817204301076, + 112.72714055928442, + -66.63720780259618, + -0.018702293765901736, + 0.2057252314249191, + 0.0 + ], + [ + 1163.88407, + 11.2543173828125, + -0.5, + -5.869257086999022, + 6.318817204301076, + 112.71498406833659, + -66.6147650500771, + -0.09351146882950868, + 0.43950390349869084, + 0.0 + ], + [ + 1163.904225, + 11.3548369140625, + -0.5, + -5.869257086999022, + 6.318817204301076, + 112.70189246270046, + -66.59232229755801, + -0.2057252314249191, + 0.6639314286895116, + 0.0 + ], + [ + 1163.924088, + 11.2040576171875, + -0.5, + -5.869257086999022, + 6.318817204301076, + 112.68506039831115, + -66.56894443035064, + -0.34599243466918217, + 0.8883589538803326, + 0.0 + ], + [ + 1163.944047, + 11.2291875, + -0.5, + -5.869257086999022, + 6.318817204301076, + 112.66448787516866, + -66.5408909897018, + -0.495610784796396, + 1.0099238633586938, + 0.0 + ], + [ + 1163.964063, + 11.285729736328125, + -0.5, + -5.869257086999022, + 5.594525904203323, + 112.63830466389639, + -66.50722686092317, + -0.6545802818065607, + 1.2998094167301708, + 0.0 + ], + [ + 1163.984073, + 11.222905029296875, + -0.5, + -5.869257086999022, + 5.594525904203323, + 112.60464053511777, + -66.46888715870307, + -0.8229009256996764, + 1.4587789137403353, + 0.0 + ], + [ + 1164.004117, + 11.323424560546874, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.56723594758597, + -66.42306653897661, + -1.000572716475743, + 1.6925575858141073, + 0.0 + ], + [ + 1164.024098, + 11.2291875, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.52702601598928, + -66.37537568987356, + -1.2062979479006621, + 1.9450385516537807, + 0.0 + ], + [ + 1164.044091, + 11.19149267578125, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.48120539626282, + -66.3304901848354, + -1.440076619974434, + 2.1133591955468964, + 0.0 + ], + [ + 1164.064071, + 11.36740185546875, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.43444966184806, + -66.27812376229087, + -1.6738552920482055, + 2.291030986322963, + 0.0 + ], + [ + 1164.084097, + 11.26688232421875, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.38395346868013, + -66.21921153692828, + -1.8982828172390263, + 2.4687027770990295, + 0.0 + ], + [ + 1164.104074, + 11.304577148437499, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.33158704613561, + -66.16216954094229, + -2.0946569017809944, + 2.6089699803432924, + 0.0 + ], + [ + 1164.124068, + 11.298294677734374, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.27267482077302, + -66.09577639807333, + -2.26297754567411, + 2.7866417711193585, + 0.0 + ], + [ + 1164.144073, + 11.2291875, + -0.5, + -5.669452590420333, + 5.594525904203323, + 112.21095725134553, + -66.03125348458097, + -2.431298189567226, + 2.992367002544278, + 0.0 + ], + [ + 1164.164068, + 11.292012207031249, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 112.14456410847659, + -65.96486034171201, + -2.6089699803432924, + 3.141985352671492, + 0.0 + ], + [ + 1164.184135, + 11.3548369140625, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 112.07349539216617, + -65.88631070789523, + -2.7959929180023098, + 3.3570617309793613, + 0.0 + ], + [ + 1164.204066, + 11.398814208984374, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.99868621710256, + -65.81056641814332, + -2.992367002544278, + 3.5160312279895267, + 0.0 + ], + [ + 1164.224074, + 11.44279150390625, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.92107169797406, + -65.73201678432655, + -3.188741087086246, + 3.646947284350839, + 0.0 + ], + [ + 1164.2441, + 11.39253173828125, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.84532740822216, + -65.65346715050975, + -3.3851151716282146, + 3.777863340712151, + 0.0 + ], + [ + 1164.264063, + 11.36740185546875, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.76303731565218, + -65.56369614043342, + -3.5534358155213304, + 4.011642012785923, + 0.0 + ], + [ + 1164.284069, + 11.4050966796875, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.67794187901734, + -65.4729900156688, + -3.712405312531495, + 4.123855775381333, + 0.0 + ], + [ + 1164.304068, + 11.348554443359374, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.59378155707078, + -65.37667320277441, + -3.852672515775758, + 4.3389321536892025, + 0.0 + ], + [ + 1164.324123, + 11.3548369140625, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.50494566168274, + -65.27755104581513, + -3.9835885721370703, + 4.544657385114122, + 0.0 + ], + [ + 1164.344058, + 11.4302265625, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.40956396347664, + -65.17281820072608, + -4.114504628498382, + 4.806489497836746, + 0.0 + ], + [ + 1164.364063, + 11.361119384765624, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.31418226527055, + -65.06715024094873, + -4.2454206848596945, + 4.9654589948469114, + 0.0 + ], + [ + 1164.384071, + 11.36740185546875, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.21599522299957, + -64.95119601960015, + -4.395039034986908, + 5.17118422627183, + 0.0 + ], + [ + 1164.40406, + 11.480486328125, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.115937951352, + -64.84739828919939, + -4.535306238231171, + 5.302100282633142, + 0.0 + ], + [ + 1164.424108, + 11.436509033203125, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 111.01214022095124, + -64.73237918253909, + -4.675573441475434, + 5.442367485877405, + 0.0 + ], + [ + 1164.444026, + 11.549593505859374, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 110.9027318024207, + -64.61736007587879, + -4.8251917916026485, + 5.563932395355766, + 0.0 + ], + [ + 1164.464073, + 11.480486328125, + -0.5, + -5.6944281524926685, + 5.594525904203323, + 110.79145315451359, + -64.49392493702385, + -4.974810141729861, + 5.741604186131833, + 0.0 + ], + [ + 1164.484134, + 11.423944091796875, + -0.5, + -5.719403714565004, + 5.594525904203323, + 110.675498933165, + -64.37423025692208, + -5.133779638740027, + 5.835115654961341, + 0.0 + ], + [ + 1164.504333, + 11.39253173828125, + -0.5, + -5.719403714565004, + 5.594525904203323, + 110.5623500558813, + -64.24798977400224, + -5.283397988867241, + 5.984734005088556, + 0.0 + ], + [ + 1164.524277, + 11.4050966796875, + -0.5, + -5.719403714565004, + 5.594525904203323, + 110.44078514640293, + -64.11613860295263, + -5.451718632760356, + 6.171756942747573, + 0.0 + ], + [ + 1164.544116, + 11.49305126953125, + -0.5, + -5.719403714565004, + 5.594525904203323, + 110.31922023692458, + -63.98615766127961, + -5.60133698288757, + 6.293321852225935, + 0.0 + ], + [ + 1164.564065, + 11.499333740234375, + -0.5, + -5.719403714565004, + 5.594525904203323, + 110.19204463931645, + -63.84963091678853, + -5.750955333014785, + 6.433589055470198, + 0.0 + ], + [ + 1164.584025, + 11.480486328125, + -0.5, + -5.719403714565004, + 5.594525904203323, + 110.0695446151498, + -63.71871486042722, + -5.881871389376096, + 6.545802818065608, + 0.0 + ], + [ + 1164.604505, + 11.373684326171874, + -0.5, + -5.719403714565004, + 5.669452590420333, + 109.9348881000353, + -63.57096673967659, + -6.02213859262036, + 6.7608791963734785, + 0.0 + ], + [ + 1164.624058, + 11.499333740234375, + -0.5, + -5.719403714565004, + 5.669452590420333, + 109.9348881000353, + -63.57096673967659, + -6.02213859262036, + 6.7608791963734785, + 0.0 + ], + [ + 1164.644068, + 11.480486328125, + -0.5, + -5.744379276637341, + 5.669452590420333, + 109.8011666996091, + -63.43069953643233, + -6.162405795864623, + 6.8543906652029865, + 0.0 + ], + [ + 1164.664061, + 11.51818115234375, + -0.5, + -5.744379276637341, + 5.669452590420333, + 109.53185366938011, + -63.12865749211302, + -6.433589055470198, + 7.2097342467551195, + 0.0 + ], + [ + 1164.684063, + 11.474203857421875, + -0.5, + -5.744379276637341, + 5.669452590420333, + 109.39158646613585, + -62.97623379792092, + -6.555153964948559, + 7.4341617719459405, + 0.0 + ], + [ + 1164.7041, + 11.461638916015625, + -0.5, + -5.744379276637341, + 5.669452590420333, + 109.25318949226818, + -62.81819941559905, + -6.67671887442692, + 7.5370243876584, + 0.0 + ], + [ + 1164.72411, + 11.524463623046875, + -0.5, + -5.744379276637341, + 5.669452590420333, + 109.10731160089415, + -62.66297037734206, + -6.779581490139379, + 7.686642737785614, + 0.0 + ], + [ + 1164.744061, + 11.449073974609375, + -0.5, + -5.744379276637341, + 5.669452590420333, + 108.95862836545523, + -62.49839019220213, + -6.8917952527347905, + 7.780154206615123, + 0.0 + ], + [ + 1164.764101, + 11.4553564453125, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 108.80246421250995, + -62.34035580988026, + -7.0040090153302, + 7.892367969210533, + 0.0 + ], + [ + 1164.784089, + 11.537028564453125, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 108.64723517425296, + -62.16455424848078, + -7.1629785123403655, + 8.098093200635452, + 0.0 + ], + [ + 1164.80412, + 11.436509033203125, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 108.4882656772428, + -61.99716871927596, + -7.331299156233481, + 8.219658110113814, + 0.0 + ], + [ + 1164.824682, + 11.398814208984374, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 108.32836106554434, + -61.82136715787649, + -7.518322093892499, + 8.331871872709224, + 0.0 + ], + [ + 1164.844088, + 11.549593505859374, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 108.32836106554434, + -61.82136715787649, + -7.518322093892499, + 8.331871872709224, + 0.0 + ], + [ + 1164.864149, + 11.436509033203125, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 108.16658622446928, + -61.65024116991849, + -7.677291590902663, + 8.472139075953486, + 0.0 + ], + [ + 1164.884112, + 11.511898681640625, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 107.84303654231918, + -61.29863804711953, + -7.929772556742336, + 8.677864307378405, + 0.0 + ], + [ + 1164.904056, + 11.474203857421875, + -0.5, + -5.744379276637341, + 5.6195014662756595, + 107.67752124249095, + -61.108809765395634, + -8.004581731805944, + 8.883589538803324, + 0.0 + ], + [ + 1164.92403, + 11.398814208984374, + -0.5, + -5.744379276637341, + 5.644477028347996, + 107.50920059859784, + -60.91524102491855, + -8.07939090686955, + 9.136070504643, + 0.0 + ], + [ + 1164.944057, + 11.480486328125, + -0.5, + -5.744379276637341, + 5.644477028347996, + 107.33620438126324, + -60.72821808725953, + -8.154200081933157, + 9.229581973472508, + 0.0 + ], + [ + 1164.964082, + 11.461638916015625, + -0.5, + -5.769354838709678, + 5.644477028347996, + 107.16227304924037, + -60.52716842927609, + -8.247711550762666, + 9.482062939312181, + 0.0 + ], + [ + 1164.984035, + 11.474203857421875, + -0.5, + -5.769354838709678, + 5.644477028347996, + 106.98647148784089, + -60.33546991817559, + -8.359925313358076, + 9.631681289439394, + 0.0 + ], + [ + 1165.004093, + 11.4553564453125, + -0.5, + -5.769354838709678, + 5.644477028347996, + 106.81534549988288, + -60.14096606301022, + -8.472139075953486, + 9.6877881707371, + 0.0 + ], + [ + 1165.024116, + 11.411379150390625, + -0.5, + -5.769354838709678, + 5.644477028347996, + 106.63486836504194, + -59.941786634403364, + -8.565650544782995, + 9.734543905151854, + 0.0 + ], + [ + 1165.044101, + 11.423944091796875, + -0.5, + -5.769354838709678, + 5.644477028347996, + 106.45626145957758, + -59.73325605891356, + -8.659162013612505, + 9.846757667747264, + 0.0 + ], + [ + 1165.064066, + 11.4302265625, + -0.5, + -5.769354838709678, + 5.644477028347996, + 106.27671943942491, + -59.54529800656625, + -8.743322335559062, + 9.837406520864313, + 0.0 + ], + [ + 1165.084078, + 11.398814208984374, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 106.0896965017659, + -59.343313233894506, + -8.82748265750562, + 9.912215695927921, + 0.0 + ], + [ + 1165.104067, + 11.486768798828125, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 105.90828425223665, + -59.131977314339814, + -8.911642979452179, + 10.071185192938085, + 0.0 + ], + [ + 1165.12407, + 11.461638916015625, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 105.72313154395422, + -58.921576509473425, + -9.005154448281687, + 10.202101249299398, + 0.0 + ], + [ + 1165.144039, + 11.386249267578124, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 105.53517349160691, + -58.70930547523044, + -9.089314770228244, + 10.34236845254366, + 0.0 + ], + [ + 1165.164064, + 11.499333740234375, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 105.34628032457131, + -58.49048863816939, + -9.164123945291852, + 10.44523106825612, + 0.0 + ], + [ + 1165.184055, + 11.4302265625, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 105.15084135471763, + -58.27541225986152, + -9.238933120355458, + 10.594849418383333, + 0.0 + ], + [ + 1165.204102, + 11.449073974609375, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 104.95353215548737, + -58.064076340306826, + -9.341795736067917, + 10.697712034095794, + 0.0 + ], + [ + 1165.224058, + 11.562158447265624, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 104.75154738281563, + -57.84432438855748, + -9.454009498663329, + 10.791223502925302, + 0.0 + ], + [ + 1165.244328, + 11.46792138671875, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 104.5495626101439, + -57.61709151930177, + -9.603627848790543, + 10.931490706169564, + 0.0 + ], + [ + 1165.2641, + 11.474203857421875, + -0.5, + -5.769354838709678, + 5.6944281524926685, + 104.34477249340726, + -57.61709151930177, + -9.753246198917756, + 10.931490706169564, + 0.0 + ], + [ + 1165.284093, + 11.499333740234375, + -0.5, + -5.794330400782014, + 5.6944281524926685, + 104.14091749135893, + -57.15140440453082, + -9.912215695927921, + 11.324238875253503, + 0.0 + ], + [ + 1165.304088, + 11.5056162109375, + -0.5, + -5.794330400782014, + 5.6944281524926685, + 103.93612737462232, + -56.91575550308046, + -10.024429458523333, + 11.464506078497765, + 0.0 + ], + [ + 1165.32407, + 11.549593505859374, + -0.5, + -5.794330400782014, + 5.6944281524926685, + 103.73320748726228, + -56.67636614287692, + -10.10858978046989, + 11.679582456805635, + 0.0 + ], + [ + 1165.344065, + 11.568440917968749, + -0.5, + -5.794330400782014, + 5.6944281524926685, + 103.53028759990225, + -56.44165235611485, + -10.155345514884644, + 11.74504048498629, + 0.0 + ], + [ + 1165.36407, + 11.53074609375, + -0.5, + -5.794330400782014, + 5.6944281524926685, + 103.32549748316562, + -56.20039276653472, + -10.174047808650545, + 11.866605394464653, + 0.0 + ], + [ + 1165.384244, + 11.524463623046875, + -0.5, + -5.794330400782014, + 5.6944281524926685, + 103.11883713705241, + -55.962873635707766, + -10.183398955533496, + 11.904009981996456, + 0.0 + ], + [ + 1165.404071, + 11.54331103515625, + -0.5, + -5.794330400782014, + 5.669452590420333, + 102.9112416762509, + -55.71413312862128, + -10.202101249299398, + 12.025574891474818, + 0.0 + ], + [ + 1165.424107, + 11.54331103515625, + -0.5, + -5.794330400782014, + 5.669452590420333, + 102.69803552731962, + -55.47193842435285, + -10.258208130597101, + 12.034926038357767, + 0.0 + ], + [ + 1165.444136, + 11.581005859374999, + -0.5, + -5.794330400782014, + 5.669452590420333, + 102.47921869025856, + -55.21852234382488, + -10.323666158777758, + 12.250002416665637, + 0.0 + ], + [ + 1165.464084, + 11.562158447265624, + -0.5, + -5.794330400782014, + 5.669452590420333, + 102.26694765601559, + -54.9669764926735, + -10.417177627607268, + 12.343513885495145, + 0.0 + ], + [ + 1165.484111, + 11.555875976562499, + -0.5, + -5.794330400782014, + 5.669452590420333, + 102.05000104833113, + -54.71449552683383, + -10.520040243319727, + 12.47442994185646, + 0.0 + ], + [ + 1165.504107, + 11.612418212890624, + -0.5, + -5.794330400782014, + 5.669452590420333, + 101.83398955533495, + -54.46669013443563, + -10.613551712149237, + 12.47442994185646, + 0.0 + ], + [ + 1165.524069, + 11.581005859374999, + -0.5, + -5.794330400782014, + 5.669452590420333, + 101.61049714483244, + -54.212338939219364, + -10.697712034095794, + 12.605345998217771, + 0.0 + ], + [ + 1165.544118, + 11.631265625, + -0.5, + -5.794330400782014, + 5.669452590420333, + 101.3870047343299, + -53.96079308806799, + -10.791223502925302, + 12.567941410685968, + 0.0 + ], + [ + 1165.564064, + 11.599853271484374, + -0.5, + -5.794330400782014, + 5.719403714565004, + 101.14855048881466, + -53.69802586065707, + -10.903437265520711, + 12.680155173281378, + 0.0 + ], + [ + 1165.584071, + 11.574723388671874, + -0.5, + -5.794330400782014, + 5.719403714565004, + 100.91477181674088, + -53.43806397731103, + -11.053055615647926, + 12.773666642110886, + 0.0 + ], + [ + 1165.604099, + 11.662677978515624, + -0.5, + -5.794330400782014, + 5.719403714565004, + 100.67818780060223, + -53.17342652052352, + -11.230727406423993, + 12.941987286004002, + 0.0 + ], + [ + 1165.624058, + 11.606135742187499, + -0.5, + -5.794330400782014, + 5.719403714565004, + 100.43225263758062, + -52.908789063736016, + -11.445803784731863, + 13.03549875483351, + 0.0 + ], + [ + 1165.644054, + 11.624983154296874, + -0.5, + -5.794330400782014, + 5.719403714565004, + 100.19286327737709, + -52.64789206570168, + -11.651529016156783, + 13.110307929897118, + 0.0 + ], + [ + 1165.66406, + 11.675242919921875, + -0.5, + -5.794330400782014, + 5.719403714565004, + 99.95066857310866, + -52.38699506766736, + -11.82920080693285, + 13.110307929897118, + 0.0 + ], + [ + 1165.684137, + 11.612418212890624, + -0.5, + -5.794330400782014, + 5.719403714565004, + 99.70192806602216, + -52.12329272556814, + -11.96011686329416, + 13.147712517428921, + 0.0 + ], + [ + 1165.704064, + 11.606135742187499, + -0.5, + -5.794330400782014, + 5.719403714565004, + 99.46440893519521, + -51.856785039404045, + -12.053628332123669, + 13.157063664311872, + 0.0 + ], + [ + 1165.724203, + 11.662677978515624, + -0.5, + -5.794330400782014, + 5.744379276637341, + 99.20912262529065, + -51.58747200917506, + -12.119086360304326, + 13.213170545609579, + 0.0 + ], + [ + 1165.744134, + 11.581005859374999, + -0.5, + -5.794330400782014, + 5.744379276637341, + 98.95944700351586, + -51.31909409363437, + -12.184544388484982, + 13.297330867556134, + 0.0 + ], + [ + 1165.764091, + 11.650113037109374, + -0.5, + -5.794330400782014, + 5.744379276637341, + 98.7050958082996, + -51.04791083402879, + -12.25935356354859, + 13.409544630151547, + 0.0 + ], + [ + 1165.784059, + 11.587288330078124, + -0.5, + -5.794330400782014, + 5.744379276637341, + 98.4554201865248, + -50.77672757442322, + -12.343513885495145, + 13.46565151144925, + 0.0 + ], + [ + 1165.804058, + 11.555875976562499, + -0.5, + -5.794330400782014, + 5.744379276637341, + 98.20013387662026, + -50.504609200129345, + -12.446376501207606, + 13.540460686512859, + 0.0 + ], + [ + 1165.824056, + 11.606135742187499, + -0.5, + -5.794330400782014, + 5.744379276637341, + 97.94765291078058, + -50.23342594052377, + -12.539887970037116, + 13.540460686512859, + 0.0 + ], + [ + 1165.844112, + 11.599853271484374, + -0.5, + -5.794330400782014, + 5.744379276637341, + 97.69330171556432, + -49.95569687810013, + -12.595994851334819, + 13.662025595991219, + 0.0 + ], + [ + 1165.86405, + 11.587288330078124, + -0.5, + -5.794330400782014, + 5.744379276637341, + 97.4277291440885, + -49.673292242235014, + -12.661452879515476, + 13.727483624171875, + 0.0 + ], + [ + 1165.884114, + 11.6563955078125, + -0.5, + -5.794330400782014, + 5.744379276637341, + 97.16870237543077, + -49.37686088604547, + -12.726910907696132, + 13.858399680533186, + 0.0 + ], + [ + 1165.904139, + 11.612418212890624, + -0.5, + -5.794330400782014, + 5.744379276637341, + 96.90593514801985, + -49.10661274112819, + -12.811071229642689, + 13.989315736894499, + 0.0 + ], + [ + 1165.924068, + 11.54331103515625, + -0.5, + -5.81930596285435, + 5.744379276637341, + 96.64036257654405, + -48.82327299057478, + -12.91393384535515, + 14.09217835260696, + 0.0 + ], + [ + 1165.944106, + 11.612418212890624, + -0.5, + -5.81930596285435, + 5.744379276637341, + 96.37479000506823, + -48.53993324002137, + -13.016796461067608, + 14.157636380787615, + 0.0 + ], + [ + 1165.964068, + 11.54331103515625, + -0.5, + -5.81930596285435, + 5.744379276637341, + 96.10921743359243, + -48.25752860415625, + -13.110307929897118, + 14.157636380787615, + 0.0 + ], + [ + 1165.984071, + 11.631265625, + -0.5, + -5.81930596285435, + 5.744379276637341, + 95.8501906649347, + -47.96764305078477, + -13.166414811194823, + 14.251147849617123, + 0.0 + ], + [ + 1166.004103, + 11.593570800781249, + -0.5, + -5.81930596285435, + 5.744379276637341, + 95.58555320814719, + -47.659990318335694, + -13.185117104960725, + 14.30725473091483, + 0.0 + ], + [ + 1166.02407, + 11.581005859374999, + -0.5, + -5.81930596285435, + 5.744379276637341, + 95.31717529260649, + -47.38132614122375, + -13.194468251843677, + 14.447521934159091, + 0.0 + ], + [ + 1166.044096, + 11.64383056640625, + -0.5, + -5.81930596285435, + 5.744379276637341, + 95.04879737706581, + -47.084894785034216, + -13.203819398726626, + 14.550384549871552, + 0.0 + ], + [ + 1166.064063, + 11.5056162109375, + -0.5, + -5.81930596285435, + 5.744379276637341, + 94.78135457621342, + -46.79033365822126, + -13.222521692492528, + 14.671949459349914, + 0.0 + ], + [ + 1166.084109, + 11.511898681640625, + -0.5, + -5.844281524926686, + 5.744379276637341, + 94.50830108723125, + -46.49109695796683, + -13.269277426907282, + 14.746758634413519, + 0.0 + ], + [ + 1166.104116, + 11.606135742187499, + -0.5, + -5.844281524926686, + 5.744379276637341, + 94.23992317169056, + -46.189990028335814, + -13.325384308204988, + 14.830918956360078, + 0.0 + ], + [ + 1166.124063, + 11.549593505859374, + -0.5, + -5.844281524926686, + 5.744379276637341, + 93.96780479739668, + -45.89542890152286, + -13.390842336385644, + 14.85897239700893, + 0.0 + ], + [ + 1166.144066, + 11.53074609375, + -0.5, + -5.844281524926686, + 5.744379276637341, + 93.68820550559646, + -45.58590593969719, + -13.46565151144925, + 14.989888453370241, + 0.0 + ], + [ + 1166.164219, + 11.637548095703124, + -0.5, + -5.844281524926686, + 5.744379276637341, + 93.40767109910793, + -45.28386389537788, + -13.549811833395808, + 15.06469762843385, + 0.0 + ], + [ + 1166.184095, + 11.54331103515625, + -0.5, + -5.844281524926686, + 5.744379276637341, + 93.12339623386623, + -44.97901650699368, + -13.652674449108268, + 15.120804509731553, + 0.0 + ], + [ + 1166.204104, + 11.61870068359375, + -0.5, + -5.844281524926686, + 5.769354838709678, + 92.8419267126894, + -44.67510423329777, + -13.783590505469581, + 15.158209097263358, + 0.0 + ], + [ + 1166.224072, + 11.581005859374999, + -0.5, + -5.844281524926686, + 5.769354838709678, + 92.55017092994133, + -44.37025684491358, + -13.923857708713843, + 15.251720566092866, + 0.0 + ], + [ + 1166.244056, + 11.587288330078124, + -0.5, + -5.844281524926686, + 5.769354838709678, + 92.2696365234528, + -44.05792853902302, + -14.045422618192205, + 15.28912515362467, + 0.0 + ], + [ + 1166.264032, + 11.61870068359375, + -0.5, + -5.844281524926686, + 5.769354838709678, + 91.9853616582111, + -43.74373000375587, + -14.148285233904666, + 15.382636622454179, + 0.0 + ], + [ + 1166.284065, + 11.581005859374999, + -0.5, + -5.844281524926686, + 5.769354838709678, + 91.69173564608644, + -43.430466583177015, + -14.213743262085321, + 15.485499238166637, + 0.0 + ], + [ + 1166.30406, + 11.61870068359375, + -0.5, + -5.844281524926686, + 5.769354838709678, + 91.40652566615644, + -43.115332933221566, + -14.269850143383024, + 15.588361853879098, + 0.0 + ], + [ + 1166.324076, + 11.631265625, + -0.5, + -5.844281524926686, + 5.769354838709678, + 91.11289965403179, + -42.79739393920124, + -14.316605877797778, + 15.72862905712336, + 0.0 + ], + [ + 1166.344056, + 11.612418212890624, + -0.5, + -5.844281524926686, + 5.769354838709678, + 90.8248843300369, + -42.482260289245794, + -14.372712759095485, + 15.766033644655163, + 0.0 + ], + [ + 1166.364159, + 11.562158447265624, + -0.5, + -5.844281524926686, + 5.794330400782014, + 90.53032320322394, + -42.15590526303081, + -14.419468493510239, + 15.878247407250575, + 0.0 + ], + [ + 1166.384075, + 11.66896044921875, + -0.5, + -5.844281524926686, + 5.794330400782014, + 90.24230787922906, + -41.83235558088071, + -14.475575374807946, + 15.981110022963033, + 0.0 + ], + [ + 1166.404054, + 11.64383056640625, + -0.5, + -5.844281524926686, + 5.794330400782014, + 89.94774675241611, + -41.511611242795496, + -14.503628815456796, + 16.05591919802664, + 0.0 + ], + [ + 1166.424088, + 11.662677978515624, + -0.5, + -5.844281524926686, + 5.794330400782014, + 89.65225051091487, + -41.19086690471028, + -14.531682256105649, + 16.065270344909592, + 0.0 + ], + [ + 1166.444119, + 11.606135742187499, + -0.5, + -5.844281524926686, + 5.794330400782014, + 89.35488404003702, + -40.869187451936774, + -14.569086843637454, + 16.13072837309025, + 0.0 + ], + [ + 1166.464107, + 11.631265625, + -0.5, + -5.844281524926686, + 5.794330400782014, + 89.05284199571771, + -40.54657288447497, + -14.64389601870106, + 16.093323785558443, + 0.0 + ], + [ + 1166.484057, + 11.712937744140625, + -0.5, + -5.844281524926686, + 5.794330400782014, + 88.74799460733351, + -40.20806136731215, + -14.728056340647617, + 16.083972638675494, + 0.0 + ], + [ + 1166.504083, + 11.6563955078125, + -0.5, + -5.844281524926686, + 5.794330400782014, + 88.45062813645568, + -39.89573306142159, + -14.840270103243027, + 16.1587818137391, + 0.0 + ], + [ + 1166.524059, + 11.6563955078125, + -0.5, + -5.844281524926686, + 5.769354838709678, + 88.15045632151295, + -39.55348108550558, + -14.933781572072537, + 16.18683525438795, + 0.0 + ], + [ + 1166.544093, + 11.687807861328125, + -0.5, + -5.844281524926686, + 5.769354838709678, + 87.84467381844046, + -39.24676346774479, + -15.008590747136143, + 16.205537548153856, + 0.0 + ], + [ + 1166.564062, + 11.64383056640625, + -0.5, + -5.844281524926686, + 5.769354838709678, + 87.53515085661479, + -38.921343556218105, + -15.06469762843385, + 16.26164442945156, + 0.0 + ], + [ + 1166.584041, + 11.662677978515624, + -0.5, + -5.844281524926686, + 5.769354838709678, + 87.22469278010081, + -38.599664103444596, + -15.130155656614505, + 16.27099557633451, + 0.0 + ], + [ + 1166.604079, + 11.7066552734375, + -0.5, + -5.844281524926686, + 5.769354838709678, + 86.91984539171662, + -38.27143884785302, + -15.195613684795163, + 16.27099557633451, + 0.0 + ], + [ + 1166.624118, + 11.637548095703124, + -0.5, + -5.844281524926686, + 5.769354838709678, + 86.60658197113776, + -37.93853801881997, + -15.261071712975818, + 16.308400163866313, + 0.0 + ], + [ + 1166.644108, + 11.73178515625, + -0.5, + -5.844281524926686, + 5.769354838709678, + 86.30079946806526, + -37.6093776485401, + -15.335880888039423, + 16.36450704516402, + 0.0 + ], + [ + 1166.664029, + 11.687807861328125, + -0.5, + -5.844281524926686, + 5.769354838709678, + 85.98473070342153, + -37.28302262232511, + -15.39198776933713, + 16.383209338929923, + 0.0 + ], + [ + 1166.684114, + 11.662677978515624, + -0.5, + -5.844281524926686, + 5.794330400782014, + 85.6667917094012, + -36.93703018765593, + -15.466796944400736, + 16.439316220227628, + 0.0 + ], + [ + 1166.704082, + 11.738067626953125, + -0.5, + -5.844281524926686, + 5.794330400782014, + 85.34698248600428, + -36.625636996453665, + -15.550957266347293, + 16.45801851399353, + 0.0 + ], + [ + 1166.724094, + 11.662677978515624, + -0.5, + -5.844281524926686, + 5.794330400782014, + 85.02904349198396, + -36.30021708492698, + -15.644468735176805, + 16.392560485812872, + 0.0 + ], + [ + 1166.744051, + 11.7066552734375, + -0.5, + -5.844281524926686, + 5.794330400782014, + 84.7148449567168, + -35.9729269440237, + -15.737980204006313, + 16.383209338929923, + 0.0 + ], + [ + 1166.76425, + 11.712937744140625, + -0.5, + -5.844281524926686, + 5.794330400782014, + 84.39597084800818, + -35.64283145905553, + -15.803438232186968, + 16.429965073344675, + 0.0 + ], + [ + 1166.784091, + 11.71922021484375, + -0.5, + -5.844281524926686, + 5.794330400782014, + 84.07616162461126, + -35.29403368032146, + -15.840842819718773, + 16.429965073344675, + 0.0 + ], + [ + 1166.80402, + 11.675242919921875, + -0.5, + -5.844281524926686, + 5.794330400782014, + 83.75167682777287, + -34.97702980098943, + -15.868896260367624, + 16.504774248408282, + 0.0 + ], + [ + 1166.824095, + 11.763197509765625, + -0.5, + -5.844281524926686, + 5.794330400782014, + 83.43186760437594, + -34.63758316913831, + -15.887598554133525, + 16.635690304769597, + 0.0 + ], + [ + 1166.844051, + 11.675242919921875, + -0.5, + -5.844281524926686, + 5.844281524926686, + 83.10738280753755, + -34.29159073446913, + -15.94370543543123, + 16.80401094866271, + 0.0 + ], + [ + 1166.864105, + 11.76947998046875, + -0.5, + -5.844281524926686, + 5.844281524926686, + 82.78570335476404, + -33.948403643864836, + -16.01851461049484, + 16.953629298789924, + 0.0 + ], + [ + 1166.884101, + 11.662677978515624, + -0.5, + -5.869257086999022, + 5.844281524926686, + 82.4705697048086, + -33.604281438572244, + -16.07462149179254, + 17.065843061385337, + 0.0 + ], + [ + 1166.904108, + 11.69409033203125, + -0.5, + -5.869257086999022, + 5.844281524926686, + 82.15450094016485, + -33.26670503609771, + -16.07462149179254, + 17.075194208268286, + 0.0 + ], + [ + 1166.924061, + 11.7066552734375, + -0.5, + -5.869257086999022, + 5.844281524926686, + 81.82814591394987, + -32.93567443644125, + -16.05591919802664, + 17.00973618008763, + 0.0 + ], + [ + 1166.944032, + 11.631265625, + -0.5, + -5.869257086999022, + 5.844281524926686, + 81.50272600242317, + -32.59155223114866, + -16.02786575737779, + 16.981682739438778, + 0.0 + ], + [ + 1166.964144, + 11.69409033203125, + -0.5, + -5.869257086999022, + 5.844281524926686, + 81.1745007468316, + -32.242754452414594, + -16.02786575737779, + 17.037789620736483, + 0.0 + ], + [ + 1166.984111, + 11.73178515625, + -0.5, + -5.869257086999022, + 5.844281524926686, + 80.85282129405809, + -31.89302155899223, + -16.083972638675494, + 17.11259879580009, + 0.0 + ], + [ + 1167.00405, + 11.675242919921875, + -0.5, + -5.869257086999022, + 5.81930596285435, + 80.52085557971334, + -31.54702912432305, + -16.1587818137391, + 17.21546141151255, + 0.0 + ], + [ + 1167.024123, + 11.650113037109374, + -0.5, + -5.869257086999022, + 5.81930596285435, + 80.19730589756324, + -31.1944908868358, + -16.24294213568566, + 17.41183549605452, + 0.0 + ], + [ + 1167.044139, + 11.71922021484375, + -0.5, + -5.869257086999022, + 5.81930596285435, + 79.86908064197166, + -30.843822878725145, + -16.299049016983364, + 17.51469811176698, + 0.0 + ], + [ + 1167.064133, + 11.662677978515624, + -0.5, + -5.869257086999022, + 5.81930596285435, + 79.55207676263963, + -30.496895329367668, + -16.28969787010041, + 17.467942377352223, + 0.0 + ], + [ + 1167.084078, + 11.7569150390625, + -0.5, + -5.869257086999022, + 5.81930596285435, + 79.23226753924271, + -30.145292206568715, + -16.25229328256861, + 17.467942377352223, + 0.0 + ], + [ + 1167.104044, + 11.637548095703124, + -0.5, + -5.869257086999022, + 5.81930596285435, + 78.91339343053409, + -29.780597478133632, + -16.18683525438795, + 17.64561416812829, + 0.0 + ], + [ + 1167.124113, + 11.6563955078125, + -0.5, + -5.869257086999022, + 5.81930596285435, + 78.59732466589034, + -29.426189011269795, + -16.13072837309025, + 17.66431646189419, + 0.0 + ], + [ + 1167.144059, + 11.675242919921875, + -0.5, + -5.869257086999022, + 5.81930596285435, + 78.26629406623388, + -29.069910315029365, + -16.07462149179254, + 17.72977449007485, + 0.0 + ], + [ + 1167.164055, + 11.637548095703124, + -0.5, + -5.869257086999022, + 5.81930596285435, + 77.93900392533061, + -28.711761389412345, + -16.05591919802664, + 17.851339399553208, + 0.0 + ], + [ + 1167.18406, + 11.64383056640625, + -0.5, + -5.869257086999022, + 5.81930596285435, + 77.60797332567414, + -28.348936890353855, + -16.083972638675494, + 17.98225545591452, + 0.0 + ], + [ + 1167.204066, + 11.712937744140625, + -0.5, + -5.869257086999022, + 5.81930596285435, + 77.28722898758893, + -27.98424216191877, + -16.1587818137391, + 17.963553162148617, + 0.0 + ], + [ + 1167.224083, + 11.66896044921875, + -0.5, + -5.869257086999022, + 5.81930596285435, + 76.96461442012712, + -27.615806974730503, + -16.214888695036805, + 18.122522659158783, + 0.0 + ], + [ + 1167.24421, + 11.73178515625, + -0.5, + -5.869257086999022, + 5.81930596285435, + 76.64574031141849, + -27.246436672853946, + -16.25229328256861, + 18.225385274871243, + 0.0 + ], + [ + 1167.264056, + 11.725502685546875, + -0.5, + -5.869257086999022, + 5.81930596285435, + 76.31845017051522, + -26.887352632548634, + -16.25229328256861, + 18.234736421754192, + 0.0 + ], + [ + 1167.28408, + 11.69409033203125, + -0.5, + -5.869257086999022, + 5.81930596285435, + 75.99583560305341, + -26.51424187191889, + -16.224239841919758, + 18.159927246690586, + 0.0 + ], + [ + 1167.304056, + 11.7066552734375, + -0.5, + -5.869257086999022, + 5.81930596285435, + 75.66948057683842, + -26.23090212136548, + -16.18683525438795, + 17.533400405532877, + 0.0 + ], + [ + 1167.324071, + 11.687807861328125, + -0.5, + -5.869257086999022, + 5.844281524926686, + 75.34873623875322, + -26.154222716925283, + -16.14943066685615, + 14.569086843637454, + 0.0 + ] + ], + "track-width": [ + [ + 1286.864064, + 12.42285693359375, + 0.0, + 0.0, + 0.0, + 91.66461732012588, + -73.67862140545819, + 0.0, + 0.0, + 0.0 + ], + [ + 1286.884102, + 12.42285693359375, + 0.75, + 0.0, + 0.0, + 91.66461732012588, + -73.67862140545819, + 0.0, + 0.0, + 0.0 + ], + [ + 1286.904078, + 10.8522392578125, + 0.75, + -9.409433040078202, + -9.44692082111437, + 91.66461732012588, + -73.67862140545819, + 0.0, + 0.0, + 0.0 + ], + [ + 1286.924068, + 10.381053955078125, + 0.75, + -9.409433040078202, + -9.44692082111437, + 91.66461732012588, + -73.67862140545819, + 0.0, + 0.0, + 0.0 + ], + [ + 1286.944172, + 10.305664306640624, + 0.75, + -9.409433040078202, + -9.44692082111437, + 91.66461732012588, + -73.75904126865157, + 0.0, + -0.8041986319337747, + 0.0 + ], + [ + 1286.964047, + 10.330794189453124, + 0.75, + -9.409433040078202, + -9.44692082111437, + 91.66274709074929, + -73.76184661271645, + 0.0, + -0.8322520725826272, + 0.0 + ], + [ + 1286.984067, + 10.31194677734375, + 0.75, + -9.409433040078202, + -9.44692082111437, + 91.65059059980146, + -73.78522447992383, + -0.018702293765901736, + -1.066030744656399, + 0.0 + ], + [ + 1287.004208, + 10.318229248046874, + 0.75, + -9.409433040078202, + -7.310117302052786, + 91.64123945291851, + -73.82636952620881, + -0.07480917506360694, + -1.4868323543891881, + 0.0 + ], + [ + 1287.024132, + 10.2993818359375, + 0.75, + -9.409433040078202, + -7.310117302052786, + 91.63188830603556, + -73.87125503124697, + -0.16832064389311563, + -1.926336257887879, + 0.0 + ], + [ + 1287.044108, + 10.173732421875, + 0.75, + -7.7224828934506355, + -7.310117302052786, + 91.62627761790579, + -73.91240007753196, + -0.2618321127226243, + -1.5429392356868932, + 0.0 + ], + [ + 1287.064067, + 10.261687011718749, + 0.75, + -7.7224828934506355, + -7.310117302052786, + 91.6234722738409, + -73.960090926635, + -0.33664128778623126, + -1.9730919923026333, + 0.0 + ], + [ + 1287.084172, + 10.167449951171875, + 0.75, + -7.7224828934506355, + -7.310117302052786, + 91.6234722738409, + -74.00310620229658, + -0.355343581552133, + -2.1788172237275525, + 0.0 + ], + [ + 1287.10405, + 10.173732421875, + 0.75, + -7.7224828934506355, + -7.310117302052786, + 91.6234722738409, + -74.05266728077622, + -0.31793899402032955, + -2.26297754567411, + 0.0 + ], + [ + 1287.124104, + 10.173732421875, + 0.75, + -7.7224828934506355, + -7.310117302052786, + 91.6234722738409, + -74.09755278581439, + -0.2337786720737717, + -2.272328692557061, + 0.0 + ], + [ + 1287.144025, + 10.129755126953125, + 0.75, + -7.7224828934506355, + -7.310117302052786, + 91.6234722738409, + -74.14150317616425, + -0.14026720324426303, + -2.300382133205914, + 0.0 + ], + [ + 1287.164099, + 10.12347265625, + 0.75, + -7.7224828934506355, + -7.197653958944283, + 91.6234722738409, + -74.18732379589072, + -0.06545802818065607, + -2.281679839440012, + 0.0 + ], + [ + 1287.184073, + 10.274251953124999, + 0.75, + -7.7224828934506355, + -7.197653958944283, + 91.6234722738409, + -74.23875510374694, + -0.018702293765901736, + -2.36584016138657, + 0.0 + ], + [ + 1287.204064, + 10.073212890625, + 0.75, + -7.647507331378298, + -7.197653958944283, + 91.63188830603556, + -74.28925129691488, + 0.0, + -2.36584016138657, + 0.0 + ], + [ + 1287.224055, + 10.32451171875, + 0.75, + -7.647507331378298, + -7.197653958944283, + 91.64030433823022, + -74.34535817821258, + 0.04675573441475434, + -2.4500004833331275, + 0.0 + ], + [ + 1287.244075, + 9.997823242187499, + 0.75, + -7.647507331378298, + -7.197653958944283, + 91.64965548511317, + -74.3986597154454, + 0.11221376259541044, + -2.5435119521626364, + 0.0 + ], + [ + 1287.26409, + 10.073212890625, + 0.75, + -7.647507331378298, + -7.197653958944283, + 91.65807151730782, + -74.44822079392505, + 0.19637408454196825, + -2.5996188334603416, + 0.0 + ], + [ + 1287.284092, + 10.08577783203125, + 0.75, + -7.647507331378298, + -7.197653958944283, + 91.66648754950248, + -74.49684675771638, + 0.2898855533714769, + -2.5715653928114888, + 0.0 + ], + [ + 1287.304133, + 10.0480830078125, + 0.75, + -7.647507331378298, + -7.197653958944283, + 91.67583869638543, + -74.54827806557262, + 0.3646947284350838, + -2.5902676865773904, + 0.0 + ], + [ + 1287.32409, + 10.092060302734374, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.68518984326838, + -74.60344983218202, + 0.4114504628498382, + -2.5996188334603416, + 0.0 + ], + [ + 1287.34411, + 10.079495361328124, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.69547610483963, + -74.65581625472656, + 0.43950390349869084, + -2.5902676865773904, + 0.0 + ], + [ + 1287.364085, + 10.104625244140625, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.70389213703429, + -74.70911779195937, + 0.44885505038164175, + -2.6183211272262428, + 0.0 + ], + [ + 1287.384064, + 10.066930419921874, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.71230816922893, + -74.76335444388049, + 0.44885505038164175, + -2.6650768616409977, + 0.0 + ], + [ + 1287.404117, + 10.129755126953125, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.72165931611188, + -74.8194613251782, + 0.44885505038164175, + -2.711832596055752, + 0.0 + ], + [ + 1287.424083, + 10.022953124999999, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.73288069237142, + -74.88304912398226, + 0.45820619726459255, + -2.777290624236408, + 0.0 + ], + [ + 1287.444065, + 10.004105712890624, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.74503718331927, + -74.93635066121507, + 0.4675573441475434, + -2.814695211768212, + 0.0 + ], + [ + 1287.464062, + 10.08577783203125, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.7571936742671, + -74.99432777188937, + 0.4862596379134452, + -2.814695211768212, + 0.0 + ], + [ + 1287.484071, + 9.966410888671875, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.76841505052664, + -75.04575907974561, + 0.5143130785622978, + -2.824046358651162, + 0.0 + ], + [ + 1287.504086, + 10.06064794921875, + 0.75, + -7.647507331378298, + -7.160166177908114, + 91.78057154147447, + -75.1028010757316, + 0.5423665192111503, + -2.833397505534113, + 0.0 + ], + [ + 1287.524063, + 10.016670654296874, + 0.75, + -7.610019550342131, + -7.160166177908114, + 91.79272803242232, + -75.1617133010942, + 0.570419959860003, + -2.814695211768212, + 0.0 + ], + [ + 1287.544064, + 9.953845947265625, + 0.75, + -7.610019550342131, + -7.160166177908114, + 91.80768986743503, + -75.21594995301531, + 0.5891222536259046, + -2.7679394773534574, + 0.0 + ], + [ + 1287.564082, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.160166177908114, + 91.82265170244776, + -75.27018660493643, + 0.5984734005088556, + -2.7959929180023098, + 0.0 + ], + [ + 1287.584064, + 9.90986865234375, + 0.75, + -7.610019550342131, + -7.160166177908114, + 91.83761353746048, + -75.32816371561073, + 0.6265268411577083, + -2.7959929180023098, + 0.0 + ], + [ + 1287.604023, + 9.98525830078125, + 0.75, + -7.610019550342131, + -7.160166177908114, + 91.8525753724732, + -75.38240036753183, + 0.6545802818065607, + -2.7959929180023098, + 0.0 + ], + [ + 1287.62408, + 10.12347265625, + 0.75, + -7.610019550342131, + -7.160166177908114, + 91.86940743686252, + -75.45159885446567, + 0.6919848693383643, + -2.889504386831818, + 0.0 + ], + [ + 1287.644074, + 9.978975830078125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.88623950125182, + -75.50770573576338, + 0.7293894568701677, + -2.9362601212465727, + 0.0 + ], + [ + 1287.664413, + 10.117190185546875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.90307156564114, + -75.56100727299619, + 0.7667940444019712, + -2.8988555337147695, + 0.0 + ], + [ + 1287.684509, + 10.079495361328124, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.91709828596557, + -75.6189843836705, + 0.785496338167873, + -2.945611268129524, + 0.0 + ], + [ + 1287.704076, + 9.928716064453125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.93206012097828, + -75.67789660903308, + 0.7948474850508238, + -2.9549624150124743, + 0.0 + ], + [ + 1287.724086, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.9479570706793, + -75.74428975190203, + 0.7948474850508238, + -2.9362601212465727, + 0.0 + ], + [ + 1287.74404, + 10.079495361328124, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.96478913506861, + -75.80600732132952, + 0.785496338167873, + -2.992367002544278, + 0.0 + ], + [ + 1287.764106, + 10.041800537109374, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.98255631414622, + -75.86024397325063, + 0.785496338167873, + -2.992367002544278, + 0.0 + ], + [ + 1287.784082, + 10.180014892578125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 91.99845326384724, + -75.9219615426781, + 0.785496338167873, + -3.0204204431931303, + 0.0 + ], + [ + 1287.804121, + 10.029235595703124, + 0.75, + -7.610019550342131, + -7.047702834799609, + 92.01341509885995, + -75.98648445617046, + 0.7948474850508238, + -3.076527324490836, + 0.0 + ], + [ + 1287.824092, + 10.016670654296874, + 0.75, + -7.610019550342131, + -7.047702834799609, + 92.02931204856097, + -76.05100736966283, + 0.8041986319337747, + -3.057825030724934, + 0.0 + ], + [ + 1287.844103, + 10.173732421875, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 92.0442738835737, + -76.11459516846689, + 0.8041986319337747, + -3.0858784713737863, + 0.0 + ], + [ + 1287.864076, + 10.13603759765625, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 92.06297617733959, + -76.17631273789436, + 0.7948474850508238, + -3.1700387933203444, + 0.0 + ], + [ + 1287.884062, + 10.16116748046875, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 92.07980824172891, + -76.23896542201014, + 0.7948474850508238, + -3.141985352671492, + 0.0 + ], + [ + 1287.904103, + 10.104625244140625, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 92.0975754208065, + -76.30068299143761, + 0.8135497788167255, + -3.151336499554443, + 0.0 + ], + [ + 1287.92407, + 10.1486025390625, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 92.11534259988412, + -76.36894636368315, + 0.8322520725826272, + -3.188741087086246, + 0.0 + ], + [ + 1287.94411, + 10.11090771484375, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 92.13404489365003, + -76.43159904779893, + 0.8509543663485291, + -3.1700387933203444, + 0.0 + ], + [ + 1287.96406, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.15181207272762, + -76.49892730535618, + 0.8696566601144308, + -3.2261456746180492, + 0.0 + ], + [ + 1287.984051, + 10.1988623046875, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.17144948118182, + -76.56251510416024, + 0.8883589538803326, + -3.272901409032804, + 0.0 + ], + [ + 1288.004056, + 10.230274658203125, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.18921666025943, + -76.62423267358771, + 0.9070612476462342, + -3.2261456746180492, + 0.0 + ], + [ + 1288.024085, + 10.092060302734374, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.20791895402533, + -76.68969070176837, + 0.9070612476462342, + -3.198092233969197, + 0.0 + ], + [ + 1288.044064, + 10.1486025390625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.22662124779123, + -76.7616945327671, + 0.9164123945291851, + -3.2916037027987057, + 0.0 + ], + [ + 1288.064057, + 10.286816894531249, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.24532354155714, + -76.84024416658387, + 0.9164123945291851, + -3.375764024745264, + 0.0 + ], + [ + 1288.08407, + 10.117190185546875, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.26309072063475, + -76.90476708007624, + 0.9164123945291851, + -3.422519759160018, + 0.0 + ], + [ + 1288.10402, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.27898767033577, + -76.97583579638666, + 0.9070612476462342, + -3.525382374872477, + 0.0 + ], + [ + 1288.124061, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.29488462003678, + -77.04783962738539, + 0.8977101007632835, + -3.5814892561701828, + 0.0 + ], + [ + 1288.144097, + 10.142320068359375, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.3107815697378, + -77.12451903182559, + 0.8790078069973817, + -3.637596137467888, + 0.0 + ], + [ + 1288.164094, + 10.180014892578125, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.3294838635037, + -77.19371751875941, + 0.8603055132314799, + -3.525382374872477, + 0.0 + ], + [ + 1288.184064, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.3481861572696, + -77.26478623506985, + 0.8509543663485291, + -3.6001915499360844, + 0.0 + ], + [ + 1288.204094, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.36969379510039, + -77.33959541013346, + 0.8509543663485291, + -3.637596137467888, + 0.0 + ], + [ + 1288.224052, + 10.142320068359375, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.38933120355458, + -77.42188550270342, + 0.8790078069973817, + -3.7030541656485436, + 0.0 + ], + [ + 1288.244115, + 10.1486025390625, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.41177395607366, + -77.49762979245533, + 0.9164123945291851, + -3.721756459414446, + 0.0 + ], + [ + 1288.264093, + 10.154885009765625, + 0.75, + -7.610019550342131, + -7.085190615835777, + 92.43328159390445, + -77.57243896751893, + 0.9631681289439395, + -3.8339702220098557, + 0.0 + ], + [ + 1288.284111, + 10.154885009765625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.45572434642354, + -77.65566417477719, + 1.0099238633586938, + -3.8713748095416594, + 0.0 + ], + [ + 1288.304102, + 9.96012841796875, + 0.75, + -7.610019550342131, + -7.122678396871946, + 92.47629686956603, + -77.73234357921739, + 1.0473284508904972, + -3.9368328377223154, + 0.0 + ], + [ + 1288.324066, + 10.0480830078125, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.49873962208511, + -77.81182832772247, + 1.066030744656399, + -3.9368328377223154, + 0.0 + ], + [ + 1288.344094, + 9.972693359375, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.5211823746042, + -77.89505353498073, + 1.0753818915393498, + -3.992939719020021, + 0.0 + ], + [ + 1288.364222, + 10.035518066406249, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.54456024181157, + -77.98295431568047, + 1.0940841853052516, + -4.095802334732481, + 0.0 + ], + [ + 1288.384124, + 10.035518066406249, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.56700299433065, + -78.06056883480896, + 1.1034353321882024, + -4.08645118784953, + 0.0 + ], + [ + 1288.404088, + 9.991540771484374, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.59131597622633, + -78.14566427144382, + 1.1127864790711532, + -4.123855775381333, + 0.0 + ], + [ + 1288.424046, + 10.066930419921874, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 92.61656407281029, + -78.23450016683185, + 1.131488772837055, + -4.236069537976743, + 0.0 + ], + [ + 1288.444068, + 10.142320068359375, + 0.75, + -7.5725317693059635, + -7.010215053763442, + 92.63807171064107, + -78.31585514471352, + 1.150191066602957, + -4.189313803561989, + 0.0 + ], + [ + 1288.464114, + 10.0480830078125, + 0.75, + -7.5725317693059635, + -7.010215053763442, + 92.66144957784846, + -78.39814523728349, + 1.1595422134859077, + -4.123855775381333, + 0.0 + ], + [ + 1288.484089, + 9.997823242187499, + 0.75, + -7.610019550342131, + -7.010215053763442, + 92.688567903809, + -78.48230555923006, + 1.1688933603688585, + -4.179962656679038, + 0.0 + ], + [ + 1288.504024, + 10.016670654296874, + 0.75, + -7.610019550342131, + -7.010215053763442, + 92.71475111508127, + -78.56459565180002, + 1.1782445072518093, + -4.189313803561989, + 0.0 + ], + [ + 1288.524044, + 9.941281005859375, + 0.75, + -7.610019550342131, + -7.010215053763442, + 92.73999921166524, + -78.64969108843486, + 1.1969468010177111, + -4.114504628498382, + 0.0 + ], + [ + 1288.544079, + 10.004105712890624, + 0.75, + -7.610019550342131, + -7.010215053763442, + 92.76898776700239, + -78.73198118100484, + 1.2343513885495148, + -4.123855775381333, + 0.0 + ], + [ + 1288.564051, + 9.972693359375, + 0.75, + -7.610019550342131, + -7.010215053763442, + 92.79610609296294, + -78.8152063882631, + 1.2624048291983672, + -4.20801609732789, + 0.0 + ], + [ + 1288.584106, + 10.004105712890624, + 0.75, + -7.610019550342131, + -7.010215053763442, + 92.8232244189235, + -78.89656136614477, + 1.3091605636131214, + -4.179962656679038, + 0.0 + ], + [ + 1288.604142, + 10.06064794921875, + 0.75, + -7.610019550342131, + -7.310117302052786, + 92.84940763019577, + -78.9844621468445, + 1.3372140042619742, + -4.151909216030186, + 0.0 + ], + [ + 1288.624033, + 9.92243359375, + 0.75, + -7.610019550342131, + -7.310117302052786, + 92.87559084146802, + -79.05646597784323, + 1.346565151144925, + -4.105153481615432, + 0.0 + ], + [ + 1288.644074, + 9.90986865234375, + 0.75, + -7.5725317693059635, + -7.310117302052786, + 92.9017740527403, + -79.1378209557249, + 1.3372140042619742, + -4.105153481615432, + 0.0 + ], + [ + 1288.664086, + 10.022953124999999, + 0.75, + -7.5725317693059635, + -7.310117302052786, + 92.92515191994767, + -79.2154354748534, + 1.3278628573790232, + -4.002290865902972, + 0.0 + ], + [ + 1288.684116, + 9.92243359375, + 0.75, + -7.5725317693059635, + -7.310117302052786, + 92.94946490184334, + -79.29585533804678, + 1.2998094167301708, + -3.992939719020021, + 0.0 + ], + [ + 1288.704115, + 9.978975830078125, + 0.75, + -7.5725317693059635, + -7.310117302052786, + 92.97751834249219, + -79.37814543061674, + 1.281107122964269, + -3.9835885721370703, + 0.0 + ], + [ + 1288.724064, + 10.16116748046875, + 0.75, + -7.5725317693059635, + -7.310117302052786, + 93.00370155376446, + -79.45482483505694, + 1.2717559760813182, + -3.9835885721370703, + 0.0 + ], + [ + 1288.744127, + 10.066930419921874, + 0.75, + -7.5725317693059635, + -7.310117302052786, + 93.02894965034842, + -79.53524469825032, + 1.2717559760813182, + -3.974237425254119, + 0.0 + ], + [ + 1288.764305, + 10.041800537109374, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.05700309099727, + -79.62127524957347, + 1.281107122964269, + -4.011642012785923, + 0.0 + ], + [ + 1288.784102, + 10.004105712890624, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.08692676102271, + -79.69701953932537, + 1.3091605636131214, + -4.011642012785923, + 0.0 + ], + [ + 1288.804121, + 9.941281005859375, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.11310997229498, + -79.77463405845386, + 1.3278628573790232, + -3.9555351314882174, + 0.0 + ], + [ + 1288.824115, + 9.997823242187499, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.14022829825554, + -79.85318369227065, + 1.346565151144925, + -3.9835885721370703, + 0.0 + ], + [ + 1288.844066, + 10.0480830078125, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.1664115095278, + -79.93173332608744, + 1.355916298027876, + -3.9555351314882174, + 0.0 + ], + [ + 1288.864028, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.19165960611177, + -80.00934784521593, + 1.355916298027876, + -3.8900771033075614, + 0.0 + ], + [ + 1288.884095, + 10.06064794921875, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.2206481614489, + -80.07948144683806, + 1.346565151144925, + -3.8152679282439546, + 0.0 + ], + [ + 1288.904094, + 10.079495361328124, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 93.25057183147436, + -80.15896619534314, + 1.346565151144925, + -3.8152679282439546, + 0.0 + ], + [ + 1288.924103, + 10.092060302734374, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 93.28330084556468, + -80.23471048509504, + 1.3652674449108269, + -3.8059167813610033, + 0.0 + ], + [ + 1288.944212, + 10.041800537109374, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 93.31509474496671, + -80.30858454547035, + 1.4026720324426303, + -3.7685121938292, + 0.0 + ], + [ + 1288.964175, + 10.0983427734375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 93.34408330030386, + -80.38526394991055, + 1.4494277668573847, + -3.7965656344780525, + 0.0 + ], + [ + 1288.98403, + 10.249122070312499, + 0.75, + -7.610019550342131, + -7.197653958944283, + 93.37494208501761, + -80.46194335435075, + 1.4868323543891881, + -3.8339702220098557, + 0.0 + ], + [ + 1289.004071, + 10.041800537109374, + 0.75, + -7.610019550342131, + -7.197653958944283, + 93.40206041097817, + -80.53768764410265, + 1.5148857950380408, + -3.8246190751269054, + 0.0 + ], + [ + 1289.024086, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.197653958944283, + 93.4319840810036, + -80.61062658978966, + 1.5148857950380408, + -3.7685121938292, + 0.0 + ], + [ + 1289.044264, + 10.079495361328124, + 0.75, + -7.610019550342131, + -7.197653958944283, + 93.46471309509393, + -80.68730599422986, + 1.50553464815509, + -3.7872144875951017, + 0.0 + ], + [ + 1289.06466, + 10.010388183593749, + 0.75, + -7.610019550342131, + -7.197653958944283, + 93.4908963063662, + -80.76585562804665, + 1.496183501272139, + -3.8059167813610033, + 0.0 + ], + [ + 1289.084098, + 10.104625244140625, + 0.75, + -7.610019550342131, + -7.085190615835777, + 93.51801463232675, + -80.76585562804665, + 1.4774812075062371, + -3.8059167813610033, + 0.0 + ], + [ + 1289.104048, + 10.1486025390625, + 0.75, + -7.610019550342131, + -7.085190615835777, + 93.5479383023522, + -80.91079840473239, + 1.4587789137403353, + -3.7404587531803473, + 0.0 + ], + [ + 1289.124102, + 10.104625244140625, + 0.75, + -7.5725317693059635, + -7.085190615835777, + 93.57599174300104, + -80.985607579796, + 1.440076619974434, + -3.7498099000632985, + 0.0 + ], + [ + 1289.144113, + 10.0983427734375, + 0.75, + -7.5725317693059635, + -7.085190615835777, + 93.60498029833819, + -81.06322209892448, + 1.430725473091483, + -3.7591610469462493, + 0.0 + ], + [ + 1289.164109, + 10.18629736328125, + 0.75, + -7.5725317693059635, + -7.085190615835777, + 93.63396885367534, + -81.13990150336468, + 1.421374326208532, + -3.7030541656485436, + 0.0 + ], + [ + 1289.184098, + 10.18629736328125, + 0.75, + -7.5725317693059635, + -7.085190615835777, + 93.66482763838908, + -81.21003510498682, + 1.412023179325581, + -3.7311076062973965, + 0.0 + ], + [ + 1289.204171, + 10.205144775390625, + 0.75, + -7.5725317693059635, + -7.085190615835777, + 93.69475130841452, + -81.2876496241153, + 1.430725473091483, + -3.7591610469462493, + 0.0 + ], + [ + 1289.2241, + 10.029235595703124, + 0.75, + -7.5725317693059635, + -7.085190615835777, + 93.71999940499849, + -81.3652641432438, + 1.4494277668573847, + -3.7591610469462493, + 0.0 + ], + [ + 1289.244138, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.74805284564734, + -81.44381377706058, + 1.4494277668573847, + -3.7591610469462493, + 0.0 + ], + [ + 1289.264058, + 10.073212890625, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.77704140098449, + -81.51862295212419, + 1.440076619974434, + -3.8246190751269054, + 0.0 + ], + [ + 1289.284101, + 10.0480830078125, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.80322461225676, + -81.59810770062928, + 1.421374326208532, + -3.8807259564246106, + 0.0 + ], + [ + 1289.304104, + 10.129755126953125, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.8312780529056, + -81.67385199038118, + 1.4026720324426303, + -3.8620236626587086, + 0.0 + ], + [ + 1289.324083, + 10.192579833984375, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.86026660824275, + -81.75614208295114, + 1.3933208855596793, + -3.9461839846052666, + 0.0 + ], + [ + 1289.344091, + 10.010388183593749, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.88644981951502, + -81.84030240489771, + 1.3839697386767287, + -4.002290865902972, + 0.0 + ], + [ + 1289.364124, + 10.029235595703124, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.91450326016387, + -81.9197871534028, + 1.3839697386767287, + -4.002290865902972, + 0.0 + ], + [ + 1289.384028, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -6.9727272727272736, + 93.94442693018931, + -82.00207724597276, + 1.3839697386767287, + -4.039695453434775, + 0.0 + ], + [ + 1289.404157, + 10.079495361328124, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 93.96873991208498, + -82.0881077972959, + 1.3839697386767287, + -4.142558069147235, + 0.0 + ], + [ + 1289.424127, + 10.079495361328124, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 93.99585823804554, + -82.16759254580099, + 1.3746185917937774, + -4.114504628498382, + 0.0 + ], + [ + 1289.444072, + 10.004105712890624, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 94.02391167869439, + -82.24614217961778, + 1.3652674449108269, + -4.0677488940836275, + 0.0 + ], + [ + 1289.464026, + 10.066930419921874, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 94.04822466059007, + -82.33123761625262, + 1.355916298027876, + -4.114504628498382, + 0.0 + ], + [ + 1289.48402, + 10.0983427734375, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 94.07721321592722, + -82.41633305288748, + 1.346565151144925, + -4.105153481615432, + 0.0 + ], + [ + 1289.504095, + 10.06064794921875, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 94.10526665657606, + -82.49394757201597, + 1.346565151144925, + -4.058397747200678, + 0.0 + ], + [ + 1289.524078, + 10.041800537109374, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 94.13425521191321, + -82.57997812333912, + 1.346565151144925, + -4.114504628498382, + 0.0 + ], + [ + 1289.544282, + 10.11090771484375, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 94.16230865256206, + -82.6603979865325, + 1.355916298027876, + -4.133206922264284, + 0.0 + ], + [ + 1289.564067, + 9.928716064453125, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.18849186383433, + -82.74923388192053, + 1.3746185917937774, + -4.179962656679038, + 0.0 + ], + [ + 1289.584062, + 9.966410888671875, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.21748041917148, + -82.83526443324368, + 1.3933208855596793, + -4.226718391093793, + 0.0 + ], + [ + 1289.604138, + 9.96012841796875, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.24553385982033, + -82.91942475519024, + 1.4026720324426303, + -4.254771831742645, + 0.0 + ], + [ + 1289.624085, + 9.941281005859375, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.269846841716, + -82.99703927431872, + 1.3933208855596793, + -4.179962656679038, + 0.0 + ], + [ + 1289.644074, + 10.073212890625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.29790028236485, + -83.07745913751211, + 1.3746185917937774, + -4.179962656679038, + 0.0 + ], + [ + 1289.664075, + 10.092060302734374, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.326888837702, + -83.16255457414695, + 1.3652674449108269, + -4.142558069147235, + 0.0 + ], + [ + 1289.68413, + 9.8973037109375, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.35307204897427, + -83.23923397858715, + 1.346565151144925, + -4.039695453434775, + 0.0 + ], + [ + 1289.704091, + 10.004105712890624, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 94.38112548962312, + -83.32152407115713, + 1.346565151144925, + -4.0209931596688735, + 0.0 + ], + [ + 1289.724102, + 9.991540771484374, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.40824381558367, + -83.41223019592175, + 1.355916298027876, + -4.105153481615432, + 0.0 + ], + [ + 1289.744072, + 9.891021240234375, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.43442702685594, + -83.48984471505024, + 1.355916298027876, + -4.123855775381333, + 0.0 + ], + [ + 1289.764028, + 9.98525830078125, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.4606102381282, + -83.56839434886703, + 1.355916298027876, + -4.058397747200678, + 0.0 + ], + [ + 1289.784122, + 9.953845947265625, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.48772856408875, + -83.64600886799552, + 1.355916298027876, + -4.0677488940836275, + 0.0 + ], + [ + 1289.804055, + 10.010388183593749, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.51484689004931, + -83.73016918994207, + 1.346565151144925, + -4.077100040966578, + 0.0 + ], + [ + 1289.824184, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.54383544538646, + -83.80591347969398, + 1.346565151144925, + -3.9835885721370703, + 0.0 + ], + [ + 1289.844103, + 10.0480830078125, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.57188888603531, + -83.88913868695224, + 1.346565151144925, + -3.9835885721370703, + 0.0 + ], + [ + 1289.86411, + 10.06064794921875, + 0.75, + -7.5725317693059635, + -7.047702834799609, + 94.60181255606075, + -83.97142877952221, + 1.3652674449108269, + -4.030344306551824, + 0.0 + ], + [ + 1289.884113, + 9.991540771484374, + 0.75, + -7.5725317693059635, + -7.160166177908114, + 94.63547668483938, + -84.04997841333899, + 1.3933208855596793, + -4.039695453434775, + 0.0 + ], + [ + 1289.904073, + 9.928716064453125, + 0.75, + -7.5725317693059635, + -7.160166177908114, + 94.66446524017653, + -84.13600896466214, + 1.430725473091483, + -4.0677488940836275, + 0.0 + ], + [ + 1289.924102, + 10.079495361328124, + 0.75, + -7.610019550342131, + -7.160166177908114, + 94.69532402489027, + -84.21736394254381, + 1.4681300606232863, + -4.114504628498382, + 0.0 + ], + [ + 1289.944063, + 9.96012841796875, + 0.75, + -7.610019550342131, + -7.160166177908114, + 94.72337746553912, + -84.30152426449037, + 1.496183501272139, + -4.133206922264284, + 0.0 + ], + [ + 1289.964085, + 9.978975830078125, + 0.75, + -7.610019550342131, + -7.160166177908114, + 94.75330113556456, + -84.38194412768375, + 1.50553464815509, + -4.105153481615432, + 0.0 + ], + [ + 1289.984073, + 10.173732421875, + 0.75, + -7.610019550342131, + -7.160166177908114, + 94.78135457621342, + -84.46236399087714, + 1.50553464815509, + -4.114504628498382, + 0.0 + ], + [ + 1290.004088, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.160166177908114, + 94.80660267279738, + -84.5446540834471, + 1.4868323543891881, + -4.08645118784953, + 0.0 + ], + [ + 1290.024056, + 10.104625244140625, + 0.75, + -7.610019550342131, + -7.160166177908114, + 94.83746145751113, + -84.62694417601706, + 1.4587789137403353, + -4.095802334732481, + 0.0 + ], + [ + 1290.044222, + 10.142320068359375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 94.86645001284826, + -84.7148449567168, + 1.430725473091483, + -4.133206922264284, + 0.0 + ], + [ + 1290.064091, + 10.129755126953125, + 0.75, + -7.610019550342131, + -7.23514173998045, + 94.89076299474394, + -84.80087550803995, + 1.412023179325581, + -4.142558069147235, + 0.0 + ], + [ + 1290.084057, + 10.167449951171875, + 0.75, + -7.610019550342131, + -7.23514173998045, + 94.91881643539278, + -84.88597094467481, + 1.3933208855596793, + -4.236069537976743, + 0.0 + ], + [ + 1290.104331, + 9.997823242187499, + 0.75, + -7.610019550342131, + -7.23514173998045, + 94.94593476135334, + -84.97387172537454, + 1.3839697386767287, + -4.2921764192744485, + 0.0 + ], + [ + 1290.12409, + 10.0983427734375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 94.97211797262561, + -85.06270762076258, + 1.3652674449108269, + -4.357634447455105, + 0.0 + ], + [ + 1290.144052, + 10.154885009765625, + 0.75, + -7.610019550342131, + -7.23514173998045, + 95.00017141327446, + -85.1524786308389, + 1.355916298027876, + -4.376336741221007, + 0.0 + ], + [ + 1290.16406, + 10.129755126953125, + 0.75, + -7.610019550342131, + -7.23514173998045, + 95.02635462454673, + -85.23850918216205, + 1.355916298027876, + -4.423092475635761, + 0.0 + ], + [ + 1290.18408, + 10.104625244140625, + 0.75, + -7.610019550342131, + -7.23514173998045, + 95.05440806519557, + -85.3254748481735, + 1.346565151144925, + -4.404390181869859, + 0.0 + ], + [ + 1290.204074, + 10.129755126953125, + 0.75, + -7.610019550342131, + -7.272629521016618, + 95.08246150584444, + -85.41431074356153, + 1.346565151144925, + -4.395039034986908, + 0.0 + ], + [ + 1290.224114, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.272629521016618, + 95.11051494649328, + -85.49660083613149, + 1.355916298027876, + -4.348283300572154, + 0.0 + ], + [ + 1290.244076, + 10.1486025390625, + 0.75, + -7.5725317693059635, + -7.272629521016618, + 95.14137373120703, + -85.58730696089611, + 1.3746185917937774, + -4.348283300572154, + 0.0 + ], + [ + 1290.26407, + 10.16116748046875, + 0.75, + -7.5725317693059635, + -7.272629521016618, + 95.17316763060906, + -85.67053216815438, + 1.3933208855596793, + -4.320229859923302, + 0.0 + ], + [ + 1290.284191, + 10.004105712890624, + 0.75, + -7.5725317693059635, + -7.272629521016618, + 95.2012210712579, + -85.76404363698389, + 1.421374326208532, + -4.376336741221007, + 0.0 + ], + [ + 1290.304316, + 10.192579833984375, + 0.75, + -7.5725317693059635, + -7.272629521016618, + 95.23114474128334, + -85.8575551058134, + 1.4494277668573847, + -4.432443622518712, + 0.0 + ], + [ + 1290.324106, + 10.117190185546875, + 0.75, + -7.5725317693059635, + -7.272629521016618, + 95.2601332966205, + -85.95854749214926, + 1.4681300606232863, + -4.563359678880024, + 0.0 + ], + [ + 1290.344118, + 10.092060302734374, + 0.75, + -7.5725317693059635, + -7.272629521016618, + 95.28818673726936, + -86.04177269940753, + 1.4774812075062371, + -4.544657385114122, + 0.0 + ], + [ + 1290.364068, + 10.2239921875, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 95.31904552198309, + -86.13528416823704, + 1.4774812075062371, + -4.647520000826582, + 0.0 + ], + [ + 1290.384072, + 10.180014892578125, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 95.34709896263195, + -86.22599029300166, + 1.4681300606232863, + -4.62881770706068, + 0.0 + ], + [ + 1290.404037, + 10.06064794921875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.37795774734568, + -86.31669641776628, + 1.4681300606232863, + -4.591413119528877, + 0.0 + ], + [ + 1290.424282, + 10.1988623046875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.40975164674771, + -86.4102078865958, + 1.4681300606232863, + -4.572710825762974, + 0.0 + ], + [ + 1290.444115, + 10.12347265625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.43780508739657, + -86.49623843791895, + 1.4681300606232863, + -4.554008531997073, + 0.0 + ], + [ + 1290.46411, + 10.154885009765625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.4695989867986, + -86.59536059487823, + 1.4868323543891881, + -4.600764266411828, + 0.0 + ], + [ + 1290.48407, + 10.13603759765625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.49952265682404, + -86.69074229308433, + 1.496183501272139, + -4.656871147709532, + 0.0 + ], + [ + 1290.50412, + 10.129755126953125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.53131655622607, + -86.78612399129042, + 1.50553464815509, + -4.703626882124286, + 0.0 + ], + [ + 1290.524061, + 10.092060302734374, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.56591579969299, + -86.8843110335614, + 1.5242369419209916, + -4.684924588358385, + 0.0 + ], + [ + 1290.544112, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.59303412565355, + -86.97688738770262, + 1.5335880888039424, + -4.797138350953796, + 0.0 + ], + [ + 1290.564133, + 10.192579833984375, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.62482802505558, + -87.06852862715553, + 1.5429392356868932, + -4.73168032277314, + 0.0 + ], + [ + 1290.584084, + 10.073212890625, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.65475169508102, + -87.16110498129675, + 1.5522903825698442, + -4.6942757352413365, + 0.0 + ], + [ + 1290.604108, + 10.004105712890624, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.68841582385964, + -87.2480706473082, + 1.5522903825698442, + -4.62881770706068, + 0.0 + ], + [ + 1290.624069, + 10.022953124999999, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.72020972326168, + -87.35093326302065, + 1.5522903825698442, + -4.666222294592483, + 0.0 + ], + [ + 1290.64405, + 9.991540771484374, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.74919827859883, + -87.43883404372039, + 1.5522903825698442, + -4.619466560177729, + 0.0 + ], + [ + 1290.664037, + 9.991540771484374, + 0.75, + -7.610019550342131, + -7.160166177908114, + 95.78286240737745, + -87.53795620067967, + 1.5522903825698442, + -4.6942757352413365, + 0.0 + ], + [ + 1290.684104, + 10.010388183593749, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.8118509627146, + -87.63801347232724, + 1.561641529452795, + -4.778436057187894, + 0.0 + ], + [ + 1290.704093, + 10.0983427734375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.84177463274004, + -87.74274631741629, + 1.561641529452795, + -4.881298672900353, + 0.0 + ], + [ + 1290.724051, + 9.916151123046875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.87076318807719, + -87.83625778624581, + 1.5522903825698442, + -4.900000966666255, + 0.0 + ], + [ + 1290.744056, + 10.004105712890624, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.89507616997287, + -87.92883414038701, + 1.5148857950380408, + -4.900000966666255, + 0.0 + ], + [ + 1290.764076, + 10.035518066406249, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.9249998399983, + -88.03263187078777, + 1.4774812075062371, + -4.946756701081009, + 0.0 + ], + [ + 1290.784101, + 9.903586181640625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.95492351002375, + -88.13175402774705, + 1.440076619974434, + -4.890649819783304, + 0.0 + ], + [ + 1290.804073, + 9.991540771484374, + 0.75, + -7.610019550342131, + -7.197653958944283, + 95.9820418359843, + -88.21404412031701, + 1.421374326208532, + -4.778436057187894, + 0.0 + ], + [ + 1290.82408, + 9.92243359375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 96.01009527663315, + -88.3131662772763, + 1.412023179325581, + -4.769084910304943, + 0.0 + ], + [ + 1290.84411, + 9.916151123046875, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.03814871728201, + -88.41228843423558, + 1.4026720324426303, + -4.834542938485599, + 0.0 + ], + [ + 1290.864209, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.06339681386598, + -88.51702127932462, + 1.4026720324426303, + -4.797138350953796, + 0.0 + ], + [ + 1290.88417, + 10.066930419921874, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.08958002513823, + -88.61240297753072, + 1.3839697386767287, + -4.853245232251501, + 0.0 + ], + [ + 1290.904057, + 10.016670654296874, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.1157632364105, + -88.70778467573682, + 1.3652674449108269, + -4.881298672900353, + 0.0 + ], + [ + 1290.924119, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.13820598892958, + -88.79942591518974, + 1.3372140042619742, + -4.853245232251501, + 0.0 + ], + [ + 1290.944209, + 10.041800537109374, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.16345408551355, + -88.9022885309022, + 1.3091605636131214, + -4.900000966666255, + 0.0 + ], + [ + 1290.964143, + 10.154885009765625, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.18870218209751, + -88.99954045848489, + 1.281107122964269, + -4.8251917916026485, + 0.0 + ], + [ + 1290.984069, + 10.041800537109374, + 0.75, + -7.610019550342131, + -7.085190615835777, + 96.21301516399319, + -89.10520841826224, + 1.2624048291983672, + -4.881298672900353, + 0.0 + ], + [ + 1291.004107, + 10.010388183593749, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.24106860464204, + -89.19871988709174, + 1.2437025354324653, + -4.900000966666255, + 0.0 + ], + [ + 1291.024069, + 10.066930419921874, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.26631670122602, + -89.29597181467443, + 1.2437025354324653, + -4.984161288612813, + 0.0 + ], + [ + 1291.044103, + 9.997823242187499, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.29343502718658, + -89.40631534789325, + 1.2530536823154166, + -5.040268169910518, + 0.0 + ], + [ + 1291.064141, + 9.972693359375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.32055335314713, + -89.50263216078764, + 1.281107122964269, + -5.077672757442322, + 0.0 + ], + [ + 1291.084033, + 10.12347265625, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.34860679379598, + -89.60268943243523, + 1.2998094167301708, + -5.021565876144617, + 0.0 + ], + [ + 1291.104031, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.37479000506823, + -89.70929250690087, + 1.3278628573790232, + -5.152481932505929, + 0.0 + ], + [ + 1291.124037, + 10.142320068359375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.40377856040539, + -89.81309023730162, + 1.346565151144925, + -5.105726198091174, + 0.0 + ], + [ + 1291.144093, + 10.21142724609375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.43089688636594, + -89.9112772795726, + 1.355916298027876, + -5.049619316793469, + 0.0 + ], + [ + 1291.164059, + 10.21142724609375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.45708009763821, + -90.01507500997336, + 1.3652674449108269, + -5.124428491857076, + 0.0 + ], + [ + 1291.1843, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.48513353828706, + -90.11419716693264, + 1.3652674449108269, + -5.105726198091174, + 0.0 + ], + [ + 1291.204145, + 10.18629736328125, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.51225186424762, + -90.2170597826451, + 1.3652674449108269, + -5.087023904325273, + 0.0 + ], + [ + 1291.224091, + 10.142320068359375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.54124041958477, + -90.31711705429267, + 1.3652674449108269, + -5.105726198091174, + 0.0 + ], + [ + 1291.244095, + 10.13603759765625, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.57022897492192, + -90.4255903581349, + 1.3746185917937774, + -5.133779638740027, + 0.0 + ], + [ + 1291.264053, + 10.129755126953125, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.5945419568176, + -90.53593389135372, + 1.3746185917937774, + -5.208588813803634, + 0.0 + ], + [ + 1291.284066, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.62353051215473, + -90.63973162175448, + 1.3839697386767287, + -5.255344548218388, + 0.0 + ], + [ + 1291.304053, + 10.274251953124999, + 0.75, + -7.610019550342131, + -7.23514173998045, + 96.6478434940504, + -90.75194538434988, + 1.3746185917937774, + -5.348856017047897, + 0.0 + ], + [ + 1291.324074, + 10.2239921875, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.67028624656949, + -90.85667822943893, + 1.355916298027876, + -5.3862606045797, + 0.0 + ], + [ + 1291.344128, + 10.12347265625, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.69366411377686, + -90.96141107452799, + 1.3185117104960726, + -5.3675583108137985, + 0.0 + ], + [ + 1291.36428, + 10.092060302734374, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.71610686629595, + -91.07362483712339, + 1.2717559760813182, + -5.3862606045797, + 0.0 + ], + [ + 1291.384065, + 10.1486025390625, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.73854961881503, + -91.18116302627733, + 1.2250002416665637, + -5.423665192111504, + 0.0 + ], + [ + 1291.404118, + 10.192579833984375, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.7619274860224, + -91.28963633011956, + 1.1782445072518093, + -5.3862606045797, + 0.0 + ], + [ + 1291.42411, + 10.2239921875, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.78437023854148, + -91.40278520740327, + 1.150191066602957, + -5.414314045228553, + 0.0 + ], + [ + 1291.444055, + 10.18629736328125, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.80494276168398, + -91.50471270842743, + 1.131488772837055, + -5.442367485877405, + 0.0 + ], + [ + 1291.464102, + 10.1988623046875, + 0.75, + -7.610019550342131, + -7.347605083088955, + 96.82458017013818, + -91.61879670039943, + 1.1221376259541043, + -5.442367485877405, + 0.0 + ], + [ + 1291.484073, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.84515269328067, + -91.73007534830654, + 1.0940841853052516, + -5.479772073409209, + 0.0 + ], + [ + 1291.504102, + 10.092060302734374, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.86479010173487, + -91.84228911090196, + 1.0753818915393498, + -5.517176660941012, + 0.0 + ], + [ + 1291.524125, + 10.13603759765625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.88536262487736, + -91.95076241474419, + 1.0473284508904972, + -5.535878954706915, + 0.0 + ], + [ + 1291.544118, + 10.16116748046875, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.90780537739644, + -92.05456014514493, + 1.0286261571245956, + -5.489123220292161, + 0.0 + ], + [ + 1291.564126, + 10.092060302734374, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.92931301522722, + -92.16490367836376, + 1.0192750102416446, + -5.461069779643307, + 0.0 + ], + [ + 1291.584106, + 10.092060302734374, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.95082065305802, + -92.2705716381411, + 1.0286261571245956, + -5.404962898345602, + 0.0 + ], + [ + 1291.604097, + 9.991540771484374, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.97139317620051, + -92.38278540073651, + 1.0379773040075464, + -5.423665192111504, + 0.0 + ], + [ + 1291.624178, + 10.154885009765625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 96.99477104340788, + -92.49032358989045, + 1.0566795977734482, + -5.330153723281995, + 0.0 + ], + [ + 1291.644097, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.01814891061527, + -92.59412132029121, + 1.066030744656399, + -5.339504870164946, + 0.0 + ], + [ + 1291.664103, + 10.035518066406249, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.04246189251093, + -92.69324347725049, + 1.0940841853052516, + -5.283397988867241, + 0.0 + ], + [ + 1291.684112, + 10.117190185546875, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.06958021847149, + -92.79891143702783, + 1.1127864790711532, + -5.283397988867241, + 0.0 + ], + [ + 1291.704054, + 10.117190185546875, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.09576342974376, + -92.90925497024665, + 1.150191066602957, + -5.245993401335437, + 0.0 + ], + [ + 1291.724117, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.12194664101601, + -93.01772827408888, + 1.1969468010177111, + -5.339504870164946, + 0.0 + ], + [ + 1291.744072, + 10.029235595703124, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.14906496697657, + -93.12339623386623, + 1.2437025354324653, + -5.348856017047897, + 0.0 + ], + [ + 1291.76406, + 10.035518066406249, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.17618329293713, + -93.23186953770845, + 1.281107122964269, + -5.3862606045797, + 0.0 + ], + [ + 1291.784111, + 10.022953124999999, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.2023665042094, + -93.3375374974858, + 1.3091605636131214, + -5.3862606045797, + 0.0 + ], + [ + 1291.804058, + 10.010388183593749, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.22948483016995, + -93.43572453975678, + 1.3278628573790232, + -5.264695695101339, + 0.0 + ], + [ + 1291.824072, + 10.010388183593749, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.2603436148837, + -93.54045738484584, + 1.346565151144925, + -5.217939960686585, + 0.0 + ], + [ + 1291.84407, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.28839705553254, + -93.64051465649341, + 1.355916298027876, + -5.17118422627183, + 0.0 + ], + [ + 1291.864089, + 10.104625244140625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.31832072555798, + -93.7358963546995, + 1.3839697386767287, + -5.040268169910518, + 0.0 + ], + [ + 1291.884081, + 9.997823242187499, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.3519848543366, + -93.83782385572367, + 1.412023179325581, + -5.002863582378715, + 0.0 + ], + [ + 1291.904125, + 10.073212890625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.38190852436205, + -93.93881624205954, + 1.4494277668573847, + -4.974810141729861, + 0.0 + ], + [ + 1291.924098, + 10.054365478515624, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.41370242376408, + -94.03232771088905, + 1.4774812075062371, + -4.9187032604321566, + 0.0 + ], + [ + 1291.944093, + 10.073212890625, + 0.75, + -7.610019550342131, + -7.122678396871946, + 97.44643143785441, + -94.13893078535469, + 1.5242369419209916, + -4.937405554198059, + 0.0 + ], + [ + 1291.964094, + 10.117190185546875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.48009556663304, + -94.22963691011931, + 1.5522903825698442, + -4.937405554198059, + 0.0 + ], + [ + 1291.984086, + 9.997823242187499, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.51282458072336, + -94.3287590670786, + 1.5803438232186968, + -4.9187032604321566, + 0.0 + ], + [ + 1292.004071, + 9.966410888671875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.5436833654371, + -94.42601099466128, + 1.6083972638675494, + -4.928054407315107, + 0.0 + ], + [ + 1292.024116, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.57547726483914, + -94.52232780755567, + 1.6177484107505002, + -4.84389408536855, + 0.0 + ], + [ + 1292.044553, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.60727116424117, + -94.61957973513836, + 1.6083972638675494, + -4.806489497836746, + 0.0 + ], + [ + 1292.064101, + 10.041800537109374, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.6381299489549, + -94.7084156305264, + 1.5990461169845984, + -4.7877872040708445, + 0.0 + ], + [ + 1292.084043, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.66711850429205, + -94.8009919846676, + 1.5803438232186968, + -4.722329175890189, + 0.0 + ], + [ + 1292.104071, + 9.941281005859375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.69984751838238, + -94.90104925631519, + 1.561641529452795, + -4.750382616539041, + 0.0 + ], + [ + 1292.124087, + 10.0480830078125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.7325765324727, + -95.00204164265105, + 1.5522903825698442, + -4.853245232251501, + 0.0 + ], + [ + 1292.144155, + 9.966410888671875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.76343531718645, + -95.09461799679227, + 1.5522903825698442, + -4.797138350953796, + 0.0 + ], + [ + 1292.164059, + 9.966410888671875, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.79335898721189, + -95.19467526843984, + 1.5522903825698442, + -4.853245232251501, + 0.0 + ], + [ + 1292.184061, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.82141242786074, + -95.29005696664593, + 1.5522903825698442, + -4.881298672900353, + 0.0 + ], + [ + 1292.204253, + 9.928716064453125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.85133609788619, + -95.39011423829352, + 1.5429392356868932, + -4.84389408536855, + 0.0 + ], + [ + 1292.224025, + 10.079495361328124, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.88219488259992, + -95.48175547774643, + 1.5242369419209916, + -4.797138350953796, + 0.0 + ], + [ + 1292.244045, + 10.12347265625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.90931320856048, + -95.57246160251105, + 1.50553464815509, + -4.7877872040708445, + 0.0 + ], + [ + 1292.264036, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 97.93923687858592, + -95.67158375947034, + 1.4774812075062371, + -4.7410314696560905, + 0.0 + ], + [ + 1292.284181, + 10.016670654296874, + 0.75, + -7.610019550342131, + -7.23514173998045, + 97.97103077798795, + -95.76509522829984, + 1.4681300606232863, + -4.750382616539041, + 0.0 + ], + [ + 1292.304036, + 10.104625244140625, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.0000193333251, + -95.85860669712935, + 1.4587789137403353, + -4.73168032277314, + 0.0 + ], + [ + 1292.324092, + 10.11090771484375, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.03087811803884, + -95.95118305127056, + 1.4681300606232863, + -4.6942757352413365, + 0.0 + ], + [ + 1292.344695, + 10.054365478515624, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.0579964439994, + -96.05030520822984, + 1.4774812075062371, + -4.769084910304943, + 0.0 + ], + [ + 1292.364053, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.0579964439994, + -96.05030520822984, + 1.4774812075062371, + -4.769084910304943, + 0.0 + ], + [ + 1292.38406, + 10.092060302734374, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.11784378405028, + -96.22704188431761, + 1.4868323543891881, + -4.619466560177729, + 0.0 + ], + [ + 1292.404184, + 10.092060302734374, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.14683233938743, + -96.31774800908224, + 1.4774812075062371, + -4.591413119528877, + 0.0 + ], + [ + 1292.424107, + 10.06064794921875, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.17395066534799, + -96.4009732163405, + 1.4681300606232863, + -4.507252797582319, + 0.0 + ], + [ + 1292.444065, + 10.073212890625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.20387433537343, + -96.49261445579342, + 1.4494277668573847, + -4.376336741221007, + 0.0 + ], + [ + 1292.464101, + 10.13603759765625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.23379800539887, + -96.58519080993463, + 1.4494277668573847, + -4.488550503816417, + 0.0 + ], + [ + 1292.484066, + 10.073212890625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.26465679011261, + -96.67215647594608, + 1.4494277668573847, + -4.451145916284613, + 0.0 + ], + [ + 1292.504105, + 10.11090771484375, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.29364534544976, + -96.76660305946388, + 1.4587789137403353, + -4.488550503816417, + 0.0 + ], + [ + 1292.524047, + 10.129755126953125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.32263390078691, + -96.86479010173487, + 1.4587789137403353, + -4.582061972645926, + 0.0 + ], + [ + 1292.544096, + 10.066930419921874, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.34975222674747, + -96.94895042368142, + 1.4681300606232863, + -4.610115413294778, + 0.0 + ], + [ + 1292.564083, + 10.1486025390625, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.37780566739632, + -97.04526723657582, + 1.4587789137403353, + -4.535306238231171, + 0.0 + ], + [ + 1292.584055, + 10.066930419921874, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.40772933742176, + -97.13410313196385, + 1.4494277668573847, + -4.582061972645926, + 0.0 + ], + [ + 1292.604105, + 10.08577783203125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.43578277807062, + -97.21639322453382, + 1.430725473091483, + -4.497901650699368, + 0.0 + ], + [ + 1292.624098, + 10.180014892578125, + 0.75, + -7.610019550342131, + -7.197653958944283, + 98.47131713622582, + -97.30522911992185, + 1.440076619974434, + -4.451145916284613, + 0.0 + ], + [ + 1292.644126, + 10.079495361328124, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.50404615031616, + -97.40061081812794, + 1.4681300606232863, + -4.5166039444652695, + 0.0 + ], + [ + 1292.664057, + 10.022953124999999, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.53116447627671, + -97.49599251633406, + 1.496183501272139, + -4.563359678880024, + 0.0 + ], + [ + 1292.684066, + 10.1486025390625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.56108814630215, + -97.58763375578697, + 1.5242369419209916, + -4.572710825762974, + 0.0 + ], + [ + 1292.704092, + 10.066930419921874, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.58727135757442, + -97.68114522461647, + 1.5242369419209916, + -4.656871147709532, + 0.0 + ], + [ + 1292.724059, + 10.1486025390625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.61719502759986, + -97.7727864640694, + 1.5148857950380408, + -4.675573441475434, + 0.0 + ], + [ + 1292.744107, + 10.192579833984375, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 98.65085915637849, + -97.85881701539255, + 1.4868323543891881, + -4.582061972645926, + 0.0 + ], + [ + 1292.764113, + 10.117190185546875, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.67891259702733, + -97.94765291078058, + 1.4774812075062371, + -4.5166039444652695, + 0.0 + ], + [ + 1292.784101, + 10.154885009765625, + 0.75, + -7.5725317693059635, + -7.23514173998045, + 98.70883626705277, + -98.03181323272713, + 1.4681300606232863, + -4.441794769401662, + 0.0 + ], + [ + 1292.804039, + 10.041800537109374, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.73969505176652, + -98.11877889873858, + 1.4774812075062371, + -4.357634447455105, + 0.0 + ], + [ + 1292.82406, + 10.029235595703124, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.77522940992174, + -98.20480945006173, + 1.50553464815509, + -4.320229859923302, + 0.0 + ], + [ + 1292.844076, + 10.016670654296874, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.80795842401206, + -98.29925603357952, + 1.5335880888039424, + -4.357634447455105, + 0.0 + ], + [ + 1292.864064, + 9.953845947265625, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.8378820940375, + -98.37687055270803, + 1.561641529452795, + -4.2921764192744485, + 0.0 + ], + [ + 1292.884096, + 9.916151123046875, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.87154622281612, + -98.46570644809606, + 1.5896949701016476, + -4.348283300572154, + 0.0 + ], + [ + 1292.904108, + 9.916151123046875, + 0.75, + -7.610019550342131, + -7.23514173998045, + 98.89959966346497, + -98.55547745817239, + 1.5990461169845984, + -4.376336741221007, + 0.0 + ], + [ + 1292.924075, + 9.90986865234375, + 0.75, + -7.610019550342131, + -7.122678396871946, + 98.93139356286702, + -98.63776755074235, + 1.5896949701016476, + -4.3389321536892025, + 0.0 + ], + [ + 1292.944072, + 9.991540771484374, + 0.75, + -7.610019550342131, + -7.122678396871946, + 98.96225234758074, + -98.72099275800062, + 1.5803438232186968, + -4.264122978625596, + 0.0 + ], + [ + 1292.964387, + 10.117190185546875, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 98.99311113229449, + -98.81356911214183, + 1.5522903825698442, + -4.320229859923302, + 0.0 + ], + [ + 1292.9841, + 10.035518066406249, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 99.02396991700822, + -98.88931340189373, + 1.5335880888039424, + -4.217367244210842, + 0.0 + ], + [ + 1293.004197, + 10.12347265625, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 99.05202335765708, + -98.972538609152, + 1.5242369419209916, + -4.179962656679038, + 0.0 + ], + [ + 1293.024111, + 9.997823242187499, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 99.08662260112399, + -99.06417984860491, + 1.5242369419209916, + -4.20801609732789, + 0.0 + ], + [ + 1293.044065, + 9.972693359375, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 99.11935161521433, + -99.14553482648658, + 1.5429392356868932, + -4.2454206848596945, + 0.0 + ], + [ + 1293.064055, + 10.041800537109374, + 0.75, + -7.5725317693059635, + -7.122678396871946, + 99.14927528523977, + -99.22782491905654, + 1.5522903825698442, + -4.189313803561989, + 0.0 + ], + [ + 1293.084062, + 9.928716064453125, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.18387452870668, + -99.31198524100311, + 1.561641529452795, + -4.226718391093793, + 0.0 + ], + [ + 1293.104083, + 9.93499853515625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.21286308404383, + -99.39614556294967, + 1.5803438232186968, + -4.217367244210842, + 0.0 + ], + [ + 1293.124117, + 9.98525830078125, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.24465698344586, + -99.47563031145475, + 1.5803438232186968, + -4.161260362913136, + 0.0 + ], + [ + 1293.144064, + 9.991540771484374, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.2764508828479, + -99.55605017464812, + 1.5896949701016476, + -4.105153481615432, + 0.0 + ], + [ + 1293.164037, + 10.11090771484375, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.30730966756164, + -99.63553492315322, + 1.5803438232186968, + -4.08645118784953, + 0.0 + ], + [ + 1293.184094, + 10.08577783203125, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.33910356696367, + -99.7150196716583, + 1.570992676335746, + -4.039695453434775, + 0.0 + ], + [ + 1293.204091, + 9.953845947265625, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.36809212230081, + -99.79543953485167, + 1.570992676335746, + -3.964886278371168, + 0.0 + ], + [ + 1293.224116, + 10.035518066406249, + 0.75, + -7.5725317693059635, + -7.197653958944283, + 99.40549670983262, + -99.87772962742163, + 1.570992676335746, + -4.011642012785923, + 0.0 + ], + [ + 1293.244058, + 9.953845947265625, + 0.75, + -7.5725317693059635, + -7.160166177908114, + 99.43542037985806, + -99.95721437592672, + 1.5803438232186968, + -4.002290865902972, + 0.0 + ], + [ + 1293.264029, + 10.481573486328125, + 0.75, + -7.5725317693059635, + -7.160166177908114, + 99.4662791645718, + -100.0366991244318, + 1.5896949701016476, + -4.002290865902972, + 0.0 + ], + [ + 1293.28407, + 10.61350537109375, + 0.75, + -7.647507331378298, + -7.160166177908114, + 99.49900817866212, + -100.1143136435603, + 1.5896949701016476, + -3.992939719020021, + 0.0 + ], + [ + 1293.304104, + 10.556963134765624, + 0.75, + -7.647507331378298, + -7.160166177908114, + 99.5233211605578, + -100.17603121298777, + 1.5803438232186968, + -3.843321368892807, + 0.0 + ], + [ + 1293.32412, + 10.481573486328125, + 0.75, + -7.647507331378298, + -7.160166177908114, + 99.54856925714176, + -100.23868389710354, + 1.5522903825698442, + -3.6188938437019864, + 0.0 + ], + [ + 1293.344101, + 10.632352783203125, + 0.75, + -7.647507331378298, + -7.160166177908114, + 99.57568758310232, + -100.29292054902466, + 1.4868323543891881, + -3.3664128778623126, + 0.0 + ], + [ + 1293.364139, + 10.506703369140626, + 0.75, + -7.647507331378298, + -7.160166177908114, + 99.60093567968629, + -100.3424816275043, + 1.421374326208532, + -3.057825030724934, + 0.0 + ], + [ + 1293.384098, + 10.619787841796875, + 0.75, + -7.647507331378298, + -7.160166177908114, + 99.62431354689367, + -100.39297782067223, + 1.3652674449108269, + -2.777290624236408, + 0.0 + ], + [ + 1293.404095, + 10.575810546875, + 0.75, + -7.647507331378298, + -7.460068426197458, + 99.64862652878934, + -100.4378633257104, + 1.3091605636131214, + -2.6183211272262428, + 0.0 + ], + [ + 1293.424087, + 10.56324560546875, + 0.75, + -7.647507331378298, + -7.460068426197458, + 99.66919905193183, + -100.47900837199538, + 1.2624048291983672, + -2.403244748918373, + 0.0 + ], + [ + 1293.444078, + 10.594657958984374, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.69070668976262, + -100.51734807421548, + 1.215649094783613, + -2.2536263987911593, + 0.0 + ], + [ + 1293.464049, + 10.56324560546875, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.70847386884023, + -100.5510122029941, + 1.1782445072518093, + -2.075954608015093, + 0.0 + ], + [ + 1293.484089, + 10.56324560546875, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.72437081854125, + -100.58000075833125, + 1.1127864790711532, + -1.8795805234731247, + 0.0 + ], + [ + 1293.504113, + 10.6512001953125, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.73746242417738, + -100.60431374022691, + 1.0379773040075464, + -1.6551529982823037, + 0.0 + ], + [ + 1293.52407, + 10.619787841796875, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.74681357106033, + -100.62301603399283, + 0.9444658351780377, + -1.430725473091483, + 0.0 + ], + [ + 1293.544065, + 10.544398193359374, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.7514891445018, + -100.63704275431725, + 0.8229009256996764, + -1.1969468010177111, + 0.0 + ], + [ + 1293.564124, + 10.556963134765624, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.75429448856669, + -100.64919924526508, + 0.6919848693383643, + -0.9818704227098413, + 0.0 + ], + [ + 1293.584109, + 10.48785595703125, + 0.75, + -7.947409579667645, + -7.460068426197458, + 99.75429448856669, + -100.65948550683633, + 0.5423665192111503, + -0.785496338167873, + 0.0 + ], + [ + 1293.604095, + 10.494138427734375, + 0.75, + -7.909921798631476, + -7.460068426197458, + 99.75429448856669, + -100.6660313096544, + 0.3927481690839365, + -0.6171756942747574, + 0.0 + ], + [ + 1293.624145, + 10.556963134765624, + 0.75, + -7.909921798631476, + -7.460068426197458, + 99.75429448856669, + -100.67164199778416, + 0.25248096583967344, + -0.4862596379134452, + 0.0 + ], + [ + 1293.644082, + 10.481573486328125, + 0.75, + -7.909921798631476, + -7.460068426197458, + 99.75429448856669, + -100.67444734184905, + 0.14026720324426303, + -0.3833970222009856, + 0.0 + ], + [ + 1293.664055, + 10.538115722656249, + 0.75, + -7.909921798631476, + -7.460068426197458, + 99.75429448856669, + -100.67538245653735, + 0.06545802818065607, + -0.2618321127226243, + 0.0 + ], + [ + 1293.684109, + 10.494138427734375, + 0.75, + -7.909921798631476, + -7.460068426197458, + 99.75429448856669, + -100.67538245653735, + 0.018702293765901736, + -0.15896949701016477, + 0.0 + ], + [ + 1293.704093, + 10.481573486328125, + 0.75, + -7.909921798631476, + -7.460068426197458, + 99.75429448856669, + -100.67538245653735, + 0.0, + -0.09351146882950868, + 0.0 + ], + [ + 1293.724075, + 10.550680664062499, + 0.75, + -7.909921798631476, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + -0.03740458753180347, + 0.0 + ], + [ + 1293.744246, + 10.481573486328125, + 0.75, + -7.909921798631476, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + -0.009351146882950868, + 0.0 + ], + [ + 1293.764064, + 10.43759619140625, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.784082, + 10.5004208984375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.804418, + 10.43759619140625, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.82409, + 10.41246630859375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.84406, + 10.5004208984375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.864086, + 10.418748779296875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.884095, + 10.46272607421875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.904124, + 10.41246630859375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.924102, + 10.431313720703125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.944231, + 10.519268310546874, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.964156, + 10.4501611328125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1293.984062, + 10.406183837890625, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.004096, + 10.43759619140625, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.024036, + 10.374771484375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.04409, + 10.374771484375, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.064089, + 10.418748779296875, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.084096, + 10.374771484375, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.104237, + 10.469008544921875, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.124084, + 10.368489013671875, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.144271, + 10.431313720703125, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.164325, + 10.512985839843749, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.184091, + 10.41246630859375, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.204083, + 10.36220654296875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.224031, + 10.431313720703125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.244217, + 10.381053955078125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.264117, + 10.36220654296875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.284222, + 10.431313720703125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.304589, + 10.48785595703125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.324075, + 10.431313720703125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.344064, + 10.374771484375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.364113, + 10.368489013671875, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.384095, + 10.41246630859375, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.404073, + 10.3496416015625, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.424069, + 10.38733642578125, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.444088, + 10.43759619140625, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.464051, + 10.431313720703125, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.484063, + 10.406183837890625, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.504097, + 10.456443603515625, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.524151, + 10.38733642578125, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.54408, + 10.512985839843749, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.564076, + 10.443878662109375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.584095, + 10.418748779296875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.604178, + 10.469008544921875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.624042, + 10.46272607421875, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.644086, + 10.443878662109375, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.66407, + 10.538115722656249, + 0.75, + -7.872434017595308, + -7.310117302052786, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.684161, + 10.41246630859375, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.704182, + 10.469008544921875, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.72411, + 10.512985839843749, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.744374, + 10.374771484375, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.764064, + 10.550680664062499, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.784083, + 10.475291015625, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.804131, + 10.494138427734375, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.824092, + 10.556963134765624, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.844098, + 10.469008544921875, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.864025, + 10.48785595703125, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.884084, + 10.550680664062499, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.904049, + 10.443878662109375, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.924099, + 10.46272607421875, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.944092, + 10.519268310546874, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.964155, + 10.48785595703125, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1294.984071, + 10.506703369140626, + 0.75, + -7.872434017595308, + -7.272629521016618, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.004071, + 10.46272607421875, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.024059, + 10.42503125, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.04423, + 10.519268310546874, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.064056, + 10.3999013671875, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.084102, + 10.406183837890625, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.104069, + 10.475291015625, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.124093, + 10.418748779296875, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.144079, + 10.381053955078125, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.164128, + 10.456443603515625, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.184425, + 10.494138427734375, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.204056, + 10.43759619140625, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.224072, + 10.393618896484375, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.244068, + 10.406183837890625, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.264089, + 10.418748779296875, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.284066, + 10.368489013671875, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.304047, + 10.374771484375, + 0.75, + -7.872434017595308, + -7.347605083088955, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.32406, + 10.443878662109375, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.344066, + 10.36220654296875, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ], + [ + 1295.364116, + 10.38733642578125, + 0.75, + -7.872434017595308, + -7.385092864125124, + 99.75429448856669, + -100.67538245653735, + 0.0, + 0.0, + 0.0 + ] + ] +} \ No newline at end of file diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index db473a8..fa5d055 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -62,6 +62,7 @@ void DriveSubsystem::teleop() { SmartDashboard::PutNumber("Right side speed", speeds.right); SmartDashboard::PutNumber("Left side encoder", m_leftSlave.GetSelectedSensorPosition(0)); SmartDashboard::PutNumber("Right side encoder", m_rightMaster.GetSelectedSensorPosition(0)); + SmartDashboard::PutNumber("Gyro angle", m_gyro->GetAngle()); if(driverJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { toggleGear(); @@ -144,7 +145,7 @@ void DriveSubsystem::resetEncoders() { double DriveSubsystem::getStartHeading() { try { - m_gyro = new AHRS(SPI::Port::kMXP); + m_gyro = new AHRS(SerialPort::Port::kMXP); SmartDashboard::PutNumber("Gyro value", std::remainder(m_gyro->GetAngle(), 360)); return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } catch (std::exception ex) { From 99ea4a56ae5d2d43814bf66b75d39f1768e8c9e0 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sat, 7 Mar 2020 16:28:59 -0600 Subject: [PATCH 26/31] Added gyro values to dashboard --- src/DriveSubsystem.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index fa5d055..abed451 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -145,17 +145,18 @@ void DriveSubsystem::resetEncoders() { double DriveSubsystem::getStartHeading() { try { - m_gyro = new AHRS(SerialPort::Port::kMXP); + m_gyro = new AHRS(SerialPort::Port::kUSB); SmartDashboard::PutNumber("Gyro value", std::remainder(m_gyro->GetAngle(), 360)); return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } catch (std::exception ex) { - std::cout << "Gyro isn't working in get heading!" << endl; + std::cout << "Gyro isn't working in get start heading!" << endl; return 0; } } double DriveSubsystem::getHeading() { try { + SmartDashboard::PutNumber("Gyro Yaw", m_gyro->GetYaw()); SmartDashboard::PutNumber("Gyro Heading", std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0)); return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } catch (std::exception ex) { From d7da5df4eb0d2bf3540809d32701a789cd2c8c2b Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Sun, 8 Mar 2020 13:53:51 -0500 Subject: [PATCH 27/31] changed constants --- src/Constants.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/Constants.h b/src/Constants.h index a1ad24c..266e3e2 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -10,7 +10,7 @@ constexpr int kLeftMotor1Port = 0; constexpr int kLeftMotor2Port = 1; constexpr int kRightMotor1Port = 2; constexpr int kRightMotor2Port = 3; - + constexpr int kLeftEncoderPorts[]{0, 1}; constexpr int kRightEncoderPorts[]{2, 3}; constexpr bool kLeftEncoderReversed = false; @@ -27,9 +27,9 @@ constexpr double kEncoderDistancePerPulse = constexpr bool kGyroReversed = true; -constexpr auto ks = 0.22_V; -constexpr auto kv = 1.98 * 1_V * 1_s / 1_m; -constexpr auto ka = 0.2 * 1_V * 1_s * 1_s / 1_m; +constexpr auto ks = 3.14_V; +constexpr auto kv = 0.146 * 1_V * 1_s / 1_m; +constexpr auto ka = 0.193 * 1_V * 1_s * 1_s / 1_m; // Example value only - as above, this must be tuned for your drive! constexpr double kPDriveVel = 8.5; From f1cf2aa8964994598cefb6242e688a8133b5cbfe Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 10 Mar 2020 20:20:08 -0500 Subject: [PATCH 28/31] Testing --- src/Autonomous/SecondAuton.cpp | 20 ++++++++++---------- src/Autonomous/SecondAuton.h | 30 +++++++++++++++--------------- src/Constants.h | 12 +----------- src/DriveSubsystem.cpp | 2 +- src/DriveSubsystem.h | 2 -- src/RobotContainer.cpp | 2 +- src/autonomous/Auton.cpp | 5 +++-- src/autonomous/Auton.h | 2 +- 8 files changed, 32 insertions(+), 43 deletions(-) diff --git a/src/Autonomous/SecondAuton.cpp b/src/Autonomous/SecondAuton.cpp index ae70ecd..a46d4f9 100644 --- a/src/Autonomous/SecondAuton.cpp +++ b/src/Autonomous/SecondAuton.cpp @@ -1,12 +1,12 @@ -#include +// #include -SecondAuton::SecondAuton() : COREAuton("Two Path Test Auto") {} +// SecondAuton::SecondAuton() : COREAuton("Two Path Test Auto") {} -void SecondAuton::AddNodes() { - m_drivePath = new Node(5, new PathFinderAction("foreward.wpilib.json")); - m_wait = new Node(3); - m_secondDrivePath = new Node(5, new PathFinderAction("second.wpilib.json")); - AddFirstNode(m_drivePath); - m_drivePath->AddNext(m_wait); - m_wait->AddNext(m_secondDrivePath); -} +// void SecondAuton::AddNodes() { +// m_drivePath = new Node(5, new PathFinderAction("foreward.wpilib.json")); +// m_wait = new Node(3); +// m_secondDrivePath = new Node(5, new PathFinderAction("second.wpilib.json")); +// AddFirstNode(m_drivePath); +// m_drivePath->AddNext(m_wait); +// m_wait->AddNext(m_secondDrivePath); +// } diff --git a/src/Autonomous/SecondAuton.h b/src/Autonomous/SecondAuton.h index f3ee7e6..3a12098 100644 --- a/src/Autonomous/SecondAuton.h +++ b/src/Autonomous/SecondAuton.h @@ -1,18 +1,18 @@ -#pragma once +// #pragma once -#include -#include -#include +// #include +// #include +// #include -using namespace CORE; -using namespace std; +// using namespace CORE; +// using namespace std; -class SecondAuton: public COREAuton { -public: - SecondAuton(); - void AddNodes() override; -private: - Node * m_drivePath = nullptr; - Node * m_wait = nullptr; - Node * m_secondDrivePath = nullptr; -}; +// class SecondAuton: public COREAuton { +// public: +// SecondAuton(); +// void AddNodes() override; +// private: +// Node * m_drivePath = nullptr; +// Node * m_wait = nullptr; +// Node * m_secondDrivePath = nullptr; +// }; diff --git a/src/Constants.h b/src/Constants.h index 266e3e2..b110919 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -6,17 +6,7 @@ #pragma once namespace DriveConstants { -constexpr int kLeftMotor1Port = 0; -constexpr int kLeftMotor2Port = 1; -constexpr int kRightMotor1Port = 2; -constexpr int kRightMotor2Port = 3; - -constexpr int kLeftEncoderPorts[]{0, 1}; -constexpr int kRightEncoderPorts[]{2, 3}; -constexpr bool kLeftEncoderReversed = false; -constexpr bool kRightEncoderReversed = true; - -constexpr auto kTrackwidth = 0.69_m; +constexpr auto kTrackwidth = 0.69_m; // Not sure if this is correct or if we need to manually measure extern const frc::DifferentialDriveKinematics kDriveKinematics; constexpr int kEncoderCPR = 1024; diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index abed451..b455234 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -145,7 +145,7 @@ void DriveSubsystem::resetEncoders() { double DriveSubsystem::getStartHeading() { try { - m_gyro = new AHRS(SerialPort::Port::kUSB); + m_gyro = new AHRS(SPI::Port::kMXP); SmartDashboard::PutNumber("Gyro value", std::remainder(m_gyro->GetAngle(), 360)); return std::remainder(m_gyro->GetAngle(), 360) * (DriveConstants::kGyroReversed ? -1.0 : 1.0); } catch (std::exception ex) { diff --git a/src/DriveSubsystem.h b/src/DriveSubsystem.h index 016a0a0..3aaa14a 100644 --- a/src/DriveSubsystem.h +++ b/src/DriveSubsystem.h @@ -12,12 +12,10 @@ #include #include #include -#include #include #include #include #include -#include #include #include diff --git a/src/RobotContainer.cpp b/src/RobotContainer.cpp index 748bdd2..5fbc336 100644 --- a/src/RobotContainer.cpp +++ b/src/RobotContainer.cpp @@ -44,7 +44,7 @@ frc2::Command* RobotContainer::GetAutonomousCommand(std::string path) { wpi::SmallString<64> deployDirectory; frc::filesystem::GetDeployDirectory(deployDirectory); wpi::sys::path::append(deployDirectory, "paths"); - wpi::sys::path::append(deployDirectory, path); + wpi::sys::path::append(deployDirectory, "example.wpilib.json"); frc::Trajectory trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory); frc2::RamseteCommand ramseteCommand( diff --git a/src/autonomous/Auton.cpp b/src/autonomous/Auton.cpp index 590bf7c..85629ff 100644 --- a/src/autonomous/Auton.cpp +++ b/src/autonomous/Auton.cpp @@ -3,8 +3,9 @@ Autonomous::Autonomous() : COREAuton("Test Auto") {} void Autonomous::AddNodes() { + std::cout << "running autonomous" << endl; m_drivePath = new Node(15, new PathFinderAction("example.wpilib.json")); - m_secondDrivePath = new Node(15, new PathFinderAction("foreward.wpilib.json")); + // m_secondDrivePath = new Node(15, new PathFinderAction("foreward.wpilib.json")); AddFirstNode(m_drivePath); - m_drivePath->AddNext(m_secondDrivePath); + // m_drivePath->AddNext(m_secondDrivePath); } diff --git a/src/autonomous/Auton.h b/src/autonomous/Auton.h index 7e8a672..601bfe7 100644 --- a/src/autonomous/Auton.h +++ b/src/autonomous/Auton.h @@ -13,5 +13,5 @@ class Autonomous: public COREAuton { void AddNodes() override; private: Node * m_drivePath; - Node * m_secondDrivePath; + // Node * m_secondDrivePath; }; From 55dc1ade42415c2e3e76d3f27d508cfa8718b1e7 Mon Sep 17 00:00:00 2001 From: unknown <50kite17050buster130@gmail.com> Date: Tue, 10 Mar 2020 20:39:17 -0500 Subject: [PATCH 29/31] More changes for merging, does not work yet --- src/IntakeSubsystem.h | 2 +- src/Robot.h | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/IntakeSubsystem.h b/src/IntakeSubsystem.h index 3599f0f..f0e28fc 100644 --- a/src/IntakeSubsystem.h +++ b/src/IntakeSubsystem.h @@ -1,4 +1,4 @@ -// #pragma once +#pragma once #include #include diff --git a/src/Robot.h b/src/Robot.h index 7e619f1..19b678c 100644 --- a/src/Robot.h +++ b/src/Robot.h @@ -7,7 +7,6 @@ #include #include #include "ClimberSubsystem.h" -#include "ControlPanelSubsystem.h" #include "ConveyorSubsystem.h" #include "DriveSubsystem.h" #include "IntakeSubsystem.h" From 65031d4536f48095b62130e77385a79bb936bb4d Mon Sep 17 00:00:00 2001 From: Aidan Lincicum Date: Tue, 8 Dec 2020 17:59:41 -0600 Subject: [PATCH 30/31] Commits made to test Pathfinder --- src/Autonomous/Actions/PathFinder.cpp | 4 ++-- src/Autonomous/Auton.h | 17 +++++++++++++++++ src/ClimberSubsystem.cpp | 2 +- src/ClimberSubsystem.h | 5 +++-- src/Constants.h | 4 +++- src/ConveyorSubsystem.cpp | 8 +------- src/ConveyorSubsystem.h | 5 +++-- src/DriveSubsystem.cpp | 10 +--------- src/IntakeSubsystem.cpp | 3 +-- src/IntakeSubsystem.h | 3 ++- src/LauncherSubsystem.cpp | 5 +++-- src/LauncherSubsystem.h | 8 +++++--- src/Robot.cpp | 5 +---- src/Robot.h | 4 ++++ src/RobotContainer.cpp | 25 +++++++++++++++++++++++++ src/RobotContainer.h | 13 +++++++++++-- src/TurretSubsystem.cpp | 3 +-- src/TurretSubsystem.h | 5 +++-- 18 files changed, 87 insertions(+), 42 deletions(-) create mode 100644 src/Autonomous/Auton.h diff --git a/src/Autonomous/Actions/PathFinder.cpp b/src/Autonomous/Actions/PathFinder.cpp index 366d175..33b53d3 100644 --- a/src/Autonomous/Actions/PathFinder.cpp +++ b/src/Autonomous/Actions/PathFinder.cpp @@ -10,8 +10,8 @@ void PathFinderAction::ActionInit() { } CORE::COREAutonAction::actionStatus PathFinderAction::Action() { - Robot::GetInstance()->m_driveSubsystem.auton(); - m_autonomousCommand = Robot::GetInstance()->m_container.GetAutonomousCommand(m_path); + Robot::GetInstance()->driveSubsystem.auton(); + m_autonomousCommand = Robot::GetInstance()->robotContainer.GetAutonomousCommand(m_path); if (m_autonomousCommand != nullptr) { m_autonomousCommand->Schedule(); } diff --git a/src/Autonomous/Auton.h b/src/Autonomous/Auton.h new file mode 100644 index 0000000..3b2980d --- /dev/null +++ b/src/Autonomous/Auton.h @@ -0,0 +1,17 @@ +#pragma once + +#include +#include +#include + +using namespace CORE; +using namespace std; + +class Autonomous: public COREAuton { +public: + Autonomous(); + void AddNodes() override; +private: + Node * m_drivePath; + Node * m_secondDrivePath; +}; \ No newline at end of file diff --git a/src/ClimberSubsystem.cpp b/src/ClimberSubsystem.cpp index ad05a44..5d45fc9 100644 --- a/src/ClimberSubsystem.cpp +++ b/src/ClimberSubsystem.cpp @@ -6,7 +6,7 @@ ClimberSubsystem::ClimberSubsystem() : } void ClimberSubsystem::robotInit() { - driverJoystick->RegisterButton(CORE::COREJoystick::Y_BUTTON); + } void ClimberSubsystem::teleopInit() { diff --git a/src/ClimberSubsystem.h b/src/ClimberSubsystem.h index 346e23d..b64c52e 100644 --- a/src/ClimberSubsystem.h +++ b/src/ClimberSubsystem.h @@ -1,13 +1,14 @@ -// #pragma once +#pragma once #include #include #include "Config.h" +#include using namespace CORE; using namespace frc; -class ClimberSubsystem : public CORESubsystem { +class ClimberSubsystem : public CORESubsystem, public frc2::SubsystemBase { public: ClimberSubsystem(); void robotInit() override; diff --git a/src/Constants.h b/src/Constants.h index b110919..ef7a716 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -1,9 +1,11 @@ +#pragma once + #include #include #include #include // All of these values should be updated according to what works with the characterization tool -#pragma once + namespace DriveConstants { constexpr auto kTrackwidth = 0.69_m; // Not sure if this is correct or if we need to manually measure diff --git a/src/ConveyorSubsystem.cpp b/src/ConveyorSubsystem.cpp index 517e5b1..57f5397 100644 --- a/src/ConveyorSubsystem.cpp +++ b/src/ConveyorSubsystem.cpp @@ -16,18 +16,12 @@ void ConveyorSubsystem::robotInit(){ m_backConveyorMotor.Set(ControlMode::PercentOutput, 0); m_lowerConveyorMotor.SetInverted(true); m_frontConveyorMotor.SetInverted(false); - - /* Registers Controls */ - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_BUTTON); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::LEFT_TRIGGER); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::LEFT_BUTTON); } void ConveyorSubsystem::teleopInit() {} void ConveyorSubsystem::teleop(){ - + cout<<"Conveyer teleop"<GetButton(CORE::COREJoystick::JoystickButton::LEFT_TRIGGER)) { setLowerMotor(lowerConveyorSpeed.Get()); } else if(operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::LEFT_BUTTON)) { diff --git a/src/ConveyorSubsystem.h b/src/ConveyorSubsystem.h index aecb2ec..fa1421a 100644 --- a/src/ConveyorSubsystem.h +++ b/src/ConveyorSubsystem.h @@ -1,10 +1,11 @@ -// #pragma once +#pragma once #include #include #include "Config.h" +#include -class ConveyorSubsystem : public CORESubsystem { +class ConveyorSubsystem : public CORESubsystem, public frc2::SubsystemBase { public: ConveyorSubsystem(); void robotInit() override; diff --git a/src/DriveSubsystem.cpp b/src/DriveSubsystem.cpp index 7b991e1..e26c42c 100644 --- a/src/DriveSubsystem.cpp +++ b/src/DriveSubsystem.cpp @@ -17,13 +17,9 @@ DriveSubsystem::DriveSubsystem() : } void DriveSubsystem::robotInit() { - cout << "Drive Subsystem" << endl; - cout << "joysticks are being registered" << endl; // Registers joystick axis and buttons, does inital setup for talons - driverJoystick->RegisterAxis(CORE::COREJoystick::LEFT_STICK_Y); - driverJoystick->RegisterAxis(CORE::COREJoystick::RIGHT_STICK_X); - driverJoystick->RegisterButton(CORE::COREJoystick::RIGHT_TRIGGER); initTalons(); + m_drive.SetSafetyEnabled(false); } void DriveSubsystem::teleopInit() { @@ -61,10 +57,6 @@ void DriveSubsystem::teleop() { SmartDashboard::PutNumber("Left side encoder", m_leftMaster.GetSelectedSensorPosition(0)); SmartDashboard::PutNumber("Right side encoder", m_rightMaster.GetSelectedSensorPosition(0)); SmartDashboard::PutNumber("Gyro angle", m_gyro->GetAngle()); - - if(driverJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)) { - toggleGear(); - } fillCompressor(); } diff --git a/src/IntakeSubsystem.cpp b/src/IntakeSubsystem.cpp index 3461f36..669a86a 100644 --- a/src/IntakeSubsystem.cpp +++ b/src/IntakeSubsystem.cpp @@ -8,8 +8,6 @@ IntakeSubsystem::IntakeSubsystem() : void IntakeSubsystem::robotInit(){ m_intakeMotor.Set(ControlMode::PercentOutput, 0); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::RIGHT_BUTTON); m_isIntakeDown = false; m_intakeMotor.SetInverted(true); } @@ -17,6 +15,7 @@ void IntakeSubsystem::robotInit(){ void IntakeSubsystem::teleopInit() {} void IntakeSubsystem::teleop(){ + cout<<"Intake teleop"<GetButton(CORE::COREJoystick::JoystickButton::RIGHT_TRIGGER)){ SetIntake(-intakeSpeed.Get()); } diff --git a/src/IntakeSubsystem.h b/src/IntakeSubsystem.h index f0e28fc..a43601b 100644 --- a/src/IntakeSubsystem.h +++ b/src/IntakeSubsystem.h @@ -4,10 +4,11 @@ #include #include #include "Config.h" +#include using namespace CORE; -class IntakeSubsystem : public CORESubsystem { +class IntakeSubsystem : public CORESubsystem, public frc2::SubsystemBase { public: IntakeSubsystem(); void robotInit() override; diff --git a/src/LauncherSubsystem.cpp b/src/LauncherSubsystem.cpp index 5140b83..7a57b58 100644 --- a/src/LauncherSubsystem.cpp +++ b/src/LauncherSubsystem.cpp @@ -1,6 +1,6 @@ #include "LauncherSubsystem.h" -// using namespace CORE; +using namespace CORE; LauncherSubsystem::LauncherSubsystem() : m_launcherMotor(BOTTOM_LAUNCHER_MOTOR_PORT), @@ -8,13 +8,14 @@ LauncherSubsystem::LauncherSubsystem() : } void LauncherSubsystem::robotInit() { - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::B_BUTTON); + } void LauncherSubsystem::teleopInit() { m_launcherOn = false; } + void LauncherSubsystem::teleop() { if (!m_launcherOn && operatorJoystick->GetRisingEdge(CORE::COREJoystick::JoystickButton::B_BUTTON)) { m_launcherOn = true; diff --git a/src/LauncherSubsystem.h b/src/LauncherSubsystem.h index d5e46d2..8e9ecde 100644 --- a/src/LauncherSubsystem.h +++ b/src/LauncherSubsystem.h @@ -1,13 +1,15 @@ -// #pragma once +#pragma once #include #include #include #include "Config.h" +#include +#include // using namespace frc; -class LauncherSubsystem : public CORESubsystem { +class LauncherSubsystem : public CORESubsystem, public frc2::SubsystemBase { public: LauncherSubsystem(); void robotInit() override; @@ -17,5 +19,5 @@ class LauncherSubsystem : public CORESubsystem { private: TalonSRX m_launcherMotor; bool m_launcherOn; - COREConstant m_launcherSpeed; + COREConstant m_launcherSpeed; }; diff --git a/src/Robot.cpp b/src/Robot.cpp index 0147e62..f6cc749 100644 --- a/src/Robot.cpp +++ b/src/Robot.cpp @@ -26,8 +26,6 @@ void Robot::RobotPeriodic() { } void Robot::TeleopPeriodic() { - std::cout << "running teleop periodic" << endl; - m_driveSubsystem.teleop(); } void Robot::teleopInit() {} @@ -35,8 +33,7 @@ void Robot::teleopInit() {} void Robot::test() {} void Robot::teleop() { - std::cout << "running teleop" << endl; - m_driveSubsystem.teleop(); + cout<<"RobotTeleop"< @@ -15,6 +14,12 @@ #include "Constants.h" #include "DriveSubsystem.h" +#include "ClimberSubsystem.h" +#include "ConveyorSubsystem.h" +#include "DriveSubsystem.h" +#include "IntakeSubsystem.h" +#include "LauncherSubsystem.h" +#include "TurretSubsystem.h" #include "CORERobotLib.h" using namespace CORE; @@ -31,7 +36,11 @@ class RobotContainer { // The robot's subsystems DriveSubsystem m_drive; - + IntakeSubsystem m_intake; + TurretSubsystem m_turret; + ConveyorSubsystem m_conveyor; + ClimberSubsystem m_climber; + LauncherSubsystem m_launcher; // The chooser for the autonomous routines frc::SendableChooser m_chooser; }; diff --git a/src/TurretSubsystem.cpp b/src/TurretSubsystem.cpp index 2e4d5d1..6dc700b 100644 --- a/src/TurretSubsystem.cpp +++ b/src/TurretSubsystem.cpp @@ -13,8 +13,6 @@ TurretSubsystem::TurretSubsystem(): m_turret(TURRET_PORT), void TurretSubsystem::robotInit() { m_startupTurretPosition = m_turret.GetSelectedSensorPosition(0); - operatorJoystick->RegisterButton(CORE::COREJoystick::JoystickButton::A_BUTTON); - operatorJoystick->RegisterAxis(CORE::COREJoystick::LEFT_STICK_X); InitTalons(); // start NetworkTables ntinst = nt::NetworkTableInstance::GetDefault(); @@ -26,6 +24,7 @@ void TurretSubsystem::teleopInit() { } void TurretSubsystem::teleop() { + cout<<"Turret teleop"<GetAxis(CORE::COREJoystick::JoystickAxis::LEFT_STICK_X); bool aButtonPressed = operatorJoystick->GetButton(CORE::COREJoystick::JoystickButton::A_BUTTON); m_motorPercent = 0; diff --git a/src/TurretSubsystem.h b/src/TurretSubsystem.h index 41137b3..0f814e1 100644 --- a/src/TurretSubsystem.h +++ b/src/TurretSubsystem.h @@ -1,4 +1,4 @@ -// #pragma once +#pragma once #include #include @@ -7,11 +7,12 @@ #include #include "Config.h" #include +#include using namespace CORE; using namespace frc; -class TurretSubsystem : public CORESubsystem { +class TurretSubsystem : public CORESubsystem, public frc2::SubsystemBase { private: TalonSRX m_turret; double m_startupTurretPosition, m_motorPercent; From 0a6ddeb9ed50ff06b5c340baee3ea31fb14fa4eb Mon Sep 17 00:00:00 2001 From: Aidan Lincicum Date: Thu, 17 Dec 2020 17:44:23 -0600 Subject: [PATCH 31/31] Changed the constants to the 2020 comp bot --- robotconfig.py | 47 +++++++++++++++++++++++++++++++++++++++++++++++ src/Constants.h | 13 +++++++------ 2 files changed, 54 insertions(+), 6 deletions(-) create mode 100644 robotconfig.py diff --git a/robotconfig.py b/robotconfig.py new file mode 100644 index 0000000..b648021 --- /dev/null +++ b/robotconfig.py @@ -0,0 +1,47 @@ +{ + # Class names of motor controllers used. + # Options: + # 'WPI_TalonSRX' + # 'WPI_TalonFX' (for Falcon 500 motors) + # 'WPI_VictorSPX' + # Note: The first motor on each side should always be a Talon SRX/FX, as the + # VictorSPX does not support encoder connections + "rightControllerTypes": ["WPI_TalonSRX", "WPI_TalonSRX"], + "leftControllerTypes": ["WPI_TalonSRX", "WPI_TalonSRX"], + # Note: The first id in the list of ports should be the one with an encoder + # Ports for the left-side motors + "leftMotorPorts": [19, 32], + # Ports for the right-side motors + "rightMotorPorts": [20, 14], + # Inversions for the left-side motors + "leftMotorsInverted": [False, False], + # Inversions for the right side motors + "rightMotorsInverted": [False, False], + # Wheel diameter (in units of your choice - will dictate units of analysis) + "wheelDiameter": 6, + # If your robot has only one encoder, set all right encoder fields to `None` + # Encoder edges-per-revolution (*NOT* cycles per revolution!) + # This value should be the edges per revolution *of the wheels*, and so + # should take into account gearing between the encoder and the wheels + "encoderEPR": 1024, + # Whether the left encoder is inverted + "leftEncoderInverted": False, + # Whether the right encoder is inverted: + "rightEncoderInverted": False, + # Your gyro type (one of "NavX", "Pigeon", "ADXRS450", "AnalogGyro", or "None") + "gyroType": "NavX", + # Whatever you put into the constructor of your gyro + # Could be: + # "SPI.Port.kMXP" (MXP SPI port for NavX or ADXRS450), + # "SerialPort.Port.kMXP" (MXP Serial port for NavX), + # "I2C.Port.kOnboard" (Onboard I2C port for NavX), + # "0" (Pigeon CAN ID or AnalogGyro channel), + # "new WPI_TalonSRX(3)" (Pigeon on a Talon SRX), + # "leftSlave" (Pigeon on the left slave Talon SRX/FX), + # "" (NavX using default SPI, ADXRS450 using onboard CS0, or no gyro) + "gyroPort": "SerialPort.Port.kMXP", +} + + + + diff --git a/src/Constants.h b/src/Constants.h index ef7a716..8643984 100644 --- a/src/Constants.h +++ b/src/Constants.h @@ -8,20 +8,21 @@ namespace DriveConstants { -constexpr auto kTrackwidth = 0.69_m; // Not sure if this is correct or if we need to manually measure +constexpr auto kTrackwidth = 6545.5767404345215_m; // Not sure if this is correct or if we need to manually measure extern const frc::DifferentialDriveKinematics kDriveKinematics; -constexpr int kEncoderCPR = 1024; +constexpr int kEncoderCPR = 2048; +constexpr double kGearReduction = 15; constexpr double kWheelDiameterInches = 6; constexpr double kEncoderDistancePerPulse = // Assumes the encoders are directly mounted on the wheel shafts - (kWheelDiameterInches * wpi::math::pi) / static_cast(kEncoderCPR); + (kWheelDiameterInches * wpi::math::pi) / (static_cast(kEncoderCPR) * kGearReduction); constexpr bool kGyroReversed = true; -constexpr auto ks = 3.14_V; -constexpr auto kv = 0.146 * 1_V * 1_s / 1_m; -constexpr auto ka = 0.193 * 1_V * 1_s * 1_s / 1_m; +constexpr auto ks = 0.191_V; +constexpr auto kv = 0.000377 * 1_V * 1_s / 1_m; +constexpr auto ka = 2.67e-5 * 1_V * 1_s * 1_s / 1_m; // Example value only - as above, this must be tuned for your drive! constexpr double kPDriveVel = 8.5;